diff --git a/.github/contributing.md b/.github/contributing.md
index ad67718ee..6bc7b5a00 100644
--- a/.github/contributing.md
+++ b/.github/contributing.md
@@ -92,7 +92,7 @@ Before creating a suggestion, please check [this list](#before-submitting-a-sugg
#### Before Submitting a Feature Request
-* **Check the [Marlin website](http://marlinfw.org/)** for tips — you might discover that the feature is already included. Most importantly, check if you're using [the latest version of Marlin](https://github.com/MarlinFirmware/Marlin/releases) and if you can get the desired behavior by changing [Marlin's config settings](http://marlinfw.org/docs/configuration/configuration.html).
+* **Check the [Marlin website](https://marlinfw.org/)** for tips — you might discover that the feature is already included. Most importantly, check if you're using [the latest version of Marlin](https://github.com/MarlinFirmware/Marlin/releases) and if you can get the desired behavior by changing [Marlin's config settings](https://marlinfw.org/docs/configuration/configuration.html).
* **Perform a [cursory search](https://github.com/MarlinFirmware/Marlin/issues?q=is%3Aissue)** to see if the enhancement has already been suggested. If it has, add a comment to the existing issue instead of opening a new one.
#### How Do I Submit A (Good) Feature Request?
@@ -116,12 +116,12 @@ Unsure where to begin contributing to Marlin? You can start by looking through t
### Pull Requests
-Pull Requests should always be targeted to working branches (e.g., `bugfix-1.1.x` and/or `bugfix-2.0.x`) and never to release branches (e.g., `1.1.x`). If this is your first Pull Request, please read our [Guide to Pull Requests](http://marlinfw.org/docs/development/getting_started_pull_requests.html) and Github's [Pull Request](https://help.github.com/articles/creating-a-pull-request/) documentation.
+Pull Requests should always be targeted to working branches (e.g., `bugfix-1.1.x` and/or `bugfix-2.0.x`) and never to release branches (e.g., `1.1.x`). If this is your first Pull Request, please read our [Guide to Pull Requests](https://marlinfw.org/docs/development/getting_started_pull_requests.html) and Github's [Pull Request](https://help.github.com/articles/creating-a-pull-request/) documentation.
* Fill in [the required template](pull_request_template.md).
* Don't include issue numbers in the PR title.
* Include pictures, diagrams, and links to videos in your Pull Request to demonstrate your changes, if needed.
-* Follow the [Coding Standards](http://marlinfw.org/docs/development/coding_standards.html) posted on our website.
+* Follow the [Coding Standards](https://marlinfw.org/docs/development/coding_standards.html) posted on our website.
* Document new code with clear and concise comments.
* End all files with a newline.
@@ -136,7 +136,7 @@ Pull Requests should always be targeted to working branches (e.g., `bugfix-1.1.x
### C++ Coding Standards
-* Please read and follow the [Coding Standards](http://marlinfw.org/docs/development/coding_standards.html) posted on our website. Failure to follow these guidelines will delay evaluation and acceptance of Pull Requests.
+* Please read and follow the [Coding Standards](https://marlinfw.org/docs/development/coding_standards.html) posted on our website. Failure to follow these guidelines will delay evaluation and acceptance of Pull Requests.
### Documentation
diff --git a/.github/issue_template.md b/.github/issue_template.md
index f45bd71d0..a211ca5e2 100644
--- a/.github/issue_template.md
+++ b/.github/issue_template.md
@@ -1,16 +1,11 @@
# NO SUPPORT REQUESTS PLEASE
-Support Requests posted here will be automatically closed!
+Do you want to ask a question? Are you looking for support? Please don't post here. Support Requests posted here will be automatically closed!
-This Issue Queue is for Marlin bug reports and development-related issues, and we prefer not to handle user-support questions here. See https://github.com/MarlinFirmware/Marlin/blob/1.1.x/.github/contributing.md#i-dont-want-to-read-this-whole-thing-i-just-have-a-question.
+Instead use one of the following options:
-For best results getting help with configuration and troubleshooting, please use the following resources:
+- The Marlin Firmware forum at https://reprap.org/forum/list.php?415
+- The MarlinFirmware Facebook Group at https://www.facebook.com/groups/1049718498464482/
+- The MarlinFirmware Discord Server at https://discord.gg/n5NJ59y.
-- RepRap.org Marlin Forum http://forums.reprap.org/list.php?415
-- Tom's 3D Forums https://discuss.toms3d.org/
-- Facebook Group "Marlin Firmware" https://www.facebook.com/groups/1049718498464482/
-- Facebook Group "Marlin Firmware for 3D Printers" https://www.facebook.com/groups/3Dtechtalk/
-- Marlin Configuration https://www.youtube.com/results?search_query=marlin+configuration on YouTube
-- Marlin Discord server. Join link: https://discord.gg/n5NJ59y
-
-After seeking help from the community, if the consensus points to to a bug in Marlin, then you should post a Bug Report at https://github.com/MarlinFirmware/Marlin/issues/new/choose).
+Before filing an issue be sure to test the latest "bugfix" branch to see whether the issue is already addressed.
diff --git a/.github/lock.yml b/.github/lock.yml
new file mode 100644
index 000000000..c5ceff66b
--- /dev/null
+++ b/.github/lock.yml
@@ -0,0 +1,40 @@
+#
+# Configuration for Lock Threads - https://github.com/dessant/lock-threads-app
+#
+
+# Number of days of inactivity before a closed issue or pull request is locked
+daysUntilLock: 60
+
+# Skip issues and pull requests created before a given timestamp. Timestamp must
+# follow ISO 8601 (`YYYY-MM-DD`). Set to `false` to disable
+skipCreatedBefore: false
+
+# Issues and pull requests with these labels will be ignored. Set to `[]` to disable
+exemptLabels: [ 'no-locking' ]
+
+# Label to add before locking, such as `outdated`. Set to `false` to disable
+lockLabel: false
+
+# Comment to post before locking. Set to `false` to disable
+lockComment: >
+ This thread has been automatically locked since there has not been
+ any recent activity after it was closed. Please open a new issue for
+ related bugs.
+
+# Assign `resolved` as the reason for locking. Set to `false` to disable
+setLockReason: true
+
+# Limit to only `issues` or `pulls`
+# only: issues
+
+# Optionally, specify configuration settings just for `issues` or `pulls`
+# issues:
+# exemptLabels:
+# - help-wanted
+# lockLabel: outdated
+
+# pulls:
+# daysUntilLock: 30
+
+# Repository to extend settings from
+# _extends: repo
diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml
index 54c0de98e..4dd483499 100644
--- a/.github/workflows/test-builds.yml
+++ b/.github/workflows/test-builds.yml
@@ -58,14 +58,25 @@ jobs:
- STM32F103RE_btt
- STM32F103RE_btt_USB
- STM32F103RC_fysetc
+ - STM32F103RC_meeb
- jgaurora_a5s_a1
- STM32F103VE_longer
- STM32F407VE_black
+ - STM32F401VE_STEVAL
+ - BIGTREE_BTT002
- BIGTREE_SKR_PRO
- BIGTREE_GTR_V1_0
- mks_robin
- ARMED
- FYSETC_S6
+ - STM32F070RB_malyan
+ - malyan_M300
+ - mks_robin_lite
+ - FLYF407ZG
+ - rumba32
+ - mks_robin_pro
+ - STM32F103RET6_creality
+ - LERDGEX
# Put lengthy tests last
@@ -78,12 +89,9 @@ jobs:
#- STM32F7
# Non-working environment tests
-
- #- BIGTREE_BTT002
#- at90usb1286_cdc
#- at90usb1286_dfu
#- STM32F103CB_malyan
- #- mks_robin_lite
#- mks_robin_mini
#- mks_robin_nano
@@ -97,7 +105,7 @@ jobs:
- name: Install PlatformIO
run: |
- pip install -U https://github.com/platformio/platformio-core/archive/master.zip
+ pip install -U https://github.com/platformio/platformio-core/archive/develop.zip
platformio update
- name: Check out the PR
@@ -106,8 +114,7 @@ jobs:
- name: Run ${{ matrix.test-platform }} Tests
run: |
# Inline tests script
- [[ "$GITHUB_REPOSITORY" == "MarlinFirmware/Marlin" ]] || exit 0
chmod +x buildroot/bin/*
- chmod +x buildroot/share/tests/*
- export PATH=./buildroot/bin/:./buildroot/share/tests/:${PATH}
+ chmod +x buildroot/tests/*
+ export PATH=./buildroot/bin/:./buildroot/tests/:${PATH}
run_tests . ${{ matrix.test-platform }}
diff --git a/.gitignore b/.gitignore
index 80c76ee1e..c163d339d 100755
--- a/.gitignore
+++ b/.gitignore
@@ -16,7 +16,7 @@
# GNU General Public License for more details.
#
# You should have received a copy of the GNU General Public License
-# along with this program. If not, see .
+# along with this program. If not, see .
#
# Our automatic versioning scheme generates the following file
diff --git a/LICENSE b/LICENSE
index 7d917cf3d..4ad6d9b1e 100644
--- a/LICENSE
+++ b/LICENSE
@@ -3,7 +3,7 @@
GNU GENERAL PUBLIC LICENSE
Version 3, 29 June 2007
- Copyright (c) 2007 Free Software Foundation, Inc.
+ Copyright (c) 2007 Free Software Foundation, Inc.
Everyone is permitted to copy and distribute verbatim copies
of this license document, but changing it is not allowed.
@@ -647,7 +647,7 @@ the "copyright" line and a pointer to where the full notice is found.
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
- along with this program. If not, see .
+ along with this program. If not, see .
Also add information on how to contact you by electronic and paper mail.
@@ -666,12 +666,12 @@ might be different; for a GUI interface, you would use an "about box".
You should also get your employer (if you work as a programmer) or school,
if any, to sign a "copyright disclaimer" for the program, if necessary.
For more information on this, and how to apply and follow the GNU GPL, see
-.
+.
The GNU General Public License does not permit incorporating your program
into proprietary programs. If your program is a subroutine library, you
may consider it more useful to permit linking proprietary applications with
the library. If this is what you want to do, use the GNU Lesser General
Public License instead of this License. But first, please read
-.
+.
diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h
index 2efe284ac..a01571c42 100644
--- a/Marlin/Configuration.h
+++ b/Marlin/Configuration.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -36,7 +36,7 @@
* Advanced settings can be found in Configuration_adv.h
*
*/
-#define CONFIGURATION_H_VERSION 020005
+#define CONFIGURATION_H_VERSION 020006
//===========================================================================
//============================= Getting Started =============================
@@ -45,13 +45,13 @@
/**
* Here are some standard links for getting your machine calibrated:
*
- * http://reprap.org/wiki/Calibration
- * http://youtu.be/wAL9d7FgInk
+ * https://reprap.org/wiki/Calibration
+ * https://youtu.be/wAL9d7FgInk
* http://calculator.josefprusa.cz
- * http://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide
- * http://www.thingiverse.com/thing:5573
+ * https://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide
+ * https://www.thingiverse.com/thing:5573
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
- * http://www.thingiverse.com/thing:298812
+ * https://www.thingiverse.com/thing:298812
*/
//===========================================================================
@@ -135,21 +135,28 @@
//#define CUSTOM_MACHINE_NAME "3D Printer"
// Printer's unique ID, used by some programs to differentiate between machines.
-// Choose your own or use a service like http://www.uuidgenerator.net/version4
+// Choose your own or use a service like https://www.uuidgenerator.net/version4
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// @section extruder
// This defines the number of extruders
-// :[1, 2, 3, 4, 5, 6, 7, 8]
+// :[0, 1, 2, 3, 4, 5, 6, 7, 8]
#define EXTRUDERS 1
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
-#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
+#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
+// Save and restore temperature and fan speed on tool-change.
+// Set standby for the unselected tool with M104/106/109 T...
+#if ENABLED(SINGLENOZZLE)
+ //#define SINGLENOZZLE_STANDBY_TEMP
+ //#define SINGLENOZZLE_STANDBY_FAN
+#endif
+
/**
* Průša MK2 Single Nozzle Multi-Material Multiplexer, and variants.
*
@@ -326,7 +333,7 @@
#define PSU_ACTIVE_HIGH false // Set 'false' for ATX, 'true' for X-Box
//#define PSU_DEFAULT_OFF // Keep power off until enabled directly with M80
- //#define PSU_POWERUP_DELAY 100 // (ms) Delay for the PSU to warm up to full power
+ //#define PSU_POWERUP_DELAY 250 // (ms) Delay for the PSU to warm up to full power
//#define AUTO_POWER_CONTROL // Enable automatic control of the PS_ON pin
#if ENABLED(AUTO_POWER_CONTROL)
@@ -364,8 +371,9 @@
* 202 : 200k thermistor - Copymaster 3D
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
- * 5 : 100K thermistor - ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan & J-Head) (4.7k pullup)
+ * 5 : 100K thermistor - ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan, J-Head, and E3D) (4.7k pullup)
* 501 : 100K Zonestar (Tronxy X3A) Thermistor
+ * 502 : 100K Zonestar Thermistor used by hot bed in Zonestar Prusa P802M
* 512 : 100k RPW-Ultra hotend thermistor (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
@@ -373,13 +381,15 @@
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
- * 11 : 100k beta 3950 1% thermistor (4.7k pullup)
+ * 11 : 100k beta 3950 1% thermistor (Used in Keenovo AC silicone mats and most Wanhao i3 machines) (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 15 : 100k thermistor calibration for JGAurora A5 hotend
* 18 : ATC Semitec 204GT-2 (4.7k pullup) Dagoma.Fr - MKS_Base_DKU001327
* 20 : Pt100 with circuit in the Ultimainboard V2.x with 5v excitation (AVR)
* 21 : Pt100 with circuit in the Ultimainboard V2.x with 3.3v excitation (STM32 \ LPC176x....)
+ * 22 : 100k (hotend) with 4.7k pullup to 3.3V and 220R to analog input (as in GTM32 Pro vB)
+ * 23 : 100k (bed) with 4.7k pullup to 3.3v and 220R to analog input (as in GTM32 Pro vB)
* 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
@@ -395,7 +405,7 @@
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
- * 1047 : Pt1000 with 4k7 pullup
+ * 1047 : Pt1000 with 4k7 pullup (E3D)
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
@@ -470,16 +480,12 @@
#define BANG_MAX 255 // Limits current to nozzle while in bang-bang mode; 255=full current
#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#define PID_K1 0.95 // Smoothing factor within any PID loop
+
#if ENABLED(PIDTEMP)
//#define PID_EDIT_MENU // Add PID editing to the "Advanced Settings" menu. (~700 bytes of PROGMEM)
//#define PID_AUTOTUNE_MENU // Add PID auto-tuning to the "Advanced Settings" menu. (~250 bytes of PROGMEM)
- //#define PID_DEBUG // Sends debug data to the serial port. Use 'M303 D' to toggle activation.
- //#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
- //#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay
//#define PID_PARAMS_PER_HOTEND // Uses separate PID parameters for each extruder (useful for mismatched extruders)
// Set/get with gcode: M301 E[extruder number, 0-2]
- #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
- // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
@@ -548,6 +554,14 @@
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
#endif // PIDTEMPBED
+#if EITHER(PIDTEMP, PIDTEMPBED)
+ //#define PID_DEBUG // Sends debug data to the serial port. Use 'M303 D' to toggle activation.
+ //#define PID_OPENLOOP // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
+ //#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay
+ #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
+ // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
+#endif
+
// @section extruder
/**
@@ -697,7 +711,7 @@
* Enable if your probe or endstops falsely trigger due to noise.
*
* - Higher values may affect repeatability or accuracy of some bed probes.
- * - To fix noise install a 100nF ceramic capacitor inline with the switch.
+ * - To fix noise install a 100nF ceramic capacitor in parallel with the switch.
* - This feature is not required for common micro-switches mounted on PCBs
* based on the Makerbot design, which already have the 100nF capacitor.
*
@@ -705,6 +719,9 @@
*/
//#define ENDSTOP_NOISE_THRESHOLD 2
+// Check for stuck or disconnected endstops during homing moves.
+//#define DETECT_BROKEN_ENDSTOP
+
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
@@ -798,10 +815,12 @@
*
* See:
* https://reprap.org/forum/read.php?1,739819
- * http://blog.kyneticcnc.com/2018/10/computing-junction-deviation-for-marlin.html
+ * https://blog.kyneticcnc.com/2018/10/computing-junction-deviation-for-marlin.html
*/
#if DISABLED(CLASSIC_JERK)
#define JUNCTION_DEVIATION_MM 0.013 // (mm) Distance from real junction edge
+ #define JD_HANDLE_SMALL_SEGMENTS // Use curvature estimation instead of just the junction angle
+ // for small segments (< 1mm) with large junction angles (> 135°).
#endif
/**
@@ -820,16 +839,19 @@
// @section probes
//
-// See http://marlinfw.org/docs/configuration/probes.html
+// See https://marlinfw.org/docs/configuration/probes.html
//
/**
- * Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
- *
- * Enable this option for a probe connected to the Z Min endstop pin.
+ * Enable this option for a probe connected to the Z-MIN pin.
+ * The probe replaces the Z-MIN endstop and is used for Z homing.
+ * (Automatically enables USE_PROBE_FOR_Z_HOMING.)
*/
#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
+// Force the use of the probe for Z-axis homing
+//#define USE_PROBE_FOR_Z_HOMING
+
/**
* Z_MIN_PROBE_PIN
*
@@ -886,6 +908,11 @@
*/
//#define BLTOUCH
+/**
+ * Pressure sensor with a BLTouch-like interface
+ */
+//#define CREALITY_TOUCH
+
/**
* Touch-MI Probe by hotends.fr
*
@@ -960,7 +987,7 @@
// Most probes should stay away from the edges of the bed, but
// with NOZZLE_AS_PROBE this can be negative for a wider probing area.
-#define MIN_PROBE_EDGE 10
+#define PROBING_MARGIN 10
// X and Y axis travel speed (mm/m) between probes
#define XY_PROBE_SPEED 8000
@@ -1138,12 +1165,11 @@
*
* RAMPS-based boards use SERVO3_PIN for the first runout sensor.
* For other boards you may need to define FIL_RUNOUT_PIN, FIL_RUNOUT2_PIN, etc.
- * By default the firmware assumes HIGH=FILAMENT PRESENT.
*/
//#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define NUM_RUNOUT_SENSORS 1 // Number of sensors, up to one per extruder. Define a FIL_RUNOUT#_PIN for each.
- #define FIL_RUNOUT_INVERTING false // Set to true to invert the logic of the sensor.
+ #define FIL_RUNOUT_STATE LOW // Pin state indicating that filament is NOT present.
#define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
@@ -1335,7 +1361,6 @@
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
-
// @section homing
// The center of the bed is at (X=0, Y=0)
@@ -1353,14 +1378,14 @@
//
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
// - If stepper drivers time out, it will need X and Y homing again before Z homing.
-// - Move the Z probe (or nozzle) to a defined XY point before Z Homing when homing all axes (G28).
+// - Move the Z probe (or nozzle) to a defined XY point before Z Homing.
// - Prevent Z homing when the Z probe is outside bed area.
//
//#define Z_SAFE_HOMING
#if ENABLED(Z_SAFE_HOMING)
- #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
- #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
+ #define Z_SAFE_HOMING_X_POINT X_CENTER // X point for Z homing
+ #define Z_SAFE_HOMING_Y_POINT Y_CENTER // Y point for Z homing
#endif
// Homing speeds (mm/m)
@@ -1499,8 +1524,11 @@
#if ENABLED(NOZZLE_PARK_FEATURE)
// Specify a park position as { X, Y, Z_raise }
#define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
+ //#define NOZZLE_PARK_X_ONLY // X move only is required to park
+ //#define NOZZLE_PARK_Y_ONLY // Y move only is required to park
+ #define NOZZLE_PARK_Z_RAISE_MIN 2 // (mm) Always raise Z by at least this distance
#define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis)
- #define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
+ #define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers)
#endif
/**
@@ -1567,6 +1595,10 @@
// Enable for a purge/clean station that's always at the gantry height (thus no Z move)
//#define NOZZLE_CLEAN_NO_Z
+
+ // Explicit wipe G-code script applies to a G12 with no arguments.
+ //#define WIPE_SEQUENCE_COMMANDS "G1 X-17 Y25 Z10 F4000\nG1 Z1\nM114\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 Z15\nM400\nG0 X-10.0 Y-9.0"
+
#endif
/**
@@ -1611,10 +1643,10 @@
*
* Select the language to display on the LCD. These languages are available:
*
- * en, an, bg, ca, cz, da, de, el, el_gr, es, eu, fi, fr, gl, hr, it, jp_kana,
- * ko_KR, nl, pl, pt, pt_br, ru, sk, tr, uk, vi, zh_CN, zh_TW, test
+ * en, an, bg, ca, cz, da, de, el, el_gr, es, eu, fi, fr, gl, hr, hu, it,
+ * jp_kana, ko_KR, nl, pl, pt, pt_br, ro ru, sk, tr, uk, vi, zh_CN, zh_TW, test
*
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cz':'Czech', 'da':'Danish', 'de':'German', 'el':'Greek', 'el_gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'jp_kana':'Japanese', 'ko_KR':'Korean (South Korea)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt_br':'Portuguese (Brazilian)', 'ru':'Russian', 'sk':'Slovak', 'tr':'Turkish', 'uk':'Ukrainian', 'vi':'Vietnamese', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Traditional)', 'test':'TEST' }
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cz':'Czech', 'da':'Danish', 'de':'German', 'el':'Greek', 'el_gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'hu':'Hungarian', 'it':'Italian', 'jp_kana':'Japanese', 'ko_KR':'Korean (South Korea)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt_br':'Portuguese (Brazilian)', 'ro':'Romanian', 'ru':'Russian', 'sk':'Slovak', 'tr':'Turkish', 'uk':'Ukrainian', 'vi':'Vietnamese', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Traditional)', 'test':'TEST' }
*/
#define LCD_LANGUAGE en
@@ -1636,7 +1668,7 @@
* - Click the controller to view the LCD menu
* - The LCD will display Japanese, Western, or Cyrillic text
*
- * See http://marlinfw.org/docs/development/lcd_language.html
+ * See https://marlinfw.org/docs/development/lcd_language.html
*
* :['JAPANESE', 'WESTERN', 'CYRILLIC']
*/
@@ -1763,7 +1795,7 @@
//
// RepRapDiscount Smart Controller.
-// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
+// https://reprap.org/wiki/RepRapDiscount_Smart_Controller
//
// Note: Usually sold with a white PCB.
//
@@ -1787,13 +1819,13 @@
//
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
-// http://reprap.org/wiki/PanelOne
+// https://reprap.org/wiki/PanelOne
//
//#define PANEL_ONE
//
// GADGETS3D G3D LCD/SD Controller
-// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel
+// https://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel
//
// Note: Usually sold with a blue PCB.
//
@@ -1880,7 +1912,7 @@
//
// 2-wire Non-latching LCD SR from https://goo.gl/aJJ4sH
-// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
+// LCD configuration: https://reprap.org/wiki/SAV_3D_LCD
//
//#define SAV_3DLCD
@@ -1902,10 +1934,12 @@
// IMPORTANT: The U8glib library is required for Graphical Display!
// https://github.com/olikraus/U8glib_Arduino
//
+// NOTE: If the LCD is unresponsive you may need to reverse the plugs.
+//
//
// RepRapDiscount FULL GRAPHIC Smart Controller
-// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
+// https://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
//
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
@@ -1918,20 +1952,20 @@
//
// Activate one of these if you have a Panucatt Devices
// Viki 2.0 or mini Viki with Graphic LCD
-// http://panucatt.com
+// https://www.panucatt.com
//
//#define VIKI2
//#define miniVIKI
//
// MakerLab Mini Panel with graphic
-// controller and SD support - http://reprap.org/wiki/Mini_panel
+// controller and SD support - https://reprap.org/wiki/Mini_panel
//
//#define MINIPANEL
//
// MaKr3d Makr-Panel with graphic controller and SD support.
-// http://reprap.org/wiki/MaKr3d_MaKrPanel
+// https://reprap.org/wiki/MaKr3d_MaKrPanel
//
//#define MAKRPANEL
@@ -1970,6 +2004,12 @@
//
//#define MKS_MINI_12864
+//
+// MKS LCD12864A/B with graphic controller and SD support. Follows MKS_MINI_12864 pinout.
+// https://www.aliexpress.com/item/33018110072.html
+//
+//#define MKS_LCD12864
+
//
// FYSETC variant of the MINI12864 graphic controller with SD support
// https://wiki.fysetc.com/Mini12864_Panel/
@@ -2011,7 +2051,7 @@
//
// Silvergate GLCD controller
-// http://github.com/android444/Silvergate
+// https://github.com/android444/Silvergate
//
//#define SILVER_GATE_GLCD_CONTROLLER
@@ -2040,7 +2080,7 @@
//
// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
-// http://reprap.org/wiki/MKS_12864OLED
+// https://reprap.org/wiki/MKS_12864OLED
//
// Tiny, but very sharp OLED display
//
@@ -2057,19 +2097,26 @@
//
//#define OVERLORD_OLED
+//
+// FYSETC OLED 2.42" 128 × 64 FULL GRAPHICS CONTROLLER with WS2812 RGB
+// Where to find : https://www.aliexpress.com/item/4000345255731.html
+//#define FYSETC_242_OLED_12864 // Uses the SSD1309 controller
+
//=============================================================================
//========================== Extensible UI Displays ===========================
//=============================================================================
//
// DGUS Touch Display with DWIN OS. (Choose one.)
+// ORIGIN : https://www.aliexpress.com/item/32993409517.html
+// FYSETC : https://www.aliexpress.com/item/32961471929.html
//
//#define DGUS_LCD_UI_ORIGIN
//#define DGUS_LCD_UI_FYSETC
//#define DGUS_LCD_UI_HIPRECY
//
-// Touch-screen LCD for Malyan M200 printers
+// Touch-screen LCD for Malyan M200/M300 printers
//
//#define MALYAN_LCD
@@ -2085,19 +2132,45 @@
//
//#define EXTENSIBLE_UI
+#if ENABLED(EXTENSIBLE_UI)
+ //#define EXTUI_LOCAL_BEEPER // Enables use of local Beeper pin with external display
+#endif
+
//=============================================================================
//=============================== Graphical TFTs ==============================
//=============================================================================
//
// FSMC display (MKS Robin, Alfawise U20, JGAurora A5S, REXYZ A1, etc.)
+// Upscaled 128x64 Marlin UI
//
//#define FSMC_GRAPHICAL_TFT
+//
+// TFT LVGL UI
+//
+// Using default MKS icons and fonts from: https://git.io/JJvzK
+// Just copy the 'assets' folder from the build directory to the
+// root of your SD card, together with the compiled firmware.
+//
+//#define TFT_LVGL_UI_FSMC // Robin nano v1.2 uses FSMC
+//#define TFT_LVGL_UI_SPI // Robin nano v2.0 uses SPI
+
+//
+// Anycubic Mega TFT (AI3M)
+//
+//#define ANYCUBIC_TFT_MODEL
+//#define ANYCUBIC_TFT_DEBUG
+
//=============================================================================
//============================ Other Controllers ============================
//=============================================================================
+//
+// Ender-3 v2 OEM display. A DWIN display with Rotary Encoder.
+//
+//#define DWIN_CREALITY_LCD
+
//
// ADS7843/XPT2046 ADC Touchscreen such as ILI9341 2.8
//
@@ -2114,7 +2187,7 @@
//
// RepRapWorld REPRAPWORLD_KEYPAD v1.1
-// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
+// https://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
//
//#define REPRAPWORLD_KEYPAD
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 // (mm) Distance to move per key-press
@@ -2151,7 +2224,7 @@
// 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
+// SkeinForge sends the wrong arc G-codes when using Arc Point as fillet procedure
//#define SF_ARC_FIX
// Support for the BariCUDA Paste Extruder
@@ -2164,7 +2237,6 @@
//#define PCA9632
// Support for PCA9533 PWM LED driver
-// https://github.com/mikeshub/SailfishRGB_LED
//#define PCA9533
/**
diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h
index 00f89662c..3f097c09e 100644
--- a/Marlin/Configuration_adv.h
+++ b/Marlin/Configuration_adv.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -31,14 +31,27 @@
* Basic settings can be found in Configuration.h
*
*/
-#define CONFIGURATION_ADV_H_VERSION 020005
+#define CONFIGURATION_ADV_H_VERSION 020006
// @section temperature
//===========================================================================
-//=============================Thermal Settings ============================
+//============================= Thermal Settings ============================
//===========================================================================
+/**
+ * Thermocouple sensors are quite sensitive to noise. Any noise induced in
+ * the sensor wires, such as by stepper motor wires run in parallel to them,
+ * may result in the thermocouple sensor reporting spurious errors. This
+ * value is the number of errors which can occur in a row before the error
+ * is reported. This allows us to ignore intermittent error conditions while
+ * still detecting an actual failure, which should result in a continuous
+ * stream of errors from the sensor.
+ *
+ * Set this value to 0 to fail on the first error to occur.
+ */
+#define THERMOCOUPLE_MAX_ERRORS 15
+
//
// Custom Thermistor 1000 parameters
//
@@ -206,7 +219,7 @@
// A well-chosen Kc value should add just enough power to melt the increased material volume.
//#define PID_EXTRUSION_SCALING
#if ENABLED(PID_EXTRUSION_SCALING)
- #define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
+ #define DEFAULT_Kc (100) // heating power = Kc * e_speed
#define LPQ_MAX_LEN 50
#endif
@@ -262,25 +275,30 @@
#endif
/**
- * Automatic Temperature:
- * The hotend target temperature is calculated by all the buffered lines of gcode.
- * The maximum buffered steps/sec of the extruder motor is called "se".
- * Start autotemp mode with M109 S B F
- * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
- * mintemp and maxtemp. Turn this off by executing M109 without F*
- * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
- * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
+ * Automatic Temperature Mode
+ *
+ * Dynamically adjust the hotend target temperature based on planned E moves.
+ *
+ * (Contrast with PID_EXTRUSION_SCALING, which tracks E movement and adjusts PID
+ * behavior using an additional kC value.)
+ *
+ * Autotemp is calculated by (mintemp + factor * mm_per_sec), capped to maxtemp.
+ *
+ * Enable Autotemp Mode with M104/M109 F S B.
+ * Disable by sending M104/M109 with no F parameter (or F0 with AUTOTEMP_PROPORTIONAL).
*/
#define AUTOTEMP
#if ENABLED(AUTOTEMP)
- #define AUTOTEMP_OLDWEIGHT 0.98
+ #define AUTOTEMP_OLDWEIGHT 0.98
+ // Turn on AUTOTEMP on M104/M109 by default using proportions set here
+ //#define AUTOTEMP_PROPORTIONAL
+ #if ENABLED(AUTOTEMP_PROPORTIONAL)
+ #define AUTOTEMP_MIN_P 0 // (°C) Added to the target temperature
+ #define AUTOTEMP_MAX_P 5 // (°C) Added to the target temperature
+ #define AUTOTEMP_FACTOR_P 1 // Apply this F parameter by default (overridden by M104/M109 F)
+ #endif
#endif
-// Extra options for the M114 "Current Position" report
-//#define M114_DETAIL // Use 'M114` for details to check planner calculations
-//#define M114_REALTIME // Real current position based on forward kinematics
-//#define M114_LEGACY // M114 used to synchronize on every call. Enable if needed.
-
// Show Temperature ADC value
// Enable for M105 to include ADC values read from temperature sensors.
//#define SHOW_TEMP_ADC_VALUES
@@ -325,6 +343,18 @@
#define EXTRUDER_RUNOUT_EXTRUDE 5 // (mm)
#endif
+/**
+ * Hotend Idle Timeout
+ * Prevent filament in the nozzle from charring and causing a critical jam.
+ */
+//#define HOTEND_IDLE_TIMEOUT
+#if ENABLED(HOTEND_IDLE_TIMEOUT)
+ #define HOTEND_IDLE_TIMEOUT_SEC (5*60) // (seconds) Time without extruder movement to trigger protection
+ #define HOTEND_IDLE_MIN_TRIGGER 180 // (°C) Minimum temperature to enable hotend protection
+ #define HOTEND_IDLE_NOZZLE_TARGET 0 // (°C) Safe temperature for the nozzle after timeout
+ #define HOTEND_IDLE_BED_TARGET 0 // (°C) Safe temperature for the bed after timeout
+#endif
+
// @section temperature
// Calibration for AD595 / AD8495 sensor to adjust temperature measurements.
@@ -340,12 +370,12 @@
*
* The fan turns on automatically whenever any driver is enabled and turns
* off (or reduces to idle speed) shortly after drivers are turned off.
- *
*/
//#define USE_CONTROLLER_FAN
#if ENABLED(USE_CONTROLLER_FAN)
//#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan
//#define CONTROLLER_FAN_USE_Z_ONLY // With this option only the Z axis is considered
+ //#define CONTROLLER_FAN_IGNORE_Z // Ignore Z stepper. Useful when stepper timeout is disabled.
#define CONTROLLERFAN_SPEED_MIN 0 // (0-255) Minimum speed. (If set below this value the fan is turned off.)
#define CONTROLLERFAN_SPEED_ACTIVE 255 // (0-255) Active speed, used when any motor is enabled
#define CONTROLLERFAN_SPEED_IDLE 0 // (0-255) Idle speed, used when motors are disabled
@@ -426,6 +456,8 @@
#define E3_AUTO_FAN_PIN -1
#define E4_AUTO_FAN_PIN -1
#define E5_AUTO_FAN_PIN -1
+#define E6_AUTO_FAN_PIN -1
+#define E7_AUTO_FAN_PIN -1
#define CHAMBER_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
@@ -581,8 +613,7 @@
// Default x offset in duplication mode (typically set to half print bed width)
#define DEFAULT_DUPLICATION_X_OFFSET 100
-
-#endif // DUAL_X_CARRIAGE
+#endif
// Activate a solenoid on the active extruder with M380. Disable all with M381.
// Define SOL0_PIN, SOL1_PIN, etc., for each extruder that has a solenoid.
@@ -590,19 +621,24 @@
// @section homing
-// Homing hits each endstop, retracts by these distances, then does a slower bump.
-#define X_HOME_BUMP_MM 5
-#define Y_HOME_BUMP_MM 5
-#define Z_HOME_BUMP_MM 2
-#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
-//#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
-//#define HOMING_BACKOFF_MM { 2, 2, 2 } // (mm) Move away from the endstops after homing
+/**
+ * Homing Procedure
+ * Homing (G28) does an indefinite move towards the endstops to establish
+ * the position of the toolhead relative to the workspace.
+ */
-// When G28 is called, this option will make Y home before X
-//#define HOME_Y_BEFORE_X
+//#define SENSORLESS_BACKOFF_MM { 2, 2 } // (mm) Backoff from endstops before sensorless homing
-// Enable this if X or Y can't home without homing the other axis first.
-//#define CODEPENDENT_XY_HOMING
+#define HOMING_BUMP_MM { 5, 5, 2 } // (mm) Backoff from endstops after first bump
+#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
+
+//#define HOMING_BACKOFF_POST_MM { 2, 2, 2 } // (mm) Backoff from endstops after homing
+
+//#define QUICK_HOME // If G28 contains XY do a diagonal move first
+//#define HOME_Y_BEFORE_X // If G28 contains XY home Y before X
+//#define CODEPENDENT_XY_HOMING // If X/Y can't home without homing Y/X first
+
+// @section bltouch
#if ENABLED(BLTOUCH)
/**
@@ -610,8 +646,8 @@
* Do not activate settings that the probe might not understand. Clones might misunderstand
* advanced commands.
*
- * Note: If the probe is not deploying, check a "Cmd: Reset" and "Cmd: Self-Test" and then
- * check the wiring of the BROWN, RED and ORANGE wires.
+ * Note: If the probe is not deploying, do a "Reset" and "Self-Test" and then check the
+ * wiring of the BROWN, RED and ORANGE wires.
*
* Note: If the trigger signal of your probe is not being recognized, it has been very often
* because the BLACK and WHITE wires needed to be swapped. They are not "interchangeable"
@@ -671,6 +707,8 @@
#endif // BLTOUCH
+// @section extras
+
/**
* Z Steppers Auto-Alignment
* Add the G34 command to align multiple Z steppers using a bed probe.
@@ -730,6 +768,34 @@
#define HOME_AFTER_G34
#endif
+//
+// Add the G35 command to read bed corners to help adjust screws.
+//
+//#define ASSISTED_TRAMMING
+#if ENABLED(ASSISTED_TRAMMING)
+
+ // Define positions for probing points, use the hotend as reference not the sensor.
+ #define TRAMMING_POINT_XY { { 20, 20 }, { 200, 20 }, { 200, 200 }, { 20, 200 } }
+
+ // Define positions names for probing points.
+ #define TRAMMING_POINT_NAME_1 "Front-Left"
+ #define TRAMMING_POINT_NAME_2 "Front-Right"
+ #define TRAMMING_POINT_NAME_3 "Back-Right"
+ #define TRAMMING_POINT_NAME_4 "Back-Left"
+
+ // Enable to restore leveling setup after operation
+ #define RESTORE_LEVELING_AFTER_G35
+
+ /**
+ * Screw thread:
+ * M3: 30 = Clockwise, 31 = Counter-Clockwise
+ * M4: 40 = Clockwise, 41 = Counter-Clockwise
+ * M5: 50 = Clockwise, 51 = Counter-Clockwise
+ */
+ #define TRAMMING_SCREW_THREAD 30
+
+#endif
+
// @section motion
#define AXIS_RELATIVE_MODES { false, false, false, false }
@@ -758,7 +824,7 @@
//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated
// Minimum time that a segment needs to take if the buffer is emptied
-#define DEFAULT_MINSEGMENTTIME 20000 // (ms)
+#define DEFAULT_MINSEGMENTTIME 20000 // (µs)
// Slow down the machine if the look ahead buffer is (by default) half full.
// Increase the slowdown divisor for larger buffer sizes.
@@ -767,10 +833,16 @@
#define SLOWDOWN_DIVISOR 2
#endif
-// Frequency limit
-// See nophead's blog for more info
-// Not working O
-//#define XY_FREQUENCY_LIMIT 15
+/**
+ * XY Frequency limit
+ * Reduce resonance by limiting the frequency of small zigzag infill moves.
+ * See https://hydraraptor.blogspot.com/2010/12/frequency-limit.html
+ * Use M201 F G to change limits at runtime.
+ */
+//#define XY_FREQUENCY_LIMIT 10 // (Hz) Maximum frequency of small zigzag infill moves. Set with M201 F.
+#ifdef XY_FREQUENCY_LIMIT
+ #define XY_FREQUENCY_MIN_PERCENT 5 // (percent) Minimum FR percentage to apply. Set with M201 G.
+#endif
// Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
// of the buffer and all stops. This should not be much greater than zero and should only be changed
@@ -826,6 +898,9 @@
//#define CALIBRATION_GCODE
#if ENABLED(CALIBRATION_GCODE)
+ //#define CALIBRATION_SCRIPT_PRE "M117 Starting Auto-Calibration\nT0\nG28\nG12\nM117 Calibrating..."
+ //#define CALIBRATION_SCRIPT_POST "M500\nM117 Calibration data saved"
+
#define CALIBRATION_MEASUREMENT_RESOLUTION 0.01 // mm
#define CALIBRATION_FEEDRATE_SLOW 60 // mm/m
@@ -882,7 +957,7 @@
//#define MICROSTEP16 LOW,LOW,HIGH
//#define MICROSTEP32 HIGH,LOW,HIGH
-// Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
+// Microstep settings (Requires a board with pins named X_MS1, X_MS2, etc.)
#define MICROSTEP_MODES { 16, 16, 16, 16, 16, 16 } // [1,2,4,8,16]
/**
@@ -909,9 +984,20 @@
//#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 } // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
-// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
-//#define DIGIPOT_I2C
-#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
+/**
+ * I2C-based DIGIPOTs (e.g., Azteeg X3 Pro)
+ */
+//#define DIGIPOT_MCP4018 // Requires https://github.com/stawel/SlowSoftI2CMaster
+//#define DIGIPOT_MCP4451
+#if EITHER(DIGIPOT_MCP4018, DIGIPOT_MCP4451)
+ #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT:4 AZTEEG_X3_PRO:8 MKS_SBASE:5 MIGHTYBOARD_REVE:5
+
+ // Actual motor currents in Amps. The number of entries must match DIGIPOT_I2C_NUM_CHANNELS.
+ // These correspond to the physical drivers, so be mindful if the order is changed.
+ #define DIGIPOT_I2C_MOTOR_CURRENTS { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 } // AZTEEG_X3_PRO
+
+ //#define DIGIPOT_USE_RAW_VALUES // Use DIGIPOT_MOTOR_CURRENT raw wiper values (instead of A4988 motor currents)
+
/**
* Common slave addresses:
*
@@ -922,16 +1008,10 @@
* AZTEEG_X5_MINI_WIFI 0x58 0x5C MCP4451
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
*/
- #define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
- #define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
+ //#define DIGIPOT_I2C_ADDRESS_A 0x2C // Unshifted slave address for first DIGIPOT
+ //#define DIGIPOT_I2C_ADDRESS_B 0x2D // Unshifted slave address for second DIGIPOT
#endif
-//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
-#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8 MKS SBASE: 5
-// Actual motor currents in Amps. The number of entries must match DIGIPOT_I2C_NUM_CHANNELS.
-// These correspond to the physical drivers, so be mindful if the order is changed.
-#define DIGIPOT_I2C_MOTOR_CURRENTS { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 } // AZTEEG_X3_PRO
-
//===========================================================================
//=============================Additional Features===========================
//===========================================================================
@@ -1036,8 +1116,12 @@
// Enable this option and set to HIGH if your SD cards are incorrectly detected.
//#define SD_DETECT_STATE HIGH
- #define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
- #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the Z enabled so your bed stays in place.
+ //#define SDCARD_READONLY // Read-only SD card (to save over 2K of flash)
+
+ #define SD_PROCEDURE_DEPTH 1 // Increase if you need more nested M32 calls
+
+ #define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
+ #define SD_FINISHED_RELEASECOMMAND "M84" // Use "M84XYE" to keep Z enabled so your bed stays in place
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
@@ -1060,9 +1144,6 @@
* during SD printing. If the recovery file is found at boot time, present
* an option on the LCD screen to continue the print from the last-known
* point in the file.
- *
- * If the machine reboots when resuming a print you may need to replace or
- * reformat the SD card. (Bad sectors delay startup triggering the watchdog.)
*/
//#define POWER_LOSS_RECOVERY
#if ENABLED(POWER_LOSS_RECOVERY)
@@ -1109,7 +1190,7 @@
#if ENABLED(SDCARD_SORT_ALPHA)
#define SDSORT_LIMIT 40 // Maximum number of sorted items (10-256). Costs 27 bytes each.
#define FOLDER_SORTING -1 // -1=above 0=none 1=below
- #define SDSORT_GCODE false // Allow turning sorting on/off with LCD and M34 g-code.
+ #define SDSORT_GCODE false // Allow turning sorting on/off with LCD and M34 G-code.
#define SDSORT_USES_RAM false // Pre-allocate a static array for faster pre-sorting.
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
@@ -1232,7 +1313,8 @@
// Show SD percentage next to the progress bar
//#define DOGM_SD_PERCENT
- // Enable to save many cycles by drawing a hollow frame on the Info Screen
+ // Save many cycles by drawing a hollow frame or no frame on the Info Screen
+ //#define XYZ_NO_FRAME
#define XYZ_HOLLOW_FRAME
// Enable to save many cycles by drawing a hollow frame on Menu Screens
@@ -1346,6 +1428,7 @@
//#define LCD_HAOYU_FT800CB // Haoyu with 4.3" or 5" (480x272)
//#define LCD_HAOYU_FT810CB // Haoyu with 5" (800x480)
//#define LCD_ALEPHOBJECTS_CLCD_UI // Aleph Objects Color LCD UI
+ //#define LCD_FYSETC_TFT81050 // FYSETC with 5" (800x480)
// Correct the resolution if not using the stock TFT panel.
//#define TOUCH_UI_320x240
@@ -1353,10 +1436,11 @@
//#define TOUCH_UI_800x480
// Mappings for boards with a standard RepRapDiscount Display connector
- //#define AO_EXP1_PINMAP // AlephObjects CLCD UI EXP1 mapping
- //#define AO_EXP2_PINMAP // AlephObjects CLCD UI EXP2 mapping
- //#define CR10_TFT_PINMAP // Rudolph Riedel's CR10 pin mapping
- //#define S6_TFT_PINMAP // FYSETC S6 pin mapping
+ //#define AO_EXP1_PINMAP // AlephObjects CLCD UI EXP1 mapping
+ //#define AO_EXP2_PINMAP // AlephObjects CLCD UI EXP2 mapping
+ //#define CR10_TFT_PINMAP // Rudolph Riedel's CR10 pin mapping
+ //#define S6_TFT_PINMAP // FYSETC S6 pin mapping
+ //#define F6_TFT_PINMAP // FYSETC F6 pin mapping
//#define OTHER_PIN_LAYOUT // Define pins manually below
#if ENABLED(OTHER_PIN_LAYOUT)
@@ -1440,7 +1524,7 @@
// ADC Button Debounce
//
#if HAS_ADC_BUTTONS
- #define ADC_BUTTON_DEBOUNCE_DELAY 16 // (ms) Increase if buttons bounce or repeat too fast
+ #define ADC_BUTTON_DEBOUNCE_DELAY 16 // Increase if buttons bounce or repeat too fast
#endif
// @section safety
@@ -1474,8 +1558,9 @@
//#define BABYSTEP_WITHOUT_HOMING
//#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_MULTIPLICATOR_Z 1 // Babysteps are very small. Increase for faster motion.
- #define BABYSTEP_MULTIPLICATOR_XY 1
+ //#define BABYSTEP_MILLIMETER_UNITS // Specify BABYSTEP_MULTIPLICATOR_(XY|Z) in mm instead of micro-steps
+ #define BABYSTEP_MULTIPLICATOR_Z 1 // (steps or mm) Steps or millimeter distance for each Z babystep
+ #define BABYSTEP_MULTIPLICATOR_XY 1 // (steps or mm) Steps or millimeter distance for each XY babystep
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
#if ENABLED(DOUBLECLICK_FOR_Z_BABYSTEPPING)
@@ -1512,14 +1597,14 @@
* If this algorithm produces a higher speed offset than the extruder can handle (compared to E jerk)
* print acceleration will be reduced during the affected moves to keep within the limit.
*
- * See http://marlinfw.org/docs/features/lin_advance.html for full instructions.
- * Mention @Sebastianv650 on GitHub to alert the author of any issues.
+ * See https://marlinfw.org/docs/features/lin_advance.html for full instructions.
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
//#define EXTRA_LIN_ADVANCE_K // Enable for second linear advance constants
#define LIN_ADVANCE_K 0.22 // Unit: mm compression per 1mm/s extruder speed
//#define LA_DEBUG // If enabled, this will generate debug information output over USB.
+ //#define EXPERIMENTAL_SCURVE // Enable this option to permit S-Curve Acceleration
#endif
// @section leveling
@@ -1538,7 +1623,9 @@
#endif
/**
- * Override MIN_PROBE_EDGE for each side of the build plate
+ * Probing Margins
+ *
+ * Override PROBING_MARGIN for each side of the build plate
* Useful to get probe points to exact positions on targets or
* to allow leveling to avoid plate clamps on only specific
* sides of the bed. With NOZZLE_AS_PROBE negative values are
@@ -1555,10 +1642,10 @@
* the probe to be unable to reach any points.
*/
#if PROBE_SELECTED && !IS_KINEMATIC
- //#define MIN_PROBE_EDGE_LEFT MIN_PROBE_EDGE
- //#define MIN_PROBE_EDGE_RIGHT MIN_PROBE_EDGE
- //#define MIN_PROBE_EDGE_FRONT MIN_PROBE_EDGE
- //#define MIN_PROBE_EDGE_BACK MIN_PROBE_EDGE
+ //#define PROBING_MARGIN_LEFT PROBING_MARGIN
+ //#define PROBING_MARGIN_RIGHT PROBING_MARGIN
+ //#define PROBING_MARGIN_FRONT PROBING_MARGIN
+ //#define PROBING_MARGIN_BACK PROBING_MARGIN
#endif
#if EITHER(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL)
@@ -1600,22 +1687,46 @@
// Add additional compensation depending on hotend temperature
// Note: this values cannot be calibrated and have to be set manually
#if ENABLED(PROBE_TEMP_COMPENSATION)
- // Max temperature that can be reached by heated bed.
- // This is required only for the calibration process.
- #define PTC_MAX_BED_TEMP BED_MAXTEMP
-
// Park position to wait for probe cooldown
- #define PTC_PARK_POS_X 0.0F
- #define PTC_PARK_POS_Y 0.0F
- #define PTC_PARK_POS_Z 100.0F
+ #define PTC_PARK_POS { 0, 0, 100 }
// Probe position to probe and wait for probe to reach target temperature
- #define PTC_PROBE_POS_X 90.0F
- #define PTC_PROBE_POS_Y 100.0F
+ #define PTC_PROBE_POS { 90, 100 }
// Enable additional compensation using hotend temperature
// Note: this values cannot be calibrated automatically but have to be set manually
//#define USE_TEMP_EXT_COMPENSATION
+
+ // Probe temperature calibration generates a table of values starting at PTC_SAMPLE_START
+ // (e.g. 30), in steps of PTC_SAMPLE_RES (e.g. 5) with PTC_SAMPLE_COUNT (e.g. 10) samples.
+
+ //#define PTC_SAMPLE_START 30.0f
+ //#define PTC_SAMPLE_RES 5.0f
+ //#define PTC_SAMPLE_COUNT 10U
+
+ // Bed temperature calibration builds a similar table.
+
+ //#define BTC_SAMPLE_START 60.0f
+ //#define BTC_SAMPLE_RES 5.0f
+ //#define BTC_SAMPLE_COUNT 10U
+
+ // The temperature the probe should be at while taking measurements during bed temperature
+ // calibration.
+ //#define BTC_PROBE_TEMP 30.0f
+
+ // Height above Z=0.0f to raise the nozzle. Lowering this can help the probe to heat faster.
+ // Note: the Z=0.0f offset is determined by the probe offset which can be set using M851.
+ //#define PTC_PROBE_HEATING_OFFSET 0.5f
+
+ // Height to raise the Z-probe between heating and taking the next measurement. Some probes
+ // may fail to untrigger if they have been triggered for a long time, which can be solved by
+ // increasing the height the probe is raised to.
+ //#define PTC_PROBE_RAISE 15U
+
+ // If the probe is outside of the defined range, use linear extrapolation using the closest
+ // point and the PTC_LINEAR_EXTRAPOLATION'th next point. E.g. if set to 4 it will use data[0]
+ // and data[4] to perform linear extrapolation for values below PTC_SAMPLE_START.
+ //#define PTC_LINEAR_EXTRAPOLATION 4
#endif
#endif
@@ -1643,6 +1754,16 @@
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
//#define BEZIER_CURVE_SUPPORT
+/**
+ * Direct Stepping
+ *
+ * Comparable to the method used by Klipper, G6 direct stepping significantly
+ * reduces motion calculations, increases top printing speeds, and results in
+ * less step aliasing by calculating all motions in advance.
+ * Preparing your G-code: https://github.com/colinrgodsey/step-daemon
+ */
+//#define DIRECT_STEPPING
+
/**
* G38 Probe Target
*
@@ -1711,14 +1832,16 @@
//================================= Buffers =================================
//===========================================================================
-// @section hidden
+// @section motion
-// The number of linear motions that can be in the plan at any give time.
-// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
-#if ENABLED(SDSUPPORT)
- #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
+// The number of linear moves that can be in the planner at once.
+// The value of BLOCK_BUFFER_SIZE must be a power of 2 (e.g. 8, 16, 32)
+#if BOTH(SDSUPPORT, DIRECT_STEPPING)
+ #define BLOCK_BUFFER_SIZE 8
+#elif ENABLED(SDSUPPORT)
+ #define BLOCK_BUFFER_SIZE 16
#else
- #define BLOCK_BUFFER_SIZE 16 // maximize block buffer
+ #define BLOCK_BUFFER_SIZE 16
#endif
// @section serial
@@ -1761,10 +1884,14 @@
//#define SERIAL_STATS_DROPPED_RX
#endif
-// Enable an emergency-command parser to intercept certain commands as they
-// enter the serial receive buffer, so they cannot be blocked.
-// Currently handles M108, M112, M410
-// Does not work on boards using AT90USB (USBCON) processors!
+/**
+ * Emergency Command Parser
+ *
+ * Add a low-level parser to intercept certain commands as they
+ * enter the serial receive buffer, so they cannot be blocked.
+ * Currently handles M108, M112, M410, M876
+ * NOTE: Not yet implemented for all platforms.
+ */
//#define EMERGENCY_PARSER
// Bad Serial-connections can miss a received command by sending an 'ok'
@@ -1780,6 +1907,9 @@
// This option inserts short delays between lines of serial output.
#define SERIAL_OVERRUN_PROTECTION
+// For serial echo, the number of digits after the decimal point
+//#define SERIAL_FLOAT_PRECISION 4
+
// @section extras
/**
@@ -1832,19 +1962,55 @@
*/
#if EXTRUDERS > 1
// Z raise distance for tool-change, as needed for some extruders
- #define TOOLCHANGE_ZRAISE 2 // (mm)
- //#define TOOLCHANGE_NO_RETURN // Never return to the previous position on tool-change
+ #define TOOLCHANGE_ZRAISE 2 // (mm)
+ //#define TOOLCHANGE_ZRAISE_BEFORE_RETRACT // Apply raise before swap retraction (if enabled)
+ //#define TOOLCHANGE_NO_RETURN // Never return to previous position on tool-change
#if ENABLED(TOOLCHANGE_NO_RETURN)
- //#define EVENT_GCODE_AFTER_TOOLCHANGE "G12X" // G-code to run after tool-change is complete
+ //#define EVENT_GCODE_AFTER_TOOLCHANGE "G12X" // Extra G-code to run after tool-change
#endif
- // Retract and prime filament on tool-change
+ /**
+ * Retract and prime filament on tool-change to reduce
+ * ooze and stringing and to get cleaner transitions.
+ */
//#define TOOLCHANGE_FILAMENT_SWAP
#if ENABLED(TOOLCHANGE_FILAMENT_SWAP)
- #define TOOLCHANGE_FIL_SWAP_LENGTH 12 // (mm)
- #define TOOLCHANGE_FIL_EXTRA_PRIME 2 // (mm)
- #define TOOLCHANGE_FIL_SWAP_RETRACT_SPEED 3600 // (mm/m)
- #define TOOLCHANGE_FIL_SWAP_PRIME_SPEED 3600 // (mm/m)
+ // Load / Unload
+ #define TOOLCHANGE_FS_LENGTH 12 // (mm) Load / Unload length
+ #define TOOLCHANGE_FS_EXTRA_RESUME_LENGTH 0 // (mm) Extra length for better restart, fine tune by LCD/Gcode)
+ #define TOOLCHANGE_FS_RETRACT_SPEED (50*60) // (mm/m) (Unloading)
+ #define TOOLCHANGE_FS_UNRETRACT_SPEED (25*60) // (mm/m) (On SINGLENOZZLE or Bowden loading must be slowed down)
+
+ // Longer prime to clean out a SINGLENOZZLE
+ #define TOOLCHANGE_FS_EXTRA_PRIME 0 // (mm) Extra priming length
+ #define TOOLCHANGE_FS_PRIME_SPEED (4.6*60) // (mm/m) Extra priming feedrate
+ #define TOOLCHANGE_FS_WIPE_RETRACT 0 // (mm/m) Retract before cooling for less stringing, better wipe, etc.
+
+ // Cool after prime to reduce stringing
+ #define TOOLCHANGE_FS_FAN -1 // Fan index or -1 to skip
+ #define TOOLCHANGE_FS_FAN_SPEED 255 // 0-255
+ #define TOOLCHANGE_FS_FAN_TIME 10 // (seconds)
+
+ // Swap uninitialized extruder with TOOLCHANGE_FS_PRIME_SPEED for all lengths (recover + prime)
+ // (May break filament if not retracted beforehand.)
+ //#define TOOLCHANGE_FS_INIT_BEFORE_SWAP
+
+ // Prime on the first T0 (If other, TOOLCHANGE_FS_INIT_BEFORE_SWAP applied)
+ // Enable it (M217 V[0/1]) before printing, to avoid unwanted priming on host connect
+ //#define TOOLCHANGE_FS_PRIME_FIRST_USED
+
+ /**
+ * Tool Change Migration
+ * This feature provides G-code and LCD options to switch tools mid-print.
+ * All applicable tool properties are migrated so the print can continue.
+ * Tools must be closely matching and other restrictions may apply.
+ * Useful to:
+ * - Change filament color without interruption
+ * - Switch spools automatically on filament runout
+ * - Switch to a different nozzle on an extruder jam
+ */
+ #define TOOLCHANGE_MIGRATION_FEATURE
+
#endif
/**
@@ -1855,8 +2021,10 @@
#if ENABLED(TOOLCHANGE_PARK)
#define TOOLCHANGE_PARK_XY { X_MIN_POS + 10, Y_MIN_POS + 10 }
#define TOOLCHANGE_PARK_XY_FEEDRATE 6000 // (mm/m)
+ //#define TOOLCHANGE_PARK_X_ONLY // X axis only move
+ //#define TOOLCHANGE_PARK_Y_ONLY // Y axis only move
#endif
-#endif
+#endif // EXTRUDERS > 1
/**
* Advanced Pause
@@ -1907,7 +2075,7 @@
#define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable for XYZ steppers to stay powered on during filament change.
//#define PARK_HEAD_ON_PAUSE // Park the nozzle during pause and filament change.
- //#define HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
+ //#define HOME_BEFORE_FILAMENT_CHANGE // If needed, home before parking for filament change
//#define FILAMENT_LOAD_UNLOAD_GCODES // Add M701/M702 Load/Unload G-codes, plus Load/Unload in the LCD Prepare menu.
//#define FILAMENT_UNLOAD_ALL_EXTRUDERS // Allow M702 to unload all extruders above a minimum target temp (as set by M302)
@@ -2248,6 +2416,7 @@
* CHOPPER_DEFAULT_19V
* CHOPPER_DEFAULT_24V
* CHOPPER_DEFAULT_36V
+ * CHOPPER_09STEP_24V // 0.9 degree steppers (24V)
* CHOPPER_PRUSAMK3_24V // Imported parameters from the official Prusa firmware for MK3 (24V)
* CHOPPER_MARLIN_119 // Old defaults from Marlin v1.1.9
*
@@ -2257,11 +2426,11 @@
#define CHOPPER_TIMING CHOPPER_DEFAULT_12V
/**
- * Monitor Trinamic drivers for error conditions,
- * like overtemperature and short to ground.
- * In the case of overtemperature Marlin can decrease the driver current until error condition clears.
+ * Monitor Trinamic drivers
+ * for error conditions like overtemperature and short to ground.
+ * To manage over-temp Marlin can decrease the driver current until the error condition clears.
* Other detected conditions can be used to stop the current print.
- * Relevant g-codes:
+ * Relevant G-codes:
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
* M911 - Report stepper driver overtemperature pre-warn condition.
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
@@ -2315,7 +2484,7 @@
* HIGHEST 255 -64 (Too sensitive => False positive)
* LOWEST 0 63 (Too insensitive => No trigger)
*
- * It is recommended to set [XYZ]_HOME_BUMP_MM to 0.
+ * It is recommended to set HOMING_BUMP_MM to { 0, 0, 0 }.
*
* SPI_ENDSTOPS *** Beta feature! *** TMC2130 Only ***
* Poll the driver through SPI to determine load when homing.
@@ -2331,11 +2500,27 @@
#define X_STALL_SENSITIVITY 8
#define X2_STALL_SENSITIVITY X_STALL_SENSITIVITY
#define Y_STALL_SENSITIVITY 8
+ #define Y2_STALL_SENSITIVITY Y_STALL_SENSITIVITY
//#define Z_STALL_SENSITIVITY 8
+ //#define Z2_STALL_SENSITIVITY Z_STALL_SENSITIVITY
+ //#define Z3_STALL_SENSITIVITY Z_STALL_SENSITIVITY
+ //#define Z4_STALL_SENSITIVITY Z_STALL_SENSITIVITY
//#define SPI_ENDSTOPS // TMC2130 only
//#define IMPROVE_HOMING_RELIABILITY
#endif
+ /**
+ * TMC Homing stepper phase.
+ *
+ * Improve homing repeatability by homing to stepper coil's nearest absolute
+ * phase position. Trinamic drivers use a stepper phase table with 1024 values
+ * spanning 4 full steps with 256 positions each (ergo, 1024 positions).
+ * Full step positions (128, 384, 640, 896) have the highest holding torque.
+ *
+ * Values from 0..1023, -1 to disable homing phase for that axis.
+ */
+ //#define TMC_HOME_PHASE { 896, 896, 896 }
+
/**
* Beta feature!
* Create a 50/50 square wave step pulse optimal for stepper drivers.
@@ -2536,7 +2721,7 @@
* Monitor L6470 drivers for error conditions like over temperature and over current.
* In the case of over temperature Marlin can decrease the drive until the error condition clears.
* Other detected conditions can be used to stop the current print.
- * Relevant g-codes:
+ * Relevant G-codes:
* M906 - I1/2/3/4/5 Set or get motor drive level using axis codes X, Y, Z, E. Report values if no axis codes given.
* I not present or I0 or I1 - X, Y, Z or E0
* I2 - X2, Y2, Z2 or E1
@@ -2613,11 +2798,11 @@
//#define PHOTO_RETRACT_MM 6.5 // (mm) E retract/recover for the photo move (M240 R S)
// Canon RC-1 or homebrew digital camera trigger
- // Data from: http://www.doc-diy.net/photo/rc-1_hacked/
+ // Data from: https://www.doc-diy.net/photo/rc-1_hacked/
//#define PHOTOGRAPH_PIN 23
// Canon Hack Development Kit
- // http://captain-slow.dk/2014/03/09/3d-printing-timelapses/
+ // https://captain-slow.dk/2014/03/09/3d-printing-timelapses/
//#define CHDK_PIN 4
// Optional second move with delay to trigger the camera shutter
@@ -2654,39 +2839,138 @@
* You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V
* hardware PWM pin for the speed control and a pin for the rotation direction.
*
- * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details.
+ * See https://marlinfw.org/docs/configuration/laser_spindle.html for more config details.
*/
//#define SPINDLE_FEATURE
//#define LASER_FEATURE
#if EITHER(SPINDLE_FEATURE, LASER_FEATURE)
#define SPINDLE_LASER_ACTIVE_HIGH false // Set to "true" if the on/off function is active HIGH
#define SPINDLE_LASER_PWM true // Set to "true" if your controller supports setting the speed/power
- #define SPINDLE_LASER_PWM_INVERT true // Set to "true" if the speed/power goes up when you want it to go slower
- #define SPINDLE_LASER_POWERUP_DELAY 5000 // (ms) Delay to allow the spindle/laser to come up to speed/power
- #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // (ms) Delay to allow the spindle to stop
+ #define SPINDLE_LASER_PWM_INVERT false // Set to "true" if the speed/power goes up when you want it to go slower
+
+ #define SPINDLE_LASER_FREQUENCY 2500 // (Hz) Spindle/laser frequency (only on supported HALs: AVR and LPC)
+
+ /**
+ * Speed / Power can be set ('M3 S') and displayed in terms of:
+ * - PWM255 (S0 - S255)
+ * - PERCENT (S0 - S100)
+ * - RPM (S0 - S50000) Best for use with a spindle
+ */
+ #define CUTTER_POWER_UNIT PWM255
+
+ /**
+ * Relative Cutter Power
+ * Normally, 'M3 O' sets
+ * OCR power is relative to the range SPEED_POWER_MIN...SPEED_POWER_MAX.
+ * so input powers of 0...255 correspond to SPEED_POWER_MIN...SPEED_POWER_MAX
+ * instead of normal range (0 to SPEED_POWER_MAX).
+ * Best used with (e.g.) SuperPID router controller: S0 = 5,000 RPM and S255 = 30,000 RPM
+ */
+ //#define CUTTER_POWER_RELATIVE // Set speed proportional to [SPEED_POWER_MIN...SPEED_POWER_MAX]
#if ENABLED(SPINDLE_FEATURE)
//#define SPINDLE_CHANGE_DIR // Enable if your spindle controller can change spindle direction
#define SPINDLE_CHANGE_DIR_STOP // Enable if the spindle should stop before changing spin direction
#define SPINDLE_INVERT_DIR false // Set to "true" if the spin direction is reversed
+ #define SPINDLE_LASER_POWERUP_DELAY 5000 // (ms) Delay to allow the spindle/laser to come up to speed/power
+ #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // (ms) Delay to allow the spindle to stop
+
/**
- * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power
+ * M3/M4 Power Equation
*
- * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT
- * where PWM duty cycle varies from 0 to 255
+ * Each tool uses different value ranges for speed / power control.
+ * These parameters are used to convert between tool power units and PWM.
*
- * set the following for your controller (ALL MUST BE SET)
+ * Speed/Power = (PWMDC / 255 * 100 - SPEED_POWER_INTERCEPT) / SPEED_POWER_SLOPE
+ * PWMDC = (spdpwr - SPEED_POWER_MIN) / (SPEED_POWER_MAX - SPEED_POWER_MIN) / SPEED_POWER_SLOPE
*/
- #define SPEED_POWER_SLOPE 118.4
- #define SPEED_POWER_INTERCEPT 0
- #define SPEED_POWER_MIN 5000
- #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM
+ #define SPEED_POWER_INTERCEPT 0 // (%) 0-100 i.e., Minimum power percentage
+ #define SPEED_POWER_MIN 5000 // (RPM)
+ #define SPEED_POWER_MAX 30000 // (RPM) SuperPID router controller 0 - 30,000 RPM
+ #define SPEED_POWER_STARTUP 25000 // (RPM) M3/M4 speed/power default (with no arguments)
+
#else
- #define SPEED_POWER_SLOPE 0.3922
- #define SPEED_POWER_INTERCEPT 0
- #define SPEED_POWER_MIN 10
- #define SPEED_POWER_MAX 100 // 0-100%
+
+ #define SPEED_POWER_INTERCEPT 0 // (%) 0-100 i.e., Minimum power percentage
+ #define SPEED_POWER_MIN 0 // (%) 0-100
+ #define SPEED_POWER_MAX 100 // (%) 0-100
+ #define SPEED_POWER_STARTUP 80 // (%) M3/M4 speed/power default (with no arguments)
+
+ /**
+ * Enable inline laser power to be handled in the planner / stepper routines.
+ * Inline power is specified by the I (inline) flag in an M3 command (e.g., M3 S20 I)
+ * or by the 'S' parameter in G0/G1/G2/G3 moves (see LASER_MOVE_POWER).
+ *
+ * This allows the laser to keep in perfect sync with the planner and removes
+ * the powerup/down delay since lasers require negligible time.
+ */
+ #define LASER_POWER_INLINE
+
+ #if ENABLED(LASER_POWER_INLINE)
+ /**
+ * Scale the laser's power in proportion to the movement rate.
+ *
+ * - Sets the entry power proportional to the entry speed over the nominal speed.
+ * - Ramps the power up every N steps to approximate the speed trapezoid.
+ * - Due to the limited power resolution this is only approximate.
+ */
+ #define LASER_POWER_INLINE_TRAPEZOID
+
+ /**
+ * Continuously calculate the current power (nominal_power * current_rate / nominal_rate).
+ * Required for accurate power with non-trapezoidal acceleration (e.g., S_CURVE_ACCELERATION).
+ * This is a costly calculation so this option is discouraged on 8-bit AVR boards.
+ *
+ * LASER_POWER_INLINE_TRAPEZOID_CONT_PER defines how many step cycles there are between power updates. If your
+ * board isn't able to generate steps fast enough (and you are using LASER_POWER_INLINE_TRAPEZOID_CONT), increase this.
+ * Note that when this is zero it means it occurs every cycle; 1 means a delay wait one cycle then run, etc.
+ */
+ //#define LASER_POWER_INLINE_TRAPEZOID_CONT
+
+ /**
+ * Stepper iterations between power updates. Increase this value if the board
+ * can't keep up with the processing demands of LASER_POWER_INLINE_TRAPEZOID_CONT.
+ * Disable (or set to 0) to recalculate power on every stepper iteration.
+ */
+ //#define LASER_POWER_INLINE_TRAPEZOID_CONT_PER 10
+
+ /**
+ * Include laser power in G0/G1/G2/G3/G5 commands with the 'S' parameter
+ */
+ //#define LASER_MOVE_POWER
+
+ #if ENABLED(LASER_MOVE_POWER)
+ // Turn off the laser on G0 moves with no power parameter.
+ // If a power parameter is provided, use that instead.
+ //#define LASER_MOVE_G0_OFF
+
+ // Turn off the laser on G28 homing.
+ //#define LASER_MOVE_G28_OFF
+ #endif
+
+ /**
+ * Inline flag inverted
+ *
+ * WARNING: M5 will NOT turn off the laser unless another move
+ * is done (so G-code files must end with 'M5 I').
+ */
+ //#define LASER_POWER_INLINE_INVERT
+
+ /**
+ * Continuously apply inline power. ('M3 S3' == 'G1 S3' == 'M3 S3 I')
+ *
+ * The laser might do some weird things, so only enable this
+ * feature if you understand the implications.
+ */
+ //#define LASER_POWER_INLINE_CONTINUOUS
+
+ #else
+
+ #define SPINDLE_LASER_POWERUP_DELAY 50 // (ms) Delay to allow the spindle/laser to come up to speed/power
+ #define SPINDLE_LASER_POWERDOWN_DELAY 50 // (ms) Delay to allow the spindle to stop
+
+ #endif
#endif
#endif
@@ -2738,6 +3022,24 @@
//#define FILAMENT_LCD_DISPLAY
#endif
+/**
+ * Power Monitor
+ * Monitor voltage (V) and/or current (A), and -when possible- power (W)
+ *
+ * Read and configure with M430
+ *
+ * The current sensor feeds DC voltage (relative to the measured current) to an analog pin
+ * The voltage sensor feeds DC voltage (relative to the measured voltage) to an analog pin
+ */
+//#define POWER_MONITOR_CURRENT // Monitor the system current
+//#define POWER_MONITOR_VOLTAGE // Monitor the system voltage
+#if EITHER(POWER_MONITOR_CURRENT, POWER_MONITOR_VOLTAGE)
+ #define POWER_MONITOR_VOLTS_PER_AMP 0.05000 // Input voltage to the MCU analog pin per amp - DO NOT apply more than ADC_VREF!
+ #define POWER_MONITOR_CURRENT_OFFSET -1 // Offset value for current sensors with linear function output
+ #define POWER_MONITOR_VOLTS_PER_VOLT 0.11786 // Input voltage to the MCU analog pin per volt - DO NOT apply more than ADC_VREF!
+ #define POWER_MONITOR_FIXED_VOLTAGE 13.6 // Voltage for a current sensor with no voltage sensor (for power display)
+#endif
+
/**
* CNC Coordinate Systems
*
@@ -2755,6 +3057,9 @@
* Include capabilities in M115 output
*/
#define EXTENDED_CAPABILITIES_REPORT
+#if ENABLED(EXTENDED_CAPABILITIES_REPORT)
+ //#define M115_GEOMETRY_REPORT
+#endif
/**
* Expected Printer Check
@@ -2774,9 +3079,21 @@
* Activate to make volumetric extrusion the default method,
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
*
- * M200 D0 to disable, M200 Dn to set a new diameter.
+ * M200 D0 to disable, M200 Dn to set a new diameter (and enable volumetric).
+ * M200 S0/S1 to disable/enable volumetric extrusion.
*/
//#define VOLUMETRIC_DEFAULT_ON
+
+ //#define VOLUMETRIC_EXTRUDER_LIMIT
+ #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT)
+ /**
+ * Default volumetric extrusion limit in cubic mm per second (mm^3/sec).
+ * This factory setting applies to all extruders.
+ * Use 'M200 [T] L' to override and 'M502' to reset.
+ * A non-zero value activates Volume-based Extrusion Limiting.
+ */
+ #define DEFAULT_VOLUMETRIC_EXTRUDER_LIMIT 0.00 // (mm^3/sec)
+ #endif
#endif
/**
@@ -2788,6 +3105,13 @@
*/
//#define NO_WORKSPACE_OFFSETS
+// Extra options for the M114 "Current Position" report
+//#define M114_DETAIL // Use 'M114` for details to check planner calculations
+//#define M114_REALTIME // Real current position based on forward kinematics
+//#define M114_LEGACY // M114 used to synchronize on every call. Enable if needed.
+
+//#define REPORT_FAN_CHANGE // Report the new fan speed when changed by M106 (and others)
+
/**
* Set the number of proportional font spaces required to fill up a typical character space.
* This can help to better align the output of commands like `G29 O` Mesh Output.
@@ -2808,6 +3132,8 @@
//#define GCODE_CASE_INSENSITIVE // Accept G-code sent to the firmware in lowercase
+//#define REPETIER_GCODE_M360 // Add commands originally from Repetier FW
+
/**
* CNC G-code options
* Support CNC-style G-code dialects used by laser cutters, drawing machine cams, etc.
@@ -2898,11 +3224,11 @@
* I2C position encoders for closed loop control.
* Developed by Chris Barr at Aus3D.
*
- * Wiki: http://wiki.aus3d.com.au/Magnetic_Encoder
+ * Wiki: https://wiki.aus3d.com.au/Magnetic_Encoder
* Github: https://github.com/Aus3D/MagneticEncoder
*
- * Supplier: http://aus3d.com.au/magnetic-encoder-module
- * Alternative Supplier: http://reliabuild3d.com/
+ * Supplier: https://aus3d.com.au/magnetic-encoder-module
+ * Alternative Supplier: https://reliabuild3d.com/
*
* Reliabuild encoders have been modified to improve reliability.
*/
@@ -3090,7 +3416,7 @@
// This is for Prusa MK3-style extruders. Customize for your hardware.
#define MMU2_FILAMENTCHANGE_EJECT_FEED 80.0
#define MMU2_LOAD_TO_NOZZLE_SEQUENCE \
- { 7.2, 562 }, \
+ { 7.2, 1145 }, \
{ 14.4, 871 }, \
{ 36.0, 1393 }, \
{ 14.4, 871 }, \
@@ -3108,6 +3434,45 @@
{ 10.0, 700 }, \
{ -10.0, 400 }, \
{ -50.0, 2000 }
+ #endif
+
+ /**
+ * MMU Extruder Sensor
+ *
+ * Support for a Prusa (or other) IR Sensor to detect filament near the extruder
+ * and make loading more reliable. Suitable for an extruder equipped with a filament
+ * sensor less than 38mm from the gears.
+ *
+ * During loading the extruder will stop when the sensor is triggered, then do a last
+ * move up to the gears. If no filament is detected, the MMU2 can make some more attempts.
+ * If all attempts fail, a filament runout will be triggered.
+ */
+ //#define MMU_EXTRUDER_SENSOR
+ #if ENABLED(MMU_EXTRUDER_SENSOR)
+ #define MMU_LOADING_ATTEMPTS_NR 5 //max. number of attempts to load filament if first load fail
+ #endif
+
+ /**
+ * Using a sensor like the MMU2S
+ * This mode requires a MK3S extruder with a sensor at the extruder idler, like the MMU2S.
+ * See https://help.prusa3d.com/en/guide/3b-mk3s-mk2-5s-extruder-upgrade_41560, step 11
+ */
+ //#define PRUSA_MMU2_S_MODE
+ #if ENABLED(PRUSA_MMU2_S_MODE)
+ #define MMU2_C0_RETRY 5 // Number of retries (total time = timeout*retries)
+
+ #define MMU2_CAN_LOAD_FEEDRATE 800 // (mm/m)
+ #define MMU2_CAN_LOAD_SEQUENCE \
+ { 0.1, MMU2_CAN_LOAD_FEEDRATE }, \
+ { 60.0, MMU2_CAN_LOAD_FEEDRATE }, \
+ { -52.0, MMU2_CAN_LOAD_FEEDRATE }
+
+ #define MMU2_CAN_LOAD_RETRACT 6.0 // (mm) Keep under the distance between Load Sequence values
+ #define MMU2_CAN_LOAD_DEVIATION 0.8 // (mm) Acceptable deviation
+
+ #define MMU2_CAN_LOAD_INCREMENT 0.2 // (mm) To reuse within MMU2 module
+ #define MMU2_CAN_LOAD_INCREMENT_SEQUENCE \
+ { -MMU2_CAN_LOAD_INCREMENT, MMU2_CAN_LOAD_FEEDRATE }
#endif
diff --git a/Marlin/Makefile b/Marlin/Makefile
index 0a9b3a45d..95135ab59 100644
--- a/Marlin/Makefile
+++ b/Marlin/Makefile
@@ -14,7 +14,7 @@
# Detailed instructions for using the makefile:
#
# 1. Modify the line containing "ARDUINO_INSTALL_DIR" to point to the directory that
-# contains the Arduino installation (for example, under Mac OS X, this
+# contains the Arduino installation (for example, under macOS, this
# might be /Applications/Arduino.app/Contents/Resources/Java).
#
# 2. Modify the line containing "UPLOAD_PORT" to refer to the filename
@@ -98,7 +98,7 @@ NEOPIXEL ?= 0
############
# Try to automatically determine whether RELOC_WORKAROUND is needed based
# on GCC versions:
-# http://www.avrfreaks.net/comment/1789106#comment-1789106
+# https://www.avrfreaks.net/comment/1789106#comment-1789106
CC_MAJ:=$(shell $(CC) -dM -E - < /dev/null | grep __GNUC__ | cut -f3 -d\ )
CC_MIN:=$(shell $(CC) -dM -E - < /dev/null | grep __GNUC_MINOR__ | cut -f3 -d\ )
@@ -170,105 +170,110 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1100)
else ifeq ($(HARDWARE_MOTHERBOARD),1101)
# Velleman K8400 Controller (derived from 3Drag Controller)
else ifeq ($(HARDWARE_MOTHERBOARD),1102)
-# 2PrintBeta BAM&DICE with STK drivers
+# Velleman K8600 Controller (derived from 3Drag Controller)
else ifeq ($(HARDWARE_MOTHERBOARD),1103)
-# 2PrintBeta BAM&DICE Due with STK drivers
+# 2PrintBeta BAM&DICE with STK drivers
else ifeq ($(HARDWARE_MOTHERBOARD),1104)
-# MKS BASE v1.0
+# 2PrintBeta BAM&DICE Due with STK drivers
else ifeq ($(HARDWARE_MOTHERBOARD),1105)
-# MKS v1.4 with A4982 stepper drivers
+# MKS BASE v1.0
else ifeq ($(HARDWARE_MOTHERBOARD),1106)
-# MKS v1.5 with Allegro A4982 stepper drivers
+# MKS v1.4 with A4982 stepper drivers
else ifeq ($(HARDWARE_MOTHERBOARD),1107)
-# MKS v1.6 with Allegro A4982 stepper drivers
+# MKS v1.5 with Allegro A4982 stepper drivers
else ifeq ($(HARDWARE_MOTHERBOARD),1108)
-
-# MKS BASE 1.0 with Heroic HR4982 stepper drivers
+# MKS v1.6 with Allegro A4982 stepper drivers
else ifeq ($(HARDWARE_MOTHERBOARD),1109)
-# MKS GEN v1.3 or 1.4
+# MKS BASE 1.0 with Heroic HR4982 stepper drivers
else ifeq ($(HARDWARE_MOTHERBOARD),1110)
-# MKS GEN L
+# MKS GEN v1.3 or 1.4
else ifeq ($(HARDWARE_MOTHERBOARD),1111)
-# zrib V2.0 control board (Chinese knock off RAMPS replica)
+# MKS GEN L
else ifeq ($(HARDWARE_MOTHERBOARD),1112)
-# BigTreeTech or BIQU KFB2.0
+# zrib V2.0 control board (Chinese knock off RAMPS replica)
else ifeq ($(HARDWARE_MOTHERBOARD),1113)
-# Felix 2.0+ Electronics Board (RAMPS like)
+# BigTreeTech or BIQU KFB2.0
else ifeq ($(HARDWARE_MOTHERBOARD),1114)
-# Invent-A-Part RigidBoard
+# Felix 2.0+ Electronics Board (RAMPS like)
else ifeq ($(HARDWARE_MOTHERBOARD),1115)
-# Invent-A-Part RigidBoard V2
+# Invent-A-Part RigidBoard
else ifeq ($(HARDWARE_MOTHERBOARD),1116)
-# Sainsmart 2-in-1 board
+# Invent-A-Part RigidBoard V2
else ifeq ($(HARDWARE_MOTHERBOARD),1117)
-# Ultimaker
+# Sainsmart 2-in-1 board
else ifeq ($(HARDWARE_MOTHERBOARD),1118)
-# Ultimaker (Older electronics. Pre 1.5.4. This is rare)
+# Ultimaker
else ifeq ($(HARDWARE_MOTHERBOARD),1119)
+# Ultimaker (Older electronics. Pre 1.5.4. This is rare)
+else ifeq ($(HARDWARE_MOTHERBOARD),1120)
MCU ?= atmega1280
# Azteeg X3
-else ifeq ($(HARDWARE_MOTHERBOARD),1120)
-# Azteeg X3 Pro
else ifeq ($(HARDWARE_MOTHERBOARD),1121)
-# Ultimainboard 2.x (Uses TEMP_SENSOR 20)
+# Azteeg X3 Pro
else ifeq ($(HARDWARE_MOTHERBOARD),1122)
-# Rumba
+# Ultimainboard 2.x (Uses TEMP_SENSOR 20)
else ifeq ($(HARDWARE_MOTHERBOARD),1123)
-# Raise3D Rumba
+# Rumba
else ifeq ($(HARDWARE_MOTHERBOARD),1124)
-# Rapide Lite RL200 Rumba
+# Raise3D Rumba
else ifeq ($(HARDWARE_MOTHERBOARD),1125)
-# Formbot T-Rex 2 Plus
+# Rapide Lite RL200 Rumba
else ifeq ($(HARDWARE_MOTHERBOARD),1126)
-# Formbot T-Rex 3
+# Formbot T-Rex 2 Plus
else ifeq ($(HARDWARE_MOTHERBOARD),1127)
-# Formbot Raptor
+# Formbot T-Rex 3
else ifeq ($(HARDWARE_MOTHERBOARD),1128)
-# Formbot Raptor 2
+# Formbot Raptor
else ifeq ($(HARDWARE_MOTHERBOARD),1129)
-# bq ZUM Mega 3D
+# Formbot Raptor 2
else ifeq ($(HARDWARE_MOTHERBOARD),1130)
-# MakeBoard Mini v2.1.2 is a control board sold by MicroMake
+# bq ZUM Mega 3D
else ifeq ($(HARDWARE_MOTHERBOARD),1131)
-# TriGorilla Anycubic version 1.3 based on RAMPS EFB
+# MakeBoard Mini v2.1.2 is a control board sold by MicroMake
else ifeq ($(HARDWARE_MOTHERBOARD),1132)
-# TriGorilla Anycubic version 1.4 based on RAMPS EFB
+# TriGorilla Anycubic version 1.3 based on RAMPS EFB
else ifeq ($(HARDWARE_MOTHERBOARD),1133)
-# TriGorilla Anycubic version 1.4 Rev 1.1
+# TriGorilla Anycubic version 1.4 based on RAMPS EFB
else ifeq ($(HARDWARE_MOTHERBOARD),1134)
-# Creality: Ender-4, CR-8
+# TriGorilla Anycubic version 1.4 Rev 1.1
else ifeq ($(HARDWARE_MOTHERBOARD),1135)
-# Creality: CR10S, CR20, CR-X
+# Creality: Ender-4, CR-8
else ifeq ($(HARDWARE_MOTHERBOARD),1136)
-# Dagoma F5
+# Creality: CR10S, CR20, CR-X
else ifeq ($(HARDWARE_MOTHERBOARD),1137)
-# FYSETC F6 1.3
+# Dagoma F5
else ifeq ($(HARDWARE_MOTHERBOARD),1138)
-# FYSETC F6 1.5
+# FYSETC F6 1.3
else ifeq ($(HARDWARE_MOTHERBOARD),1139)
-# Duplicator i3 Plus
+# FYSETC F6 1.5
else ifeq ($(HARDWARE_MOTHERBOARD),1140)
-# VORON
+# Duplicator i3 Plus
else ifeq ($(HARDWARE_MOTHERBOARD),1141)
-# TRONXY V3 1.0
+# VORON
else ifeq ($(HARDWARE_MOTHERBOARD),1142)
-# Z-Bolt X Series
+# TRONXY V3 1.0
else ifeq ($(HARDWARE_MOTHERBOARD),1143)
-# TT OSCAR
+# Z-Bolt X Series
else ifeq ($(HARDWARE_MOTHERBOARD),1144)
-# Overlord/Overlord Pro
+# TT OSCAR
else ifeq ($(HARDWARE_MOTHERBOARD),1145)
-# ADIMLab Gantry v1
+# Overlord/Overlord Pro
else ifeq ($(HARDWARE_MOTHERBOARD),1146)
-# ADIMLab Gantry v2
+# ADIMLab Gantry v1
else ifeq ($(HARDWARE_MOTHERBOARD),1147)
-# BIQU Tango V1
+# ADIMLab Gantry v2
else ifeq ($(HARDWARE_MOTHERBOARD),1148)
-# MKS GEN L V2
+# BIQU Tango V1
else ifeq ($(HARDWARE_MOTHERBOARD),1149)
-# Copymaster 3D
+# MKS GEN L V2
else ifeq ($(HARDWARE_MOTHERBOARD),1150)
+# Copymaster 3D
+else ifeq ($(HARDWARE_MOTHERBOARD),1151)
+# Ortur 4
+else ifeq ($(HARDWARE_MOTHERBOARD),1152)
+# Tenlog D3 Hero
+else ifeq ($(HARDWARE_MOTHERBOARD),1153)
#
# RAMBo and derivatives
@@ -361,34 +366,38 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1501)
else ifeq ($(HARDWARE_MOTHERBOARD),1502)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
-# Melzi with ATmega1284 (MaKr3d version)
+# Melzi V2.0
else ifeq ($(HARDWARE_MOTHERBOARD),1503)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
-# Melzi Creality3D board (for CR-10 etc)
+# Melzi with ATmega1284 (MaKr3d version)
else ifeq ($(HARDWARE_MOTHERBOARD),1504)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
-# Melzi Malyan M150 board
+# Melzi Creality3D board (for CR-10 etc)
else ifeq ($(HARDWARE_MOTHERBOARD),1505)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
-# Tronxy X5S
+# Melzi Malyan M150 board
else ifeq ($(HARDWARE_MOTHERBOARD),1506)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
-# STB V1.1
+# Tronxy X5S
else ifeq ($(HARDWARE_MOTHERBOARD),1507)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
-# Azteeg X1
+# STB V1.1
else ifeq ($(HARDWARE_MOTHERBOARD),1508)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
-# Anet 1.0 (Melzi clone)
+# Azteeg X1
else ifeq ($(HARDWARE_MOTHERBOARD),1509)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
+# Anet 1.0 (Melzi clone)
+else ifeq ($(HARDWARE_MOTHERBOARD),1510)
+ HARDWARE_VARIANT ?= Sanguino
+ MCU ?= atmega1284p
#
# Other ATmega644P, ATmega644, ATmega1284P
@@ -686,7 +695,7 @@ ifeq ($(HARDWARE_VARIANT), Teensy)
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="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_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)
diff --git a/Marlin/Marlin.ino b/Marlin/Marlin.ino
index 9bfb2881b..57c825445 100644
--- a/Marlin/Marlin.ino
+++ b/Marlin/Marlin.ino
@@ -1,9 +1,8 @@
-/*
-================================================================================
+/*==============================================================================
Marlin Firmware
- (c) 2011-2019 MarlinFirmware
+ (c) 2011-2020 MarlinFirmware
Portions of Marlin are (c) by their respective authors.
All code complies with GPLv2 and/or GPLv3
@@ -12,25 +11,28 @@
Greetings! Thank you for choosing Marlin 2 as your 3D printer firmware.
To configure Marlin you must edit Configuration.h and Configuration_adv.h
-located in the root 'Marlin' folder. Check the config/examples folder to see if
-there's a more suitable starting-point for your specific hardware.
+located in the root 'Marlin' folder. Check our Configurations repository to
+see if there's a more suitable starting-point for your specific hardware.
Before diving in, we recommend the following essential links:
Marlin Firmware Official Website
- - http://marlinfw.org/
+ - https://marlinfw.org/
The official Marlin Firmware website contains the most up-to-date
documentation. Contributions are always welcome!
Configuration
+ - https://github.com/MarlinFirmware/Configurations
+ Example configurations for several printer models.
+
- https://www.youtube.com/watch?v=3gwWVFtdg-4
A good 20-minute overview of Marlin configuration by Tom Sanladerer.
(Applies to Marlin 1.0.x, so Jerk and Acceleration should be halved.)
Also... https://www.google.com/search?tbs=vid%3A1&q=configure+marlin
- - http://marlinfw.org/docs/configuration/configuration.html
+ - https://marlinfw.org/docs/configuration/configuration.html
Marlin's configuration options are explained in more detail here.
Getting Help
@@ -45,9 +47,11 @@ Getting Help
Contributing
- - http://marlinfw.org/docs/development/contributing.html
+ - https://marlinfw.org/docs/development/contributing.html
If you'd like to contribute to Marlin, read this first!
- - http://marlinfw.org/docs/development/coding_standards.html
+ - https://marlinfw.org/docs/development/coding_standards.html
Before submitting code get to know the Coding Standards.
-*/
+
+
+------------------------------------------------------------------------------*/
diff --git a/Marlin/Version.h b/Marlin/Version.h
index 1f65f4d49..723ccef70 100644
--- a/Marlin/Version.h
+++ b/Marlin/Version.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -34,7 +34,7 @@
* Verbose version identifier which should contain a reference to the location
* from where the binary was downloaded or the source code was compiled.
*/
-//#define DETAILED_BUILD_VERSION SHORT_BUILD_VERSION " (Github)"
+//#define DETAILED_BUILD_VERSION SHORT_BUILD_VERSION
/**
* The STRING_DISTRIBUTION_DATE represents when the binary file was built,
@@ -65,12 +65,12 @@
* The WEBSITE_URL is the location where users can get more information such as
* documentation about a specific Marlin release.
*/
-//#define WEBSITE_URL "http://marlinfw.org"
+//#define WEBSITE_URL "https://marlinfw.org"
/**
* Set the vendor info the serial USB interface, if changable
* Currently only supported by DUE platform
*/
-//#define USB_DEVICE_VENDOR_ID 0x0000
-//#define USB_DEVICE_PRODUCT_ID 0x0000
-//#define USB_DEVICE_MANUFACTURE_NAME WEBSITE_URL
+//#define USB_DEVICE_VENDOR_ID 0x0000
+//#define USB_DEVICE_PRODUCT_ID 0x0000
+//#define USB_DEVICE_MANUFACTURE_NAME WEBSITE_URL
diff --git a/Marlin/lib/readme.txt b/Marlin/lib/readme.txt
index dbadc3d63..5ec60aa85 100644
--- a/Marlin/lib/readme.txt
+++ b/Marlin/lib/readme.txt
@@ -33,4 +33,4 @@ PlatformIO will find your libraries automatically, configure preprocessor's
include paths and build them.
More information about PlatformIO Library Dependency Finder
-- http://docs.platformio.org/page/librarymanager/ldf.html
+- https://docs.platformio.org/page/librarymanager/ldf.html
diff --git a/Marlin/src/HAL/AVR/HAL.cpp b/Marlin/src/HAL/AVR/HAL.cpp
index 317d13a54..58d57c8ee 100644
--- a/Marlin/src/HAL/AVR/HAL.cpp
+++ b/Marlin/src/HAL/AVR/HAL.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __AVR__
#include "../../inc/MarlinConfig.h"
diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h
index 025516981..b0e0674c7 100644
--- a/Marlin/src/HAL/AVR/HAL.h
+++ b/Marlin/src/HAL/AVR/HAL.h
@@ -14,7 +14,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*/
#pragma once
@@ -50,7 +50,11 @@
// Defines
// ------------------------
-//#define analogInputToDigitalPin(IO) IO
+// AVR PROGMEM extension for sprintf_P
+#define S_FMT "%S"
+
+// AVR PROGMEM extension for string define
+#define PGMSTR(NAM,STR) const char NAM[] PROGMEM = STR
#ifndef CRITICAL_SECTION_START
#define CRITICAL_SECTION_START() unsigned char _sreg = SREG; cli()
@@ -60,16 +64,10 @@
#define ENABLE_ISRS() sei()
#define DISABLE_ISRS() cli()
-// On AVR this is in math.h?
-//#define square(x) ((x)*(x))
-
// ------------------------
// Types
// ------------------------
-typedef uint16_t hal_timer_t;
-#define HAL_TIMER_TYPE_MAX 0xFFFF
-
typedef int8_t pin_t;
#define SHARED_SERVOS HAS_SERVOS
@@ -142,220 +140,6 @@ extern "C" {
}
#pragma GCC diagnostic pop
-// timers
-#define HAL_TIMER_RATE ((F_CPU) / 8) // i.e., 2MHz or 2.5MHz
-
-#define STEP_TIMER_NUM 1
-#define TEMP_TIMER_NUM 0
-#define PULSE_TIMER_NUM STEP_TIMER_NUM
-
-#define TEMP_TIMER_FREQUENCY ((F_CPU) / 64.0 / 256.0)
-
-#define STEPPER_TIMER_RATE HAL_TIMER_RATE
-#define STEPPER_TIMER_PRESCALE 8
-#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // Cannot be of type double
-
-#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
-#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
-#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
-
-#define ENABLE_STEPPER_DRIVER_INTERRUPT() SBI(TIMSK1, OCIE1A)
-#define DISABLE_STEPPER_DRIVER_INTERRUPT() CBI(TIMSK1, OCIE1A)
-#define STEPPER_ISR_ENABLED() TEST(TIMSK1, OCIE1A)
-
-#define ENABLE_TEMPERATURE_INTERRUPT() SBI(TIMSK0, OCIE0B)
-#define DISABLE_TEMPERATURE_INTERRUPT() CBI(TIMSK0, OCIE0B)
-#define TEMPERATURE_ISR_ENABLED() TEST(TIMSK0, OCIE0B)
-
-FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t) {
- switch (timer_num) {
- case STEP_TIMER_NUM:
- // waveform generation = 0100 = CTC
- SET_WGM(1, CTC_OCRnA);
-
- // output mode = 00 (disconnected)
- SET_COMA(1, NORMAL);
-
- // Set the timer pre-scaler
- // Generally we use a divider of 8, resulting in a 2MHz timer
- // frequency on a 16MHz MCU. If you are going to change this, be
- // sure to regenerate speed_lookuptable.h with
- // create_speed_lookuptable.py
- SET_CS(1, PRESCALER_8); // CS 2 = 1/8 prescaler
-
- // Init Stepper ISR to 122 Hz for quick starting
- // (F_CPU) / (STEPPER_TIMER_PRESCALE) / frequency
- OCR1A = 0x4000;
- TCNT1 = 0;
- break;
-
- case TEMP_TIMER_NUM:
- // Use timer0 for temperature measurement
- // Interleave temperature interrupt with millies interrupt
- OCR0B = 128;
- break;
- }
-}
-
-#define TIMER_OCR_1 OCR1A
-#define TIMER_COUNTER_1 TCNT1
-
-#define TIMER_OCR_0 OCR0A
-#define TIMER_COUNTER_0 TCNT0
-
-#define _CAT(a,V...) a##V
-#define HAL_timer_set_compare(timer, compare) (_CAT(TIMER_OCR_, timer) = compare)
-#define HAL_timer_get_compare(timer) _CAT(TIMER_OCR_, timer)
-#define HAL_timer_get_count(timer) _CAT(TIMER_COUNTER_, timer)
-
-/**
- * On AVR there is no hardware prioritization and preemption of
- * interrupts, so this emulates it. The UART has first priority
- * (otherwise, characters will be lost due to UART overflow).
- * Then: Stepper, Endstops, Temperature, and -finally- all others.
- */
-#define HAL_timer_isr_prologue(TIMER_NUM)
-#define HAL_timer_isr_epilogue(TIMER_NUM)
-
-/* 18 cycles maximum latency */
-#define HAL_STEP_TIMER_ISR() \
-extern "C" void TIMER1_COMPA_vect() __attribute__ ((signal, naked, used, externally_visible)); \
-extern "C" void TIMER1_COMPA_vect_bottom() asm ("TIMER1_COMPA_vect_bottom") __attribute__ ((used, externally_visible, noinline)); \
-void TIMER1_COMPA_vect() { \
- __asm__ __volatile__ ( \
- A("push r16") /* 2 Save R16 */ \
- A("in r16, __SREG__") /* 1 Get SREG */ \
- A("push r16") /* 2 Save SREG into stack */ \
- A("lds r16, %[timsk0]") /* 2 Load into R0 the Temperature timer Interrupt mask register */ \
- A("push r16") /* 2 Save TIMSK0 into the stack */ \
- A("andi r16,~%[msk0]") /* 1 Disable the temperature ISR */ \
- A("sts %[timsk0], r16") /* 2 And set the new value */ \
- A("lds r16, %[timsk1]") /* 2 Load into R0 the stepper timer Interrupt mask register [TIMSK1] */ \
- A("andi r16,~%[msk1]") /* 1 Disable the stepper ISR */ \
- A("sts %[timsk1], r16") /* 2 And set the new value */ \
- A("push r16") /* 2 Save TIMSK1 into stack */ \
- A("in r16, 0x3B") /* 1 Get RAMPZ register */ \
- A("push r16") /* 2 Save RAMPZ into stack */ \
- A("in r16, 0x3C") /* 1 Get EIND register */ \
- A("push r0") /* C runtime can modify all the following registers without restoring them */ \
- A("push r1") \
- A("push r18") \
- A("push r19") \
- A("push r20") \
- A("push r21") \
- A("push r22") \
- A("push r23") \
- A("push r24") \
- A("push r25") \
- A("push r26") \
- A("push r27") \
- A("push r30") \
- A("push r31") \
- A("clr r1") /* C runtime expects this register to be 0 */ \
- A("call TIMER1_COMPA_vect_bottom") /* Call the bottom handler - No inlining allowed, otherwise registers used are not saved */ \
- A("pop r31") \
- A("pop r30") \
- A("pop r27") \
- A("pop r26") \
- A("pop r25") \
- A("pop r24") \
- A("pop r23") \
- A("pop r22") \
- A("pop r21") \
- A("pop r20") \
- A("pop r19") \
- A("pop r18") \
- A("pop r1") \
- A("pop r0") \
- A("out 0x3C, r16") /* 1 Restore EIND register */ \
- A("pop r16") /* 2 Get the original RAMPZ register value */ \
- A("out 0x3B, r16") /* 1 Restore RAMPZ register to its original value */ \
- A("pop r16") /* 2 Get the original TIMSK1 value but with stepper ISR disabled */ \
- A("ori r16,%[msk1]") /* 1 Reenable the stepper ISR */ \
- A("cli") /* 1 Disable global interrupts - Reenabling Stepper ISR can reenter amd temperature can reenter, and we want that, if it happens, after this ISR has ended */ \
- A("sts %[timsk1], r16") /* 2 And restore the old value - This reenables the stepper ISR */ \
- A("pop r16") /* 2 Get the temperature timer Interrupt mask register [TIMSK0] */ \
- A("sts %[timsk0], r16") /* 2 And restore the old value - This reenables the temperature ISR */ \
- A("pop r16") /* 2 Get the old SREG value */ \
- A("out __SREG__, r16") /* 1 And restore the SREG value */ \
- A("pop r16") /* 2 Restore R16 value */ \
- A("reti") /* 4 Return from interrupt */ \
- : \
- : [timsk0] "i" ((uint16_t)&TIMSK0), \
- [timsk1] "i" ((uint16_t)&TIMSK1), \
- [msk0] "M" ((uint8_t)(1<.
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/AVR/MarlinSerial.cpp b/Marlin/src/HAL/AVR/MarlinSerial.cpp
index 350d0f302..f41ef2011 100644
--- a/Marlin/src/HAL/AVR/MarlinSerial.cpp
+++ b/Marlin/src/HAL/AVR/MarlinSerial.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -43,6 +43,10 @@
#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;
@@ -131,6 +135,18 @@
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)
+ if (page_manager.maybe_store_rxd_char(c)) return;
+ #endif
+
// 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.
@@ -142,14 +158,6 @@
// Get the next element
ring_buffer_pos_t i = (ring_buffer_pos_t)(h + 1) & (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;
-
- // Read the character from the USART
- uint8_t 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
diff --git a/Marlin/src/HAL/AVR/MarlinSerial.h b/Marlin/src/HAL/AVR/MarlinSerial.h
index cd7aad90a..1182d86ac 100644
--- a/Marlin/src/HAL/AVR/MarlinSerial.h
+++ b/Marlin/src/HAL/AVR/MarlinSerial.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -299,12 +299,12 @@
template
struct MarlinInternalSerialCfg {
static constexpr int PORT = serial;
- static constexpr unsigned int RX_SIZE = 128;
- static constexpr unsigned int TX_SIZE = 48;
+ 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 = HAS_DGUS_LCD && ENABLED(DGUS_SERIAL_STATS_RX_BUFFER_OVERRUNS);
+ 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;
};
diff --git a/Marlin/src/HAL/AVR/Servo.cpp b/Marlin/src/HAL/AVR/Servo.cpp
index 02c131bd4..66ed993c6 100644
--- a/Marlin/src/HAL/AVR/Servo.cpp
+++ b/Marlin/src/HAL/AVR/Servo.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -59,7 +59,6 @@
#include
-#include "../shared/Marduino.h"
#include "../shared/servo.h"
#include "../shared/servo_private.h"
diff --git a/Marlin/src/HAL/AVR/ServoTimers.h b/Marlin/src/HAL/AVR/ServoTimers.h
index 86007fd10..564714df6 100644
--- a/Marlin/src/HAL/AVR/ServoTimers.h
+++ b/Marlin/src/HAL/AVR/ServoTimers.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/AVR/eeprom.cpp b/Marlin/src/HAL/AVR/eeprom.cpp
index ee416b7a1..c7906985e 100644
--- a/Marlin/src/HAL/AVR/eeprom.cpp
+++ b/Marlin/src/HAL/AVR/eeprom.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#ifdef __AVR__
@@ -25,9 +25,18 @@
#if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE)
+/**
+ * PersistentStore for Arduino-style EEPROM interface
+ * with implementations supplied by the framework.
+ */
+
#include "../shared/eeprom_api.h"
-bool PersistentStore::access_start() { return true; }
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE size_t(E2END + 1)
+#endif
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+bool PersistentStore::access_start() { return true; }
bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
@@ -46,7 +55,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
crc16(crc, &v, 1);
pos++;
value++;
- };
+ }
return false;
}
@@ -61,7 +70,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
return false; // always assume success for AVR's
}
-size_t PersistentStore::capacity() { return E2END + 1; }
-
#endif // EEPROM_SETTINGS || SD_FIRMWARE_UPDATE
#endif // __AVR__
diff --git a/Marlin/src/HAL/AVR/endstop_interrupts.h b/Marlin/src/HAL/AVR/endstop_interrupts.h
index 8f89c69ba..ae9a605ac 100644
--- a/Marlin/src/HAL/AVR/endstop_interrupts.h
+++ b/Marlin/src/HAL/AVR/endstop_interrupts.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/AVR/fast_pwm.cpp b/Marlin/src/HAL/AVR/fast_pwm.cpp
index 42e7cc3f1..29866bccf 100644
--- a/Marlin/src/HAL/AVR/fast_pwm.cpp
+++ b/Marlin/src/HAL/AVR/fast_pwm.cpp
@@ -16,14 +16,14 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#ifdef __AVR__
#include "../../inc/MarlinConfigPre.h"
-#if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_PWM
+#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM
#include "HAL.h"
@@ -274,9 +274,9 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255
else
top = *timer.ICRn; // top = ICRn
- _SET_OCRnQ(timer.OCRnQ, timer.q, v * float(top / v_size)); // Scale 8/16-bit v to top value
+ _SET_OCRnQ(timer.OCRnQ, timer.q, v * float(top) / float(v_size)); // Scale 8/16-bit v to top value
}
}
-#endif // FAST_PWM_FAN || SPINDLE_LASER_PWM
+#endif // NEEDS_HARDWARE_PWM
#endif // __AVR__
diff --git a/Marlin/src/HAL/AVR/fastio.cpp b/Marlin/src/HAL/AVR/fastio.cpp
index 9f70b50f7..b51d7f976 100644
--- a/Marlin/src/HAL/AVR/fastio.cpp
+++ b/Marlin/src/HAL/AVR/fastio.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -234,5 +234,55 @@ uint8_t extDigitalRead(const int8_t pin) {
}
}
+#if 0
+/**
+ * Set Timer 5 PWM frequency in Hz, from 3.8Hz up to ~16MHz
+ * with a minimum resolution of 100 steps.
+ *
+ * DC values -1.0 to 1.0. Negative duty cycle inverts the pulse.
+ */
+uint16_t set_pwm_frequency_hz(const float &hz, const float dca, const float dcb, const float dcc) {
+ float count = 0;
+ if (hz > 0 && (dca || dcb || dcc)) {
+ count = float(F_CPU) / hz; // 1x prescaler, TOP for 16MHz base freq.
+ uint16_t prescaler; // Range of 30.5Hz (65535) 64.5KHz (>31)
+
+ if (count >= 255. * 256.) { prescaler = 1024; SET_CS(5, PRESCALER_1024); }
+ else if (count >= 255. * 64.) { prescaler = 256; SET_CS(5, PRESCALER_256); }
+ else if (count >= 255. * 8.) { prescaler = 64; SET_CS(5, PRESCALER_64); }
+ else if (count >= 255.) { prescaler = 8; SET_CS(5, PRESCALER_8); }
+ else { prescaler = 1; SET_CS(5, PRESCALER_1); }
+
+ count /= float(prescaler);
+ const float pwm_top = round(count); // Get the rounded count
+
+ ICR5 = (uint16_t)pwm_top - 1; // Subtract 1 for TOP
+ OCR5A = pwm_top * ABS(dca); // Update and scale DCs
+ OCR5B = pwm_top * ABS(dcb);
+ OCR5C = pwm_top * ABS(dcc);
+ _SET_COM(5, A, dca ? (dca < 0 ? COM_SET_CLEAR : COM_CLEAR_SET) : COM_NORMAL); // Set compare modes
+ _SET_COM(5, B, dcb ? (dcb < 0 ? COM_SET_CLEAR : COM_CLEAR_SET) : COM_NORMAL);
+ _SET_COM(5, C, dcc ? (dcc < 0 ? COM_SET_CLEAR : COM_CLEAR_SET) : COM_NORMAL);
+
+ SET_WGM(5, FAST_PWM_ICRn); // Fast PWM with ICR5 as TOP
+
+ //SERIAL_ECHOLNPGM("Timer 5 Settings:");
+ //SERIAL_ECHOLNPAIR(" Prescaler=", prescaler);
+ //SERIAL_ECHOLNPAIR(" TOP=", ICR5);
+ //SERIAL_ECHOLNPAIR(" OCR5A=", OCR5A);
+ //SERIAL_ECHOLNPAIR(" OCR5B=", OCR5B);
+ //SERIAL_ECHOLNPAIR(" OCR5C=", OCR5C);
+ }
+ else {
+ // Restore the default for Timer 5
+ SET_WGM(5, PWM_PC_8); // PWM 8-bit (Phase Correct)
+ SET_COMS(5, NORMAL, NORMAL, NORMAL); // Do nothing
+ SET_CS(5, PRESCALER_64); // 16MHz / 64 = 250KHz
+ OCR5A = OCR5B = OCR5C = 0;
+ }
+ return round(count);
+}
+#endif
+
#endif // FASTIO_EXT_START
#endif // __AVR__
diff --git a/Marlin/src/HAL/AVR/fastio.h b/Marlin/src/HAL/AVR/fastio.h
index 787275271..bd6935aaf 100644
--- a/Marlin/src/HAL/AVR/fastio.h
+++ b/Marlin/src/HAL/AVR/fastio.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/AVR/fastio/fastio_1280.h b/Marlin/src/HAL/AVR/fastio/fastio_1280.h
index b62156caa..f482f823e 100644
--- a/Marlin/src/HAL/AVR/fastio/fastio_1280.h
+++ b/Marlin/src/HAL/AVR/fastio/fastio_1280.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/AVR/fastio/fastio_1281.h b/Marlin/src/HAL/AVR/fastio/fastio_1281.h
index 7552540ff..e0bc5e299 100644
--- a/Marlin/src/HAL/AVR/fastio/fastio_1281.h
+++ b/Marlin/src/HAL/AVR/fastio/fastio_1281.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/AVR/fastio/fastio_168.h b/Marlin/src/HAL/AVR/fastio/fastio_168.h
index 549e0246d..8cfdd1e8f 100644
--- a/Marlin/src/HAL/AVR/fastio/fastio_168.h
+++ b/Marlin/src/HAL/AVR/fastio/fastio_168.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/AVR/fastio/fastio_644.h b/Marlin/src/HAL/AVR/fastio/fastio_644.h
index 3a48c109e..f4a9427e0 100644
--- a/Marlin/src/HAL/AVR/fastio/fastio_644.h
+++ b/Marlin/src/HAL/AVR/fastio/fastio_644.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h b/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h
index 23d16a20e..51d400b70 100644
--- a/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h
+++ b/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h b/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h
+++ b/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/AVR/inc/Conditionals_adv.h b/Marlin/src/HAL/AVR/inc/Conditionals_adv.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/AVR/inc/Conditionals_adv.h
+++ b/Marlin/src/HAL/AVR/inc/Conditionals_adv.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/AVR/inc/Conditionals_post.h b/Marlin/src/HAL/AVR/inc/Conditionals_post.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/AVR/inc/Conditionals_post.h
+++ b/Marlin/src/HAL/AVR/inc/Conditionals_post.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/AVR/inc/SanityCheck.h b/Marlin/src/HAL/AVR/inc/SanityCheck.h
index 1c7c68f21..e55e45b73 100644
--- a/Marlin/src/HAL/AVR/inc/SanityCheck.h
+++ b/Marlin/src/HAL/AVR/inc/SanityCheck.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -25,16 +25,6 @@
* Test AVR-specific configuration values for errors at compile-time.
*/
-/**
- * Digipot requirement
- */
- #if ENABLED(DIGIPOT_MCP4018)
- #if !defined(DIGIPOTS_I2C_SDA_X) || !defined(DIGIPOTS_I2C_SDA_Y) || !defined(DIGIPOTS_I2C_SDA_Z) \
- || !defined(DIGIPOTS_I2C_SDA_E0) || !defined(DIGIPOTS_I2C_SDA_E1)
- #error "DIGIPOT_MCP4018 requires DIGIPOTS_I2C_SDA_* pins to be defined."
- #endif
-#endif
-
/**
* Checks for FAST PWM
*/
@@ -51,15 +41,17 @@
#elif NUM_SERVOS > 0 && (WITHIN(SPINDLE_LASER_PWM_PIN, 2, 3) || SPINDLE_LASER_PWM_PIN == 5)
#error "Counter/Timer for SPINDLE_LASER_PWM_PIN is used by the servo system."
#endif
+#elif defined(SPINDLE_LASER_FREQUENCY)
+ #error "SPINDLE_LASER_FREQUENCY requires SPINDLE_LASER_PWM."
#endif
/**
* The Trinamic library includes SoftwareSerial.h, leading to a compile error.
*/
-#if HAS_TRINAMIC_CONFIG && ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
+#if BOTH(HAS_TRINAMIC_CONFIG, ENDSTOP_INTERRUPTS_FEATURE)
#error "TMCStepper includes SoftwareSerial.h which is incompatible with ENDSTOP_INTERRUPTS_FEATURE. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif
-#if HAS_TMC_SW_SERIAL && ENABLED(MONITOR_DRIVER_STATUS)
+#if BOTH(HAS_TMC_SW_SERIAL, MONITOR_DRIVER_STATUS)
#error "MONITOR_DRIVER_STATUS causes performance issues when used with SoftwareSerial-connected drivers. Disable MONITOR_DRIVER_STATUS or use hardware serial to continue."
#endif
diff --git a/Marlin/src/HAL/AVR/math.h b/Marlin/src/HAL/AVR/math.h
index e8be0a04b..7ede4accc 100644
--- a/Marlin/src/HAL/AVR/math.h
+++ b/Marlin/src/HAL/AVR/math.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/AVR/pinsDebug.h b/Marlin/src/HAL/AVR/pinsDebug.h
index fbd2e084f..d73f520d1 100644
--- a/Marlin/src/HAL/AVR/pinsDebug.h
+++ b/Marlin/src/HAL/AVR/pinsDebug.h
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h b/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h
index f6da07774..051972a86 100644
--- a/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h
+++ b/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/AVR/pinsDebug_plus_70.h b/Marlin/src/HAL/AVR/pinsDebug_plus_70.h
index 6e7b8fbaa..46c03088d 100644
--- a/Marlin/src/HAL/AVR/pinsDebug_plus_70.h
+++ b/Marlin/src/HAL/AVR/pinsDebug_plus_70.h
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/AVR/spi_pins.h b/Marlin/src/HAL/AVR/spi_pins.h
index daaebb76d..f3fa78e2b 100644
--- a/Marlin/src/HAL/AVR/spi_pins.h
+++ b/Marlin/src/HAL/AVR/spi_pins.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/AVR/timers.h b/Marlin/src/HAL/AVR/timers.h
new file mode 100644
index 000000000..6c40d3220
--- /dev/null
+++ b/Marlin/src/HAL/AVR/timers.h
@@ -0,0 +1,259 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ */
+#pragma once
+
+#include
+
+// ------------------------
+// Types
+// ------------------------
+
+typedef uint16_t hal_timer_t;
+#define HAL_TIMER_TYPE_MAX 0xFFFF
+
+// ------------------------
+// Defines
+// ------------------------
+
+#define HAL_TIMER_RATE ((F_CPU) / 8) // i.e., 2MHz or 2.5MHz
+
+#ifndef STEP_TIMER_NUM
+ #define STEP_TIMER_NUM 1
+#endif
+#ifndef PULSE_TIMER_NUM
+ #define PULSE_TIMER_NUM STEP_TIMER_NUM
+#endif
+#ifndef TEMP_TIMER_NUM
+ #define TEMP_TIMER_NUM 0
+#endif
+
+#define TEMP_TIMER_FREQUENCY ((F_CPU) / 64.0 / 256.0)
+
+#define STEPPER_TIMER_RATE HAL_TIMER_RATE
+#define STEPPER_TIMER_PRESCALE 8
+#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // Cannot be of type double
+
+#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
+#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
+#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
+
+#define ENABLE_STEPPER_DRIVER_INTERRUPT() SBI(TIMSK1, OCIE1A)
+#define DISABLE_STEPPER_DRIVER_INTERRUPT() CBI(TIMSK1, OCIE1A)
+#define STEPPER_ISR_ENABLED() TEST(TIMSK1, OCIE1A)
+
+#define ENABLE_TEMPERATURE_INTERRUPT() SBI(TIMSK0, OCIE0B)
+#define DISABLE_TEMPERATURE_INTERRUPT() CBI(TIMSK0, OCIE0B)
+#define TEMPERATURE_ISR_ENABLED() TEST(TIMSK0, OCIE0B)
+
+FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t) {
+ switch (timer_num) {
+ case STEP_TIMER_NUM:
+ // waveform generation = 0100 = CTC
+ SET_WGM(1, CTC_OCRnA);
+
+ // output mode = 00 (disconnected)
+ SET_COMA(1, NORMAL);
+
+ // Set the timer pre-scaler
+ // Generally we use a divider of 8, resulting in a 2MHz timer
+ // frequency on a 16MHz MCU. If you are going to change this, be
+ // sure to regenerate speed_lookuptable.h with
+ // create_speed_lookuptable.py
+ SET_CS(1, PRESCALER_8); // CS 2 = 1/8 prescaler
+
+ // Init Stepper ISR to 122 Hz for quick starting
+ // (F_CPU) / (STEPPER_TIMER_PRESCALE) / frequency
+ OCR1A = 0x4000;
+ TCNT1 = 0;
+ break;
+
+ case TEMP_TIMER_NUM:
+ // Use timer0 for temperature measurement
+ // Interleave temperature interrupt with millies interrupt
+ OCR0B = 128;
+ break;
+ }
+}
+
+#define TIMER_OCR_1 OCR1A
+#define TIMER_COUNTER_1 TCNT1
+
+#define TIMER_OCR_0 OCR0A
+#define TIMER_COUNTER_0 TCNT0
+
+#define _CAT(a,V...) a##V
+#define HAL_timer_set_compare(timer, compare) (_CAT(TIMER_OCR_, timer) = compare)
+#define HAL_timer_get_compare(timer) _CAT(TIMER_OCR_, timer)
+#define HAL_timer_get_count(timer) _CAT(TIMER_COUNTER_, timer)
+
+/**
+ * On AVR there is no hardware prioritization and preemption of
+ * interrupts, so this emulates it. The UART has first priority
+ * (otherwise, characters will be lost due to UART overflow).
+ * Then: Stepper, Endstops, Temperature, and -finally- all others.
+ */
+#define HAL_timer_isr_prologue(TIMER_NUM)
+#define HAL_timer_isr_epilogue(TIMER_NUM)
+
+/* 18 cycles maximum latency */
+#ifndef HAL_STEP_TIMER_ISR
+
+#define HAL_STEP_TIMER_ISR() \
+extern "C" void TIMER1_COMPA_vect() __attribute__ ((signal, naked, used, externally_visible)); \
+extern "C" void TIMER1_COMPA_vect_bottom() asm ("TIMER1_COMPA_vect_bottom") __attribute__ ((used, externally_visible, noinline)); \
+void TIMER1_COMPA_vect() { \
+ __asm__ __volatile__ ( \
+ A("push r16") /* 2 Save R16 */ \
+ A("in r16, __SREG__") /* 1 Get SREG */ \
+ A("push r16") /* 2 Save SREG into stack */ \
+ A("lds r16, %[timsk0]") /* 2 Load into R0 the Temperature timer Interrupt mask register */ \
+ A("push r16") /* 2 Save TIMSK0 into the stack */ \
+ A("andi r16,~%[msk0]") /* 1 Disable the temperature ISR */ \
+ A("sts %[timsk0], r16") /* 2 And set the new value */ \
+ A("lds r16, %[timsk1]") /* 2 Load into R0 the stepper timer Interrupt mask register [TIMSK1] */ \
+ A("andi r16,~%[msk1]") /* 1 Disable the stepper ISR */ \
+ A("sts %[timsk1], r16") /* 2 And set the new value */ \
+ A("push r16") /* 2 Save TIMSK1 into stack */ \
+ A("in r16, 0x3B") /* 1 Get RAMPZ register */ \
+ A("push r16") /* 2 Save RAMPZ into stack */ \
+ A("in r16, 0x3C") /* 1 Get EIND register */ \
+ A("push r0") /* C runtime can modify all the following registers without restoring them */ \
+ A("push r1") \
+ A("push r18") \
+ A("push r19") \
+ A("push r20") \
+ A("push r21") \
+ A("push r22") \
+ A("push r23") \
+ A("push r24") \
+ A("push r25") \
+ A("push r26") \
+ A("push r27") \
+ A("push r30") \
+ A("push r31") \
+ A("clr r1") /* C runtime expects this register to be 0 */ \
+ A("call TIMER1_COMPA_vect_bottom") /* Call the bottom handler - No inlining allowed, otherwise registers used are not saved */ \
+ A("pop r31") \
+ A("pop r30") \
+ A("pop r27") \
+ A("pop r26") \
+ A("pop r25") \
+ A("pop r24") \
+ A("pop r23") \
+ A("pop r22") \
+ A("pop r21") \
+ A("pop r20") \
+ A("pop r19") \
+ A("pop r18") \
+ A("pop r1") \
+ A("pop r0") \
+ A("out 0x3C, r16") /* 1 Restore EIND register */ \
+ A("pop r16") /* 2 Get the original RAMPZ register value */ \
+ A("out 0x3B, r16") /* 1 Restore RAMPZ register to its original value */ \
+ A("pop r16") /* 2 Get the original TIMSK1 value but with stepper ISR disabled */ \
+ A("ori r16,%[msk1]") /* 1 Reenable the stepper ISR */ \
+ A("cli") /* 1 Disable global interrupts - Reenabling Stepper ISR can reenter amd temperature can reenter, and we want that, if it happens, after this ISR has ended */ \
+ A("sts %[timsk1], r16") /* 2 And restore the old value - This reenables the stepper ISR */ \
+ A("pop r16") /* 2 Get the temperature timer Interrupt mask register [TIMSK0] */ \
+ A("sts %[timsk0], r16") /* 2 And restore the old value - This reenables the temperature ISR */ \
+ A("pop r16") /* 2 Get the old SREG value */ \
+ A("out __SREG__, r16") /* 1 And restore the SREG value */ \
+ A("pop r16") /* 2 Restore R16 value */ \
+ A("reti") /* 4 Return from interrupt */ \
+ : \
+ : [timsk0] "i" ((uint16_t)&TIMSK0), \
+ [timsk1] "i" ((uint16_t)&TIMSK1), \
+ [msk0] "M" ((uint8_t)(1<.
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/AVR/watchdog.cpp b/Marlin/src/HAL/AVR/watchdog.cpp
index e35a70f2c..3f10c4adf 100644
--- a/Marlin/src/HAL/AVR/watchdog.cpp
+++ b/Marlin/src/HAL/AVR/watchdog.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __AVR__
#include "../../inc/MarlinConfig.h"
diff --git a/Marlin/src/HAL/AVR/watchdog.h b/Marlin/src/HAL/AVR/watchdog.h
index 57dfcfc0b..a16c88b35 100644
--- a/Marlin/src/HAL/AVR/watchdog.h
+++ b/Marlin/src/HAL/AVR/watchdog.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/DUE/DebugMonitor.cpp b/Marlin/src/HAL/DUE/DebugMonitor.cpp
index 3ed9873e6..79759151d 100644
--- a/Marlin/src/HAL/DUE/DebugMonitor.cpp
+++ b/Marlin/src/HAL/DUE/DebugMonitor.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef ARDUINO_ARCH_SAM
#include "../../core/macros.h"
diff --git a/Marlin/src/HAL/DUE/HAL.cpp b/Marlin/src/HAL/DUE/HAL.cpp
index cb381ff4b..f2bf4ebbf 100644
--- a/Marlin/src/HAL/DUE/HAL.cpp
+++ b/Marlin/src/HAL/DUE/HAL.cpp
@@ -14,7 +14,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*/
/**
diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h
index 42f6f175f..31409c76d 100644
--- a/Marlin/src/HAL/DUE/HAL.h
+++ b/Marlin/src/HAL/DUE/HAL.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -30,11 +30,11 @@
#define CPU_32_BIT
#include "../shared/Marduino.h"
+#include "../shared/eeprom_if.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio.h"
#include "watchdog.h"
-#include "timers.h"
#include
@@ -130,14 +130,6 @@ void sei(); // Enable interrupts
void HAL_clear_reset_source(); // clear reset reason
uint8_t HAL_get_reset_source(); // get reset reason
-//
-// EEPROM
-//
-void eeprom_write_byte(uint8_t *pos, unsigned char value);
-uint8_t eeprom_read_byte(uint8_t *pos);
-void eeprom_read_block (void *__dst, const void *__src, size_t __n);
-void eeprom_update_block (const void *__src, void *__dst, size_t __n);
-
//
// ADC
//
@@ -151,8 +143,9 @@ extern uint16_t HAL_adc_result; // result of last ADC conversion
inline void HAL_adc_init() {}//todo
-#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch)
+#define HAL_ADC_VREF 3.3
#define HAL_ADC_RESOLUTION 10
+#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch)
#define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true
diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp
index 97a6fa05a..6d8f7ef81 100644
--- a/Marlin/src/HAL/DUE/HAL_SPI.cpp
+++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/DUE/InterruptVectors.cpp b/Marlin/src/HAL/DUE/InterruptVectors.cpp
index 7964f2d1f..e4e0ce99f 100644
--- a/Marlin/src/HAL/DUE/InterruptVectors.cpp
+++ b/Marlin/src/HAL/DUE/InterruptVectors.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/DUE/InterruptVectors.h b/Marlin/src/HAL/DUE/InterruptVectors.h
index 534cd17f4..6faeb34b7 100644
--- a/Marlin/src/HAL/DUE/InterruptVectors.h
+++ b/Marlin/src/HAL/DUE/InterruptVectors.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/DUE/MarlinSerial.cpp b/Marlin/src/HAL/DUE/MarlinSerial.cpp
index d114c7598..c9a372eeb 100644
--- a/Marlin/src/HAL/DUE/MarlinSerial.cpp
+++ b/Marlin/src/HAL/DUE/MarlinSerial.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/DUE/MarlinSerial.h b/Marlin/src/HAL/DUE/MarlinSerial.h
index fa6a2c7d1..dfafa1514 100644
--- a/Marlin/src/HAL/DUE/MarlinSerial.h
+++ b/Marlin/src/HAL/DUE/MarlinSerial.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp b/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp
index 7a020bbaf..a41dbfeb7 100644
--- a/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp
+++ b/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -73,9 +73,7 @@ int MarlinSerialUSB::peek() {
pending_char = udi_cdc_getc();
- #if ENABLED(EMERGENCY_PARSER)
- emergency_parser.update(emergency_state, (char)pending_char);
- #endif
+ TERN_(EMERGENCY_PARSER, emergency_parser.update(emergency_state, (char)pending_char));
return pending_char;
}
@@ -97,9 +95,7 @@ int MarlinSerialUSB::read() {
int c = udi_cdc_getc();
- #if ENABLED(EMERGENCY_PARSER)
- emergency_parser.update(emergency_state, (char)c);
- #endif
+ TERN_(EMERGENCY_PARSER, emergency_parser.update(emergency_state, (char)c));
return c;
}
diff --git a/Marlin/src/HAL/DUE/MarlinSerialUSB.h b/Marlin/src/HAL/DUE/MarlinSerialUSB.h
index 9aece901b..2e3622e55 100644
--- a/Marlin/src/HAL/DUE/MarlinSerialUSB.h
+++ b/Marlin/src/HAL/DUE/MarlinSerialUSB.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/DUE/Servo.cpp b/Marlin/src/HAL/DUE/Servo.cpp
index 266158bbc..5524aa9ce 100644
--- a/Marlin/src/HAL/DUE/Servo.cpp
+++ b/Marlin/src/HAL/DUE/Servo.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -44,7 +44,6 @@
#if HAS_SERVOS
-#include "../shared/Marduino.h"
#include "../shared/servo.h"
#include "../shared/servo_private.h"
diff --git a/Marlin/src/HAL/DUE/Tone.cpp b/Marlin/src/HAL/DUE/Tone.cpp
index 44bb52b42..9beb60222 100644
--- a/Marlin/src/HAL/DUE/Tone.cpp
+++ b/Marlin/src/HAL/DUE/Tone.cpp
@@ -18,7 +18,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -31,7 +31,6 @@
#include "../../inc/MarlinConfig.h"
#include "HAL.h"
-#include "timers.h"
static pin_t tone_pin;
volatile static int32_t toggles;
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 0fb8a782e..2ef7011b1 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
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp
index 01320ba9b..47060d6a5 100644
--- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp
+++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
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 c4816c3db..54c244d4f 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
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
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 96b7a1f61..960df1bd8 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
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.h b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.h
index e0f15bfd8..f076c503c 100644
--- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.h
+++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/DUE/EepromEmulation.cpp b/Marlin/src/HAL/DUE/eeprom_flash.cpp
similarity index 88%
rename from Marlin/src/HAL/DUE/EepromEmulation.cpp
rename to Marlin/src/HAL/DUE/eeprom_flash.cpp
index 66af50cfd..d98f06039 100644
--- a/Marlin/src/HAL/DUE/EepromEmulation.cpp
+++ b/Marlin/src/HAL/DUE/eeprom_flash.cpp
@@ -1,9 +1,10 @@
/**
* Marlin 3D Printer Firmware
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
- * Based on Sprinter and grbl.
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
+ * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
+ * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@@ -16,9 +17,14 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
+#ifdef ARDUINO_ARCH_SAM
+
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(FLASH_EEPROM_EMULATION)
/* EEPROM emulation over flash with reduced wear
*
@@ -50,14 +56,7 @@
*
*/
-#ifdef ARDUINO_ARCH_SAM
-
-#include "../../inc/MarlinConfig.h"
-
-#if ENABLED(FLASH_EEPROM_EMULATION)
-
-#include "../shared/Marduino.h"
-#include "../shared/eeprom_api.h"
+//#define EE_EMU_DEBUG
#define EEPROMSize 4096
#define PagesPerGroup 128
@@ -134,15 +133,18 @@ static uint8_t buffer[256] = {0}, // The RAM buffer to accumulate writes
curPage = 0, // Current FLASH page inside the group
curGroup = 0xFF; // Current FLASH group
-//#define EE_EMU_DEBUG
-#ifdef EE_EMU_DEBUG
- static void ee_Dump(int page,const void* data) {
+#define DEBUG_OUT ENABLED(EE_EMU_DEBUG)
+#include "../../core/debug_out.h"
+
+static void ee_Dump(const int page, const void* data) {
+
+ #ifdef EE_EMU_DEBUG
const uint8_t* c = (const uint8_t*) data;
char buffer[80];
sprintf_P(buffer, PSTR("Page: %d (0x%04x)\n"), page, page);
- SERIAL_ECHO(buffer);
+ DEBUG_ECHO(buffer);
char* p = &buffer[0];
for (int i = 0; i< PageSize; ++i) {
@@ -152,12 +154,16 @@ static uint8_t buffer[256] = {0}, // The RAM buffer to accumulate writes
if ((i & 0xF) == 0xF) {
*p++ = '\n';
*p = 0;
- SERIAL_ECHO(buffer);
+ DEBUG_ECHO(buffer);
p = &buffer[0];
}
}
- }
-#endif
+
+ #else
+ UNUSED(page);
+ UNUSED(data);
+ #endif
+}
/* Flash Writing Protection Key */
#define FWP_KEY 0x5Au
@@ -170,17 +176,16 @@ static uint8_t buffer[256] = {0}, // The RAM buffer to accumulate writes
#define EEFC_ERROR_FLAGS (EEFC_FSR_FLOCKE | EEFC_FSR_FCMDE)
#endif
-
/**
* Writes the contents of the specified page (no previous erase)
* @param page (page #)
* @param data (pointer to the data buffer)
*/
__attribute__ ((long_call, section (".ramfunc")))
-static bool ee_PageWrite(uint16_t page,const void* data) {
+static bool ee_PageWrite(uint16_t page, const void* data) {
uint16_t i;
- uint32_t addrflash = ((uint32_t)getFlashStorage(page));
+ uint32_t addrflash = uint32_t(getFlashStorage(page));
// Read the flash contents
uint32_t pageContents[PageSize>>2];
@@ -195,13 +200,11 @@ static bool ee_PageWrite(uint16_t page,const void* data) {
for (i = 0; i > 2; i++)
pageContents[i] = (((uint32_t*)data)[i]) | (~(pageContents[i] ^ ((uint32_t*)data)[i]));
- #ifdef EE_EMU_DEBUG
- SERIAL_ECHO_START();
- SERIAL_ECHOLNPAIR("EEPROM PageWrite ", page);
- SERIAL_ECHOLNPAIR(" in FLASH address ", (uint32_t)addrflash);
- SERIAL_ECHOLNPAIR(" base address ", (uint32_t)getFlashStorage(0));
- SERIAL_FLUSH();
- #endif
+ DEBUG_ECHO_START();
+ DEBUG_ECHOLNPAIR("EEPROM PageWrite ", page);
+ DEBUG_ECHOLNPAIR(" in FLASH address ", (uint32_t)addrflash);
+ DEBUG_ECHOLNPAIR(" base address ", (uint32_t)getFlashStorage(0));
+ DEBUG_FLUSH();
// Get the page relative to the start of the EFC controller, and the EFC controller to use
Efc *efc;
@@ -243,10 +246,8 @@ static bool ee_PageWrite(uint16_t page,const void* data) {
// Reenable interrupts
__enable_irq();
- #ifdef EE_EMU_DEBUG
- SERIAL_ECHO_START();
- SERIAL_ECHOLNPAIR("EEPROM Unlock failure for page ", page);
- #endif
+ DEBUG_ECHO_START();
+ DEBUG_ECHOLNPAIR("EEPROM Unlock failure for page ", page);
return false;
}
@@ -270,10 +271,9 @@ static bool ee_PageWrite(uint16_t page,const void* data) {
// Reenable interrupts
__enable_irq();
- #ifdef EE_EMU_DEBUG
- SERIAL_ECHO_START();
- SERIAL_ECHOLNPAIR("EEPROM Write failure for page ", page);
- #endif
+ DEBUG_ECHO_START();
+ DEBUG_ECHOLNPAIR("EEPROM Write failure for page ", page);
+
return false;
}
@@ -287,11 +287,11 @@ static bool ee_PageWrite(uint16_t page,const void* data) {
if (memcmp(getFlashStorage(page),data,PageSize)) {
#ifdef EE_EMU_DEBUG
- SERIAL_ECHO_START();
- SERIAL_ECHOLNPAIR("EEPROM Verify Write failure for page ", page);
+ DEBUG_ECHO_START();
+ DEBUG_ECHOLNPAIR("EEPROM Verify Write failure for page ", page);
- ee_Dump( page,(uint32_t *) addrflash);
- ee_Dump(-page,data);
+ ee_Dump( page, (uint32_t *)addrflash);
+ ee_Dump(-page, data);
// Calculate count of changed bits
uint32_t* p1 = (uint32_t*)addrflash;
@@ -307,7 +307,7 @@ static bool ee_PageWrite(uint16_t page,const void* data) {
}
}
}
- SERIAL_ECHOLNPAIR("--> Differing bits: ", count);
+ DEBUG_ECHOLNPAIR("--> Differing bits: ", count);
#endif
return false;
@@ -324,15 +324,13 @@ __attribute__ ((long_call, section (".ramfunc")))
static bool ee_PageErase(uint16_t page) {
uint16_t i;
- uint32_t addrflash = ((uint32_t)getFlashStorage(page));
+ uint32_t addrflash = uint32_t(getFlashStorage(page));
- #ifdef EE_EMU_DEBUG
- SERIAL_ECHO_START();
- SERIAL_ECHOLNPAIR("EEPROM PageErase ", page);
- SERIAL_ECHOLNPAIR(" in FLASH address ", (uint32_t)addrflash);
- SERIAL_ECHOLNPAIR(" base address ", (uint32_t)getFlashStorage(0));
- SERIAL_FLUSH();
- #endif
+ DEBUG_ECHO_START();
+ DEBUG_ECHOLNPAIR("EEPROM PageErase ", page);
+ DEBUG_ECHOLNPAIR(" in FLASH address ", (uint32_t)addrflash);
+ DEBUG_ECHOLNPAIR(" base address ", (uint32_t)getFlashStorage(0));
+ DEBUG_FLUSH();
// Get the page relative to the start of the EFC controller, and the EFC controller to use
Efc *efc;
@@ -373,10 +371,9 @@ static bool ee_PageErase(uint16_t page) {
// Reenable interrupts
__enable_irq();
- #ifdef EE_EMU_DEBUG
- SERIAL_ECHO_START();
- SERIAL_ECHOLNPAIR("EEPROM Unlock failure for page ",page);
- #endif
+ DEBUG_ECHO_START();
+ DEBUG_ECHOLNPAIR("EEPROM Unlock failure for page ",page);
+
return false;
}
@@ -398,10 +395,9 @@ static bool ee_PageErase(uint16_t page) {
// Reenable interrupts
__enable_irq();
- #ifdef EE_EMU_DEBUG
- SERIAL_ECHO_START();
- SERIAL_ECHOLNPAIR("EEPROM Erase failure for page ",page);
- #endif
+ DEBUG_ECHO_START();
+ DEBUG_ECHOLNPAIR("EEPROM Erase failure for page ",page);
+
return false;
}
@@ -415,20 +411,17 @@ static bool ee_PageErase(uint16_t page) {
uint32_t * aligned_src = (uint32_t *) addrflash;
for (i = 0; i < PageSize >> 2; i++) {
if (*aligned_src++ != 0xFFFFFFFF) {
-
- #ifdef EE_EMU_DEBUG
- SERIAL_ECHO_START();
- SERIAL_ECHOLNPAIR("EEPROM Verify Erase failure for page ",page);
-
- ee_Dump( page,(uint32_t *) addrflash);
- #endif
+ DEBUG_ECHO_START();
+ DEBUG_ECHOLNPAIR("EEPROM Verify Erase failure for page ",page);
+ ee_Dump(page, (uint32_t *)addrflash);
return false;
}
}
return true;
}
-static uint8_t ee_Read(uint32_t address, bool excludeRAMBuffer = false) {
+
+static uint8_t ee_Read(uint32_t address, bool excludeRAMBuffer=false) {
uint32_t baddr;
uint32_t blen;
@@ -511,7 +504,7 @@ static uint8_t ee_Read(uint32_t address, bool excludeRAMBuffer = false) {
return 0xFF;
}
-static uint32_t ee_GetAddrRange(uint32_t address, bool excludeRAMBuffer = false) {
+static uint32_t ee_GetAddrRange(uint32_t address, bool excludeRAMBuffer=false) {
uint32_t baddr,
blen,
nextAddr = 0xFFFF,
@@ -603,7 +596,7 @@ static bool ee_IsPageClean(int page) {
return true;
}
-static bool ee_Flush(uint32_t overrideAddress = 0xFFFFFFFF, uint8_t overrideData = 0xFF) {
+static bool ee_Flush(uint32_t overrideAddress = 0xFFFFFFFF, uint8_t overrideData=0xFF) {
// Check if RAM buffer has something to be written
bool isEmpty = true;
@@ -929,11 +922,9 @@ static void ee_Init() {
// If all groups seem to be used, default to first group
if (curGroup >= GroupCount) curGroup = 0;
- #ifdef EE_EMU_DEBUG
- SERIAL_ECHO_START();
- SERIAL_ECHOLNPAIR("EEPROM Current Group: ",curGroup);
- SERIAL_FLUSH();
- #endif
+ DEBUG_ECHO_START();
+ DEBUG_ECHOLNPAIR("EEPROM Current Group: ",curGroup);
+ DEBUG_FLUSH();
// Now, validate that all the other group pages are empty
for (int grp = 0; grp < GroupCount; grp++) {
@@ -941,11 +932,9 @@ static void ee_Init() {
for (int page = 0; page < PagesPerGroup; page++) {
if (!ee_IsPageClean(grp * PagesPerGroup + page)) {
- #ifdef EE_EMU_DEBUG
- SERIAL_ECHO_START();
- SERIAL_ECHOLNPAIR("EEPROM Page ", page, " not clean on group ", grp);
- SERIAL_FLUSH();
- #endif
+ DEBUG_ECHO_START();
+ DEBUG_ECHOLNPAIR("EEPROM Page ", page, " not clean on group ", grp);
+ DEBUG_FLUSH();
ee_PageErase(grp * PagesPerGroup + page);
}
}
@@ -955,66 +944,69 @@ static void ee_Init() {
// and also validate that all the other ones are clean
for (curPage = 0; curPage < PagesPerGroup; curPage++) {
if (ee_IsPageClean(curGroup * PagesPerGroup + curPage)) {
- #ifdef EE_EMU_DEBUG
- ee_Dump(curGroup * PagesPerGroup + curPage, getFlashStorage(curGroup * PagesPerGroup + curPage));
- #endif
+ ee_Dump(curGroup * PagesPerGroup + curPage, getFlashStorage(curGroup * PagesPerGroup + curPage));
break;
}
}
- #ifdef EE_EMU_DEBUG
- SERIAL_ECHO_START();
- SERIAL_ECHOLNPAIR("EEPROM Active page: ", curPage);
- SERIAL_FLUSH();
- #endif
+ DEBUG_ECHO_START();
+ DEBUG_ECHOLNPAIR("EEPROM Active page: ", curPage);
+ DEBUG_FLUSH();
// Make sure the pages following the first clean one are also clean
for (int page = curPage + 1; page < PagesPerGroup; page++) {
if (!ee_IsPageClean(curGroup * PagesPerGroup + page)) {
- #ifdef EE_EMU_DEBUG
- SERIAL_ECHO_START();
- SERIAL_ECHOLNPAIR("EEPROM Page ", page, " not clean on active group ", curGroup);
- SERIAL_FLUSH();
- ee_Dump(curGroup * PagesPerGroup + page, getFlashStorage(curGroup * PagesPerGroup + page));
- #endif
+ DEBUG_ECHO_START();
+ DEBUG_ECHOLNPAIR("EEPROM Page ", page, " not clean on active group ", curGroup);
+ DEBUG_FLUSH();
+ ee_Dump(curGroup * PagesPerGroup + page, getFlashStorage(curGroup * PagesPerGroup + page));
ee_PageErase(curGroup * PagesPerGroup + page);
}
}
}
-uint8_t eeprom_read_byte(uint8_t* addr) {
- ee_Init();
- return ee_Read((uint32_t)addr);
-}
+/* PersistentStore -----------------------------------------------------------*/
-void eeprom_write_byte(uint8_t* addr, uint8_t value) {
- ee_Init();
- ee_Write((uint32_t)addr, value);
-}
+#include "../shared/eeprom_api.h"
-void eeprom_update_block(const void* __src, void* __dst, size_t __n) {
- uint8_t* dst = (uint8_t*)__dst;
- const uint8_t* src = (const uint8_t*)__src;
- while (__n--) {
- eeprom_write_byte(dst, *src);
- ++dst;
- ++src;
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE 0x1000 // 4KB
+#endif
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+bool PersistentStore::access_start() { ee_Init(); return true; }
+bool PersistentStore::access_finish() { ee_Flush(); return true; }
+
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ while (size--) {
+ uint8_t * const p = (uint8_t * const)pos;
+ uint8_t v = *value;
+ // EEPROM has only ~100,000 write cycles,
+ // so only write bytes that have changed!
+ if (v != ee_Read(uint32_t(p))) {
+ ee_Write(uint32_t(p), v);
+ delay(2);
+ if (ee_Read(uint32_t(p)) != v) {
+ SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
+ return true;
+ }
+ }
+ crc16(crc, &v, 1);
+ pos++;
+ value++;
}
+ return false;
}
-void eeprom_read_block(void* __dst, const void* __src, size_t __n) {
- uint8_t* dst = (uint8_t*)__dst;
- uint8_t* src = (uint8_t*)__src;
- while (__n--) {
- *dst = eeprom_read_byte(src);
- ++dst;
- ++src;
- }
-}
-
-void eeprom_flush() {
- ee_Flush();
+bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
+ do {
+ uint8_t c = ee_Read(uint32_t(pos));
+ if (writing) *value = c;
+ crc16(crc, &c, 1);
+ pos++;
+ value++;
+ } while (--size);
+ return false;
}
#endif // FLASH_EEPROM_EMULATION
-#endif // ARDUINO_ARCH_AVR
+#endif // ARDUINO_ARCH_SAM
diff --git a/Marlin/src/HAL/DUE/eeprom.cpp b/Marlin/src/HAL/DUE/eeprom_wired.cpp
similarity index 76%
rename from Marlin/src/HAL/DUE/eeprom.cpp
rename to Marlin/src/HAL/DUE/eeprom_wired.cpp
index ec9ef51ff..4599d6a7c 100644
--- a/Marlin/src/HAL/DUE/eeprom.cpp
+++ b/Marlin/src/HAL/DUE/eeprom_wired.cpp
@@ -17,32 +17,29 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#ifdef ARDUINO_ARCH_SAM
-#include "../../inc/MarlinConfigPre.h"
-
-#if ENABLED(EEPROM_SETTINGS)
-
#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"
-#if !defined(E2END) && ENABLED(FLASH_EEPROM_EMULATION)
- #define E2END 0xFFF // Default to Flash emulated EEPROM size (EepromEmulation_Due.cpp)
+#ifndef MARLIN_EEPROM_SIZE
+ #error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM."
#endif
-
-extern void eeprom_flush();
-
-bool PersistentStore::access_start() { return true; }
-
-bool PersistentStore::access_finish() {
- #if ENABLED(FLASH_EEPROM_EMULATION)
- eeprom_flush();
- #endif
- return true;
-}
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+bool PersistentStore::access_start() { eeprom_init(); return true; }
+bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
while (size--) {
@@ -61,7 +58,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
crc16(crc, &v, 1);
pos++;
value++;
- };
+ }
return false;
}
@@ -76,7 +73,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
return false;
}
-size_t PersistentStore::capacity() { return E2END + 1; }
-
-#endif // EEPROM_SETTINGS
+#endif // USE_WIRED_EEPROM
#endif // ARDUINO_ARCH_SAM
diff --git a/Marlin/src/HAL/DUE/endstop_interrupts.h b/Marlin/src/HAL/DUE/endstop_interrupts.h
index f81d9055d..999ada512 100644
--- a/Marlin/src/HAL/DUE/endstop_interrupts.h
+++ b/Marlin/src/HAL/DUE/endstop_interrupts.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -47,43 +47,21 @@ void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
- #if HAS_X_MAX
- _ATTACH(X_MAX_PIN);
- #endif
- #if HAS_X_MIN
- _ATTACH(X_MIN_PIN);
- #endif
- #if HAS_Y_MAX
- _ATTACH(Y_MAX_PIN);
- #endif
- #if HAS_Y_MIN
- _ATTACH(Y_MIN_PIN);
- #endif
- #if HAS_Z_MAX
- _ATTACH(Z_MAX_PIN);
- #endif
- #if HAS_Z_MIN
- _ATTACH(Z_MIN_PIN);
- #endif
- #if HAS_Z2_MAX
- _ATTACH(Z2_MAX_PIN);
- #endif
- #if HAS_Z2_MIN
- _ATTACH(Z2_MIN_PIN);
- #endif
- #if HAS_Z3_MAX
- _ATTACH(Z3_MAX_PIN);
- #endif
- #if HAS_Z3_MIN
- _ATTACH(Z3_MIN_PIN);
- #endif
- #if HAS_Z4_MAX
- _ATTACH(Z4_MAX_PIN);
- #endif
- #if HAS_Z4_MIN
- _ATTACH(Z4_MIN_PIN);
- #endif
- #if HAS_Z_MIN_PROBE_PIN
- _ATTACH(Z_MIN_PROBE_PIN);
- #endif
+ TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN));
+ TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN));
+ TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN));
+ TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN));
+ TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN));
+ TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN));
+ TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN));
+ TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN));
+ TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN));
+ TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN));
+ TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN));
+ TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN));
+ TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN));
+ TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN));
+ TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
+ TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
+ TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
}
diff --git a/Marlin/src/HAL/DUE/fastio.h b/Marlin/src/HAL/DUE/fastio.h
index ba801b5b7..286319302 100644
--- a/Marlin/src/HAL/DUE/fastio.h
+++ b/Marlin/src/HAL/DUE/fastio.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -174,7 +174,7 @@
#define IS_OUTPUT(IO) ((digitalPinToPort(IO)->PIO_OSR & digitalPinToBitMask(IO)) != 0)
// Shorthand
-#define OUT_WRITE(IO,V) { SET_OUTPUT(IO); WRITE(IO,V); }
+#define OUT_WRITE(IO,V) do{ SET_OUTPUT(IO); WRITE(IO,V); }while(0)
// digitalRead/Write wrappers
#define extDigitalRead(IO) digitalRead(IO)
diff --git a/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp b/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp
index 672932f56..1682faea6 100644
--- a/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp
+++ b/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/DUE/fastio/G2_PWM.h b/Marlin/src/HAL/DUE/fastio/G2_PWM.h
index a94c1c527..dc4edffff 100644
--- a/Marlin/src/HAL/DUE/fastio/G2_PWM.h
+++ b/Marlin/src/HAL/DUE/fastio/G2_PWM.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/DUE/fastio/G2_pins.h b/Marlin/src/HAL/DUE/fastio/G2_pins.h
index 44b9cb35e..80c87bd39 100644
--- a/Marlin/src/HAL/DUE/fastio/G2_pins.h
+++ b/Marlin/src/HAL/DUE/fastio/G2_pins.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/DUE/inc/Conditionals_LCD.h b/Marlin/src/HAL/DUE/inc/Conditionals_LCD.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/DUE/inc/Conditionals_LCD.h
+++ b/Marlin/src/HAL/DUE/inc/Conditionals_LCD.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/DUE/inc/Conditionals_adv.h b/Marlin/src/HAL/DUE/inc/Conditionals_adv.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/DUE/inc/Conditionals_adv.h
+++ b/Marlin/src/HAL/DUE/inc/Conditionals_adv.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/DUE/inc/Conditionals_post.h b/Marlin/src/HAL/DUE/inc/Conditionals_post.h
index 8a305009c..ce6d3fdde 100644
--- a/Marlin/src/HAL/DUE/inc/Conditionals_post.h
+++ b/Marlin/src/HAL/DUE/inc/Conditionals_post.h
@@ -16,13 +16,13 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
#if USE_FALLBACK_EEPROM
- #undef SRAM_EEPROM_EMULATION
- #undef SDCARD_EEPROM_EMULATION
#define FLASH_EEPROM_EMULATION
+#elif EITHER(I2C_EEPROM, SPI_EEPROM)
+ #define USE_SHARED_EEPROM 1
#endif
diff --git a/Marlin/src/HAL/DUE/inc/SanityCheck.h b/Marlin/src/HAL/DUE/inc/SanityCheck.h
index 0f7be7955..cdea34436 100644
--- a/Marlin/src/HAL/DUE/inc/SanityCheck.h
+++ b/Marlin/src/HAL/DUE/inc/SanityCheck.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/DUE/pinsDebug.h b/Marlin/src/HAL/DUE/pinsDebug.h
index 448c2391d..28687ff26 100644
--- a/Marlin/src/HAL/DUE/pinsDebug.h
+++ b/Marlin/src/HAL/DUE/pinsDebug.h
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/DUE/spi_pins.h b/Marlin/src/HAL/DUE/spi_pins.h
index a205540bc..e28eaf827 100644
--- a/Marlin/src/HAL/DUE/spi_pins.h
+++ b/Marlin/src/HAL/DUE/spi_pins.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/DUE/timers.cpp b/Marlin/src/HAL/DUE/timers.cpp
index 74ae88284..795cdad66 100644
--- a/Marlin/src/HAL/DUE/timers.cpp
+++ b/Marlin/src/HAL/DUE/timers.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -34,8 +34,6 @@
#include "../../inc/MarlinConfig.h"
#include "HAL.h"
-#include "timers.h"
-
// ------------------------
// Local defines
// ------------------------
diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h
index 514466011..9defe39a0 100644
--- a/Marlin/src/HAL/DUE/timers.h
+++ b/Marlin/src/HAL/DUE/timers.h
@@ -15,7 +15,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -40,11 +40,17 @@ typedef uint32_t hal_timer_t;
#define HAL_TIMER_RATE ((F_CPU) / 2) // frequency of timers peripherals
#ifndef STEP_TIMER_NUM
-#define STEP_TIMER_NUM 2 // index of timer to use for stepper
+ #define STEP_TIMER_NUM 2 // Timer Index for Stepper
+#endif
+#ifndef PULSE_TIMER_NUM
+ #define PULSE_TIMER_NUM STEP_TIMER_NUM
+#endif
+#ifndef TEMP_TIMER_NUM
+ #define TEMP_TIMER_NUM 4 // Timer Index for Temperature
+#endif
+#ifndef TONE_TIMER_NUM
+ #define TONE_TIMER_NUM 6 // index of timer to use for beeper tones
#endif
-#define TEMP_TIMER_NUM 4 // index of timer to use for temperature
-#define PULSE_TIMER_NUM STEP_TIMER_NUM
-#define TONE_TIMER_NUM 6 // index of timer to use for beeper tones
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
@@ -66,8 +72,12 @@ typedef uint32_t hal_timer_t;
#ifndef HAL_STEP_TIMER_ISR
#define HAL_STEP_TIMER_ISR() void TC2_Handler()
#endif
-#define HAL_TEMP_TIMER_ISR() void TC4_Handler()
-#define HAL_TONE_TIMER_ISR() void TC6_Handler()
+#ifndef HAL_TEMP_TIMER_ISR
+ #define HAL_TEMP_TIMER_ISR() void TC4_Handler()
+#endif
+#ifndef HAL_TONE_TIMER_ISR
+ #define HAL_TONE_TIMER_ISR() void TC6_Handler()
+#endif
// ------------------------
// Types
diff --git a/Marlin/src/HAL/DUE/upload_extra_script.py b/Marlin/src/HAL/DUE/upload_extra_script.py
new file mode 100644
index 000000000..06c2b914f
--- /dev/null
+++ b/Marlin/src/HAL/DUE/upload_extra_script.py
@@ -0,0 +1,18 @@
+#
+# Set upload_command
+#
+# Windows: bossac.exe
+# Other: leave unchanged
+#
+
+import platform
+current_OS = platform.system()
+
+if current_OS == 'Windows':
+
+ Import("env")
+
+ # Use bossac.exe on Windows
+ env.Replace(
+ UPLOADCMD="bossac --info --unlock --write --verify --reset --erase -U false --boot"
+ )
diff --git a/Marlin/src/HAL/DUE/usb/conf_usb.h b/Marlin/src/HAL/DUE/usb/conf_usb.h
index 697314212..4de9e347e 100644
--- a/Marlin/src/HAL/DUE/usb/conf_usb.h
+++ b/Marlin/src/HAL/DUE/usb/conf_usb.h
@@ -78,10 +78,6 @@
//! To define a Full speed device
//#define USB_DEVICE_FULL_SPEED
-#if MB(ARCHIM1)
- #define USB_DEVICE_FULL_SPEED
-#endif
-
//! To authorize the High speed
#ifndef USB_DEVICE_FULL_SPEED
#if (UC3A3||UC3A4)
diff --git a/Marlin/src/HAL/DUE/watchdog.cpp b/Marlin/src/HAL/DUE/watchdog.cpp
index c245633d7..0f4697183 100644
--- a/Marlin/src/HAL/DUE/watchdog.cpp
+++ b/Marlin/src/HAL/DUE/watchdog.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef ARDUINO_ARCH_SAM
#include "../../inc/MarlinConfig.h"
diff --git a/Marlin/src/HAL/DUE/watchdog.h b/Marlin/src/HAL/DUE/watchdog.h
index 7d9665f20..5725a1000 100644
--- a/Marlin/src/HAL/DUE/watchdog.h
+++ b/Marlin/src/HAL/DUE/watchdog.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/ESP32/FlushableHardwareSerial.cpp b/Marlin/src/HAL/ESP32/FlushableHardwareSerial.cpp
index 4d70d34ed..d4b2f42c5 100644
--- a/Marlin/src/HAL/ESP32/FlushableHardwareSerial.cpp
+++ b/Marlin/src/HAL/ESP32/FlushableHardwareSerial.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/ESP32/FlushableHardwareSerial.h b/Marlin/src/HAL/ESP32/FlushableHardwareSerial.h
index 703bcbeb7..b43caea13 100644
--- a/Marlin/src/HAL/ESP32/FlushableHardwareSerial.h
+++ b/Marlin/src/HAL/ESP32/FlushableHardwareSerial.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp
index d9afa13ab..1e00df517 100644
--- a/Marlin/src/HAL/ESP32/HAL.cpp
+++ b/Marlin/src/HAL/ESP32/HAL.cpp
@@ -16,21 +16,18 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef ARDUINO_ARCH_ESP32
-#include "HAL.h"
-#include "timers.h"
+#include "../../inc/MarlinConfig.h"
+
#include
#include
#include
#include
-#include "../../inc/MarlinConfigPre.h"
-
#if ENABLED(WIFISUPPORT)
#include
#include "wifi.h"
@@ -97,9 +94,7 @@ void HAL_init_board() {
esp3dlib.init();
#elif ENABLED(WIFISUPPORT)
wifi_init();
- #if ENABLED(OTASUPPORT)
- OTA_init();
- #endif
+ TERN_(OTASUPPORT, OTA_init());
#if ENABLED(WEBSUPPORT)
spiffs_init();
web_init();
@@ -133,9 +128,7 @@ void HAL_idletask() {
#if BOTH(WIFISUPPORT, OTASUPPORT)
OTA_handle();
#endif
- #if ENABLED(ESP3D_WIFISUPPORT)
- esp3dlib.idletask();
- #endif
+ TERN_(ESP3D_WIFISUPPORT, esp3dlib.idletask());
}
void HAL_clear_reset_source() { }
@@ -176,39 +169,17 @@ void HAL_adc_init() {
adc1_config_width(ADC_WIDTH_12Bit);
// Configure channels only if used as (re-)configuring a pin for ADC that is used elsewhere might have adverse effects
- #if HAS_TEMP_ADC_0
- adc1_set_attenuation(get_channel(TEMP_0_PIN), ADC_ATTEN_11db);
- #endif
- #if HAS_TEMP_ADC_1
- adc1_set_attenuation(get_channel(TEMP_1_PIN), ADC_ATTEN_11db);
- #endif
- #if HAS_TEMP_ADC_2
- adc1_set_attenuation(get_channel(TEMP_2_PIN), ADC_ATTEN_11db);
- #endif
- #if HAS_TEMP_ADC_3
- adc1_set_attenuation(get_channel(TEMP_3_PIN), ADC_ATTEN_11db);
- #endif
- #if HAS_TEMP_ADC_4
- adc1_set_attenuation(get_channel(TEMP_4_PIN), ADC_ATTEN_11db);
- #endif
- #if HAS_TEMP_ADC_5
- adc1_set_attenuation(get_channel(TEMP_5_PIN), ADC_ATTEN_11db);
- #endif
- #if HAS_TEMP_ADC_6
- adc2_set_attenuation(get_channel(TEMP_6_PIN), ADC_ATTEN_11db);
- #endif
- #if HAS_TEMP_ADC_7
- adc3_set_attenuation(get_channel(TEMP_7_PIN), ADC_ATTEN_11db);
- #endif
- #if HAS_HEATED_BED
- adc1_set_attenuation(get_channel(TEMP_BED_PIN), ADC_ATTEN_11db);
- #endif
- #if HAS_TEMP_CHAMBER
- adc1_set_attenuation(get_channel(TEMP_CHAMBER_PIN), ADC_ATTEN_11db);
- #endif
- #if ENABLED(FILAMENT_WIDTH_SENSOR)
- adc1_set_attenuation(get_channel(FILWIDTH_PIN), ADC_ATTEN_11db);
- #endif
+ TERN_(HAS_TEMP_ADC_0, adc1_set_attenuation(get_channel(TEMP_0_PIN), ADC_ATTEN_11db));
+ TERN_(HAS_TEMP_ADC_1, adc1_set_attenuation(get_channel(TEMP_1_PIN), ADC_ATTEN_11db));
+ TERN_(HAS_TEMP_ADC_2, adc1_set_attenuation(get_channel(TEMP_2_PIN), ADC_ATTEN_11db));
+ TERN_(HAS_TEMP_ADC_3, adc1_set_attenuation(get_channel(TEMP_3_PIN), ADC_ATTEN_11db));
+ TERN_(HAS_TEMP_ADC_4, adc1_set_attenuation(get_channel(TEMP_4_PIN), ADC_ATTEN_11db));
+ TERN_(HAS_TEMP_ADC_5, adc1_set_attenuation(get_channel(TEMP_5_PIN), ADC_ATTEN_11db));
+ TERN_(HAS_TEMP_ADC_6, adc2_set_attenuation(get_channel(TEMP_6_PIN), ADC_ATTEN_11db));
+ TERN_(HAS_TEMP_ADC_7, adc3_set_attenuation(get_channel(TEMP_7_PIN), ADC_ATTEN_11db));
+ TERN_(HAS_HEATED_BED, adc1_set_attenuation(get_channel(TEMP_BED_PIN), ADC_ATTEN_11db));
+ TERN_(HAS_TEMP_CHAMBER, adc1_set_attenuation(get_channel(TEMP_CHAMBER_PIN), ADC_ATTEN_11db));
+ TERN_(FILAMENT_WIDTH_SENSOR, adc1_set_attenuation(get_channel(FILWIDTH_PIN), ADC_ATTEN_11db));
// Note that adc2 is shared with the WiFi module, which has higher priority, so the conversion may fail.
// That's why we're not setting it up here.
diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h
index a04343b69..c91f9efff 100644
--- a/Marlin/src/HAL/ESP32/HAL.h
+++ b/Marlin/src/HAL/ESP32/HAL.h
@@ -14,7 +14,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*/
#pragma once
@@ -34,8 +34,6 @@
#include "watchdog.h"
#include "i2s.h"
-#include "timers.h"
-
#if ENABLED(WIFISUPPORT)
#include "WebSocketSerial.h"
#endif
@@ -109,19 +107,14 @@ int freeMemory();
void analogWrite(pin_t pin, int value);
-// EEPROM
-void eeprom_write_byte(uint8_t *pos, unsigned char value);
-uint8_t eeprom_read_byte(uint8_t *pos);
-void eeprom_read_block (void *__dst, const void *__src, size_t __n);
-void eeprom_update_block (const void *__src, void *__dst, size_t __n);
-
// ADC
#define HAL_ANALOG_SELECT(pin)
void HAL_adc_init();
-#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
+#define HAL_ADC_VREF 3.3
#define HAL_ADC_RESOLUTION 10
+#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true
diff --git a/Marlin/src/HAL/ESP32/HAL_SPI.cpp b/Marlin/src/HAL/ESP32/HAL_SPI.cpp
index 981d9b49c..8e5875fc3 100644
--- a/Marlin/src/HAL/ESP32/HAL_SPI.cpp
+++ b/Marlin/src/HAL/ESP32/HAL_SPI.cpp
@@ -17,19 +17,17 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef ARDUINO_ARCH_ESP32
-#include "HAL.h"
-#include "../shared/HAL_SPI.h"
-#include
-#include "spi_pins.h"
-#include
+#include "../../inc/MarlinConfig.h"
-#include "../../core/macros.h"
+#include "../shared/HAL_SPI.h"
+
+#include
+#include
// ------------------------
// Public Variables
diff --git a/Marlin/src/HAL/ESP32/Servo.cpp b/Marlin/src/HAL/ESP32/Servo.cpp
index 68ee3d909..fcf584858 100644
--- a/Marlin/src/HAL/ESP32/Servo.cpp
+++ b/Marlin/src/HAL/ESP32/Servo.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#ifdef ARDUINO_ARCH_ESP32
@@ -61,9 +61,7 @@ void Servo::move(const int value) {
if (attach(0) >= 0) {
write(value);
safe_delay(servo_delay[channel]);
- #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
- detach();
- #endif
+ TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
}
}
#endif // HAS_SERVOS
diff --git a/Marlin/src/HAL/ESP32/Servo.h b/Marlin/src/HAL/ESP32/Servo.h
index 3f575150e..b0d929452 100644
--- a/Marlin/src/HAL/ESP32/Servo.h
+++ b/Marlin/src/HAL/ESP32/Servo.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/ESP32/WebSocketSerial.cpp b/Marlin/src/HAL/ESP32/WebSocketSerial.cpp
index c7ee6951e..533f873e4 100644
--- a/Marlin/src/HAL/ESP32/WebSocketSerial.cpp
+++ b/Marlin/src/HAL/ESP32/WebSocketSerial.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#ifdef ARDUINO_ARCH_ESP32
diff --git a/Marlin/src/HAL/ESP32/WebSocketSerial.h b/Marlin/src/HAL/ESP32/WebSocketSerial.h
index e76a2bc68..7a25c6dc5 100644
--- a/Marlin/src/HAL/ESP32/WebSocketSerial.h
+++ b/Marlin/src/HAL/ESP32/WebSocketSerial.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/ESP32/eeprom_impl.cpp b/Marlin/src/HAL/ESP32/eeprom.cpp
similarity index 77%
rename from Marlin/src/HAL/ESP32/eeprom_impl.cpp
rename to Marlin/src/HAL/ESP32/eeprom.cpp
index dbfee1405..1bf687c6f 100644
--- a/Marlin/src/HAL/ESP32/eeprom_impl.cpp
+++ b/Marlin/src/HAL/ESP32/eeprom.cpp
@@ -16,29 +16,25 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef ARDUINO_ARCH_ESP32
#include "../../inc/MarlinConfig.h"
-#if ENABLED(EEPROM_SETTINGS) && DISABLED(FLASH_EEPROM_EMULATION)
+#if ENABLED(EEPROM_SETTINGS)
#include "../shared/eeprom_api.h"
-#include "EEPROM.h"
+#include
-#define EEPROM_SIZE 4096
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE 0x1000 // 4KB
+#endif
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
-bool PersistentStore::access_start() {
- return EEPROM.begin(EEPROM_SIZE);
-}
-
-bool PersistentStore::access_finish() {
- EEPROM.end();
- return true;
-}
+bool PersistentStore::access_start() { return EEPROM.begin(MARLIN_EEPROM_SIZE); }
+bool PersistentStore::access_finish() { EEPROM.end(); return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
for (size_t i = 0; i < size; i++) {
@@ -57,7 +53,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
return false;
}
-size_t PersistentStore::capacity() { return EEPROM_SIZE; }
-
#endif // EEPROM_SETTINGS
#endif // ARDUINO_ARCH_ESP32
diff --git a/Marlin/src/HAL/ESP32/endstop_interrupts.h b/Marlin/src/HAL/ESP32/endstop_interrupts.h
index 2da1cc747..743ccd99c 100644
--- a/Marlin/src/HAL/ESP32/endstop_interrupts.h
+++ b/Marlin/src/HAL/ESP32/endstop_interrupts.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -42,43 +42,21 @@ void ICACHE_RAM_ATTR endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
- #if HAS_X_MAX
- _ATTACH(X_MAX_PIN);
- #endif
- #if HAS_X_MIN
- _ATTACH(X_MIN_PIN);
- #endif
- #if HAS_Y_MAX
- _ATTACH(Y_MAX_PIN);
- #endif
- #if HAS_Y_MIN
- _ATTACH(Y_MIN_PIN);
- #endif
- #if HAS_Z_MAX
- _ATTACH(Z_MAX_PIN);
- #endif
- #if HAS_Z_MIN
- _ATTACH(Z_MIN_PIN);
- #endif
- #if HAS_Z2_MAX
- _ATTACH(Z2_MAX_PIN);
- #endif
- #if HAS_Z2_MIN
- _ATTACH(Z2_MIN_PIN);
- #endif
- #if HAS_Z3_MAX
- _ATTACH(Z3_MAX_PIN);
- #endif
- #if HAS_Z3_MIN
- _ATTACH(Z3_MIN_PIN);
- #endif
- #if HAS_Z4_MAX
- _ATTACH(Z4_MAX_PIN);
- #endif
- #if HAS_Z4_MIN
- _ATTACH(Z4_MIN_PIN);
- #endif
- #if HAS_Z_MIN_PROBE_PIN
- _ATTACH(Z_MIN_PROBE_PIN);
- #endif
+ TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN));
+ TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN));
+ TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN));
+ TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN));
+ TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN));
+ TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN));
+ TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN));
+ TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN));
+ TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN));
+ TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN));
+ TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN));
+ TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN));
+ TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN));
+ TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN));
+ TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
+ TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
+ TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
}
diff --git a/Marlin/src/HAL/ESP32/fastio.h b/Marlin/src/HAL/ESP32/fastio.h
index 09930194d..2ded3a5f6 100644
--- a/Marlin/src/HAL/ESP32/fastio.h
+++ b/Marlin/src/HAL/ESP32/fastio.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/ESP32/i2s.cpp b/Marlin/src/HAL/ESP32/i2s.cpp
index d80c3c24e..99b2f755e 100644
--- a/Marlin/src/HAL/ESP32/i2s.cpp
+++ b/Marlin/src/HAL/ESP32/i2s.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#ifdef ARDUINO_ARCH_ESP32
diff --git a/Marlin/src/HAL/ESP32/i2s.h b/Marlin/src/HAL/ESP32/i2s.h
index 63a579a18..573b98383 100644
--- a/Marlin/src/HAL/ESP32/i2s.h
+++ b/Marlin/src/HAL/ESP32/i2s.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/ESP32/inc/Conditionals_LCD.h b/Marlin/src/HAL/ESP32/inc/Conditionals_LCD.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/ESP32/inc/Conditionals_LCD.h
+++ b/Marlin/src/HAL/ESP32/inc/Conditionals_LCD.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/ESP32/inc/Conditionals_adv.h b/Marlin/src/HAL/ESP32/inc/Conditionals_adv.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/ESP32/inc/Conditionals_adv.h
+++ b/Marlin/src/HAL/ESP32/inc/Conditionals_adv.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/ESP32/inc/Conditionals_post.h b/Marlin/src/HAL/ESP32/inc/Conditionals_post.h
index 11603c9ef..5f1c4b160 100644
--- a/Marlin/src/HAL/ESP32/inc/Conditionals_post.h
+++ b/Marlin/src/HAL/ESP32/inc/Conditionals_post.h
@@ -16,12 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
-
-// If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation
-#if ENABLED(EEPROM_SETTINGS) && NONE(USE_WIRED_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION)
- #define SDCARD_EEPROM_EMULATION
-#endif
diff --git a/Marlin/src/HAL/ESP32/inc/SanityCheck.h b/Marlin/src/HAL/ESP32/inc/SanityCheck.h
index b6ad7a3c4..7653f6fe7 100644
--- a/Marlin/src/HAL/ESP32/inc/SanityCheck.h
+++ b/Marlin/src/HAL/ESP32/inc/SanityCheck.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/ESP32/ota.cpp b/Marlin/src/HAL/ESP32/ota.cpp
index 34a2482c9..7cf65ed2d 100644
--- a/Marlin/src/HAL/ESP32/ota.cpp
+++ b/Marlin/src/HAL/ESP32/ota.cpp
@@ -14,7 +14,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*/
#ifdef ARDUINO_ARCH_ESP32
diff --git a/Marlin/src/HAL/ESP32/ota.h b/Marlin/src/HAL/ESP32/ota.h
index 1780fb32c..7f9b237aa 100644
--- a/Marlin/src/HAL/ESP32/ota.h
+++ b/Marlin/src/HAL/ESP32/ota.h
@@ -14,7 +14,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*/
#pragma once
diff --git a/Marlin/src/HAL/ESP32/servotimers.h b/Marlin/src/HAL/ESP32/servotimers.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/ESP32/servotimers.h
+++ b/Marlin/src/HAL/ESP32/servotimers.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/ESP32/spi_pins.h b/Marlin/src/HAL/ESP32/spi_pins.h
index 0e67615a2..15f8f2ab6 100644
--- a/Marlin/src/HAL/ESP32/spi_pins.h
+++ b/Marlin/src/HAL/ESP32/spi_pins.h
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/ESP32/spiffs.cpp b/Marlin/src/HAL/ESP32/spiffs.cpp
index 0013dd609..a0e713bff 100644
--- a/Marlin/src/HAL/ESP32/spiffs.cpp
+++ b/Marlin/src/HAL/ESP32/spiffs.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef ARDUINO_ARCH_ESP32
#include "../../inc/MarlinConfigPre.h"
diff --git a/Marlin/src/HAL/ESP32/spiffs.h b/Marlin/src/HAL/ESP32/spiffs.h
index b9cbb23bd..64ec7dd11 100644
--- a/Marlin/src/HAL/ESP32/spiffs.h
+++ b/Marlin/src/HAL/ESP32/spiffs.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/ESP32/timers.cpp b/Marlin/src/HAL/ESP32/timers.cpp
index ef181a438..3300aea8a 100644
--- a/Marlin/src/HAL/ESP32/timers.cpp
+++ b/Marlin/src/HAL/ESP32/timers.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef ARDUINO_ARCH_ESP32
#include
@@ -28,9 +27,7 @@
#include
#include
-#include "HAL.h"
-
-#include "timers.h"
+#include "../../inc/MarlinConfig.h"
// ------------------------
// Local defines
diff --git a/Marlin/src/HAL/ESP32/timers.h b/Marlin/src/HAL/ESP32/timers.h
index bc4306be2..d722670f3 100644
--- a/Marlin/src/HAL/ESP32/timers.h
+++ b/Marlin/src/HAL/ESP32/timers.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -38,10 +38,18 @@
typedef uint64_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFFFFFFFFFULL
-#define STEP_TIMER_NUM 0 // index of timer to use for stepper
-#define TEMP_TIMER_NUM 1 // index of timer to use for temperature
-#define PWM_TIMER_NUM 2 // index of timer to use for PWM outputs
-#define PULSE_TIMER_NUM STEP_TIMER_NUM
+#ifndef STEP_TIMER_NUM
+ #define STEP_TIMER_NUM 0 // Timer Index for Stepper
+#endif
+#ifndef PULSE_TIMER_NUM
+ #define PULSE_TIMER_NUM STEP_TIMER_NUM
+#endif
+#ifndef TEMP_TIMER_NUM
+ #define TEMP_TIMER_NUM 1 // Timer Index for Temperature
+#endif
+#ifndef PWM_TIMER_NUM
+ #define PWM_TIMER_NUM 2 // index of timer to use for PWM outputs
+#endif
#define HAL_TIMER_RATE APB_CLK_FREQ // frequency of timer peripherals
@@ -79,9 +87,15 @@ typedef uint64_t hal_timer_t;
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
-#define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler()
-#define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler()
-#define HAL_PWM_TIMER_ISR() extern "C" void pwmTC_Handler()
+#ifndef HAL_TEMP_TIMER_ISR
+ #define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler()
+#endif
+#ifndef HAL_STEP_TIMER_ISR
+ #define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler()
+#endif
+#ifndef HAL_PWM_TIMER_ISR
+ #define HAL_PWM_TIMER_ISR() extern "C" void pwmTC_Handler()
+#endif
extern "C" void tempTC_Handler();
extern "C" void stepTC_Handler();
diff --git a/Marlin/src/HAL/ESP32/watchdog.cpp b/Marlin/src/HAL/ESP32/watchdog.cpp
index 9f681e609..f6fcfa318 100644
--- a/Marlin/src/HAL/ESP32/watchdog.cpp
+++ b/Marlin/src/HAL/ESP32/watchdog.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef ARDUINO_ARCH_ESP32
#include "../../inc/MarlinConfig.h"
diff --git a/Marlin/src/HAL/ESP32/watchdog.h b/Marlin/src/HAL/ESP32/watchdog.h
index 7e0799086..b6c169e34 100644
--- a/Marlin/src/HAL/ESP32/watchdog.h
+++ b/Marlin/src/HAL/ESP32/watchdog.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/ESP32/web.cpp b/Marlin/src/HAL/ESP32/web.cpp
index b795efe3c..7a27707a3 100644
--- a/Marlin/src/HAL/ESP32/web.cpp
+++ b/Marlin/src/HAL/ESP32/web.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef ARDUINO_ARCH_ESP32
#include "../../inc/MarlinConfigPre.h"
diff --git a/Marlin/src/HAL/ESP32/web.h b/Marlin/src/HAL/ESP32/web.h
index 8dbefd8ee..60023ac63 100644
--- a/Marlin/src/HAL/ESP32/web.h
+++ b/Marlin/src/HAL/ESP32/web.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/ESP32/wifi.cpp b/Marlin/src/HAL/ESP32/wifi.cpp
index 9203dd62e..f4cf5a606 100644
--- a/Marlin/src/HAL/ESP32/wifi.cpp
+++ b/Marlin/src/HAL/ESP32/wifi.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef ARDUINO_ARCH_ESP32
#include "../../core/serial.h"
diff --git a/Marlin/src/HAL/ESP32/wifi.h b/Marlin/src/HAL/ESP32/wifi.h
index 580c6c87f..759a73b25 100644
--- a/Marlin/src/HAL/ESP32/wifi.h
+++ b/Marlin/src/HAL/ESP32/wifi.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/HAL.h b/Marlin/src/HAL/HAL.h
index fa2782cfc..29702f2d2 100644
--- a/Marlin/src/HAL/HAL.h
+++ b/Marlin/src/HAL/HAL.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -27,8 +27,20 @@
#define HAL_ADC_RANGE _BV(HAL_ADC_RESOLUTION)
+#ifndef I2C_ADDRESS
+ #define I2C_ADDRESS(A) (A)
+#endif
+
+// Needed for AVR sprintf_P PROGMEM extension
+#ifndef S_FMT
+ #define S_FMT "%s"
+#endif
+
+// String helper
+#ifndef PGMSTR
+ #define PGMSTR(NAM,STR) constexpr char NAM[] = STR
+#endif
+
inline void watchdog_refresh() {
- #if ENABLED(USE_WATCHDOG)
- HAL_watchdog_refresh();
- #endif
+ TERN_(USE_WATCHDOG, HAL_watchdog_refresh());
}
diff --git a/Marlin/src/HAL/LINUX/HAL.cpp b/Marlin/src/HAL/LINUX/HAL.cpp
index d38644f1a..d7d7c2d2b 100644
--- a/Marlin/src/HAL/LINUX/HAL.cpp
+++ b/Marlin/src/HAL/LINUX/HAL.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __PLAT_LINUX__
#include "../../inc/MarlinConfig.h"
diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h
index 0475c953c..96e121d91 100644
--- a/Marlin/src/HAL/LINUX/HAL.h
+++ b/Marlin/src/HAL/LINUX/HAL.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -56,7 +56,6 @@ uint8_t _getc();
#include "../shared/HAL_SPI.h"
#include "fastio.h"
#include "watchdog.h"
-#include "timers.h"
#include "serial.h"
#define SHARED_SERVOS HAS_SERVOS
@@ -87,9 +86,10 @@ int freeMemory();
#pragma GCC diagnostic pop
// ADC
+#define HAL_ADC_VREF 5.0
+#define HAL_ADC_RESOLUTION 10
#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch)
#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch)
-#define HAL_ADC_RESOLUTION 10
#define HAL_READ_ADC() HAL_adc_get_result()
#define HAL_ADC_READY() true
@@ -106,3 +106,8 @@ inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; }
FORCE_INLINE static void DELAY_CYCLES(uint64_t x) {
Clock::delayCycles(x);
}
+
+// Add strcmp_P if missing
+#ifndef strcmp_P
+ #define strcmp_P(a, b) strcmp((a), (b))
+#endif
diff --git a/Marlin/src/HAL/LINUX/arduino.cpp b/Marlin/src/HAL/LINUX/arduino.cpp
index 008db1559..4b56d02a3 100644
--- a/Marlin/src/HAL/LINUX/arduino.cpp
+++ b/Marlin/src/HAL/LINUX/arduino.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __PLAT_LINUX__
#include
@@ -76,20 +75,6 @@ uint16_t analogRead(pin_t adc_pin) {
return Gpio::get(DIGITAL_PIN_TO_ANALOG_PIN(adc_pin));
}
-// **************************
-// Persistent Config Storage
-// **************************
-
-void eeprom_write_byte(unsigned char *pos, unsigned char value) {
-
-}
-
-unsigned char eeprom_read_byte(uint8_t * pos) { return '\0'; }
-
-void eeprom_read_block(void *__dst, const void *__src, size_t __n) { }
-
-void eeprom_update_block(const void *__src, void *__dst, size_t __n) { }
-
char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s) {
char format_string[20];
snprintf(format_string, 20, "%%%d.%df", __width, __prec);
diff --git a/Marlin/src/HAL/LINUX/eeprom_impl.cpp b/Marlin/src/HAL/LINUX/eeprom.cpp
similarity index 86%
rename from Marlin/src/HAL/LINUX/eeprom_impl.cpp
rename to Marlin/src/HAL/LINUX/eeprom.cpp
index 4745f0567..967ca851a 100644
--- a/Marlin/src/HAL/LINUX/eeprom_impl.cpp
+++ b/Marlin/src/HAL/LINUX/eeprom.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __PLAT_LINUX__
#include "../../inc/MarlinConfig.h"
@@ -29,10 +28,15 @@
#include "../shared/eeprom_api.h"
#include
-#define LINUX_EEPROM_SIZE (E2END + 1)
-uint8_t buffer[LINUX_EEPROM_SIZE];
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE 0x1000 // 4KB of Emulated EEPROM
+#endif
+
+uint8_t buffer[MARLIN_EEPROM_SIZE];
char filename[] = "eeprom.dat";
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+
bool PersistentStore::access_start() {
const char eeprom_erase_value = 0xFF;
FILE * eeprom_file = fopen(filename, "rb");
@@ -41,8 +45,8 @@ bool PersistentStore::access_start() {
fseek(eeprom_file, 0L, SEEK_END);
std::size_t file_size = ftell(eeprom_file);
- if (file_size < LINUX_EEPROM_SIZE) {
- memset(buffer + file_size, eeprom_erase_value, LINUX_EEPROM_SIZE - file_size);
+ if (file_size < MARLIN_EEPROM_SIZE) {
+ memset(buffer + file_size, eeprom_erase_value, MARLIN_EEPROM_SIZE - file_size);
}
else {
fseek(eeprom_file, 0L, SEEK_SET);
@@ -96,7 +100,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin
return bytes_read != size; // return true for any error
}
-size_t PersistentStore::capacity() { return 4096; } // 4KiB of Emulated EEPROM
-
#endif // EEPROM_SETTINGS
#endif // __PLAT_LINUX__
diff --git a/Marlin/src/HAL/LINUX/fastio.h b/Marlin/src/HAL/LINUX/fastio.h
index 08dca7780..4567c62a5 100644
--- a/Marlin/src/HAL/LINUX/fastio.h
+++ b/Marlin/src/HAL/LINUX/fastio.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LINUX/hardware/Clock.cpp b/Marlin/src/HAL/LINUX/hardware/Clock.cpp
index 8265fedbf..1984a4a44 100644
--- a/Marlin/src/HAL/LINUX/hardware/Clock.cpp
+++ b/Marlin/src/HAL/LINUX/hardware/Clock.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __PLAT_LINUX__
#include "../../../inc/MarlinConfig.h"
diff --git a/Marlin/src/HAL/LINUX/hardware/Clock.h b/Marlin/src/HAL/LINUX/hardware/Clock.h
index 17c2fd950..072eacfd7 100644
--- a/Marlin/src/HAL/LINUX/hardware/Clock.h
+++ b/Marlin/src/HAL/LINUX/hardware/Clock.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LINUX/hardware/Gpio.cpp b/Marlin/src/HAL/LINUX/hardware/Gpio.cpp
index e49fb1375..61a7be7da 100644
--- a/Marlin/src/HAL/LINUX/hardware/Gpio.cpp
+++ b/Marlin/src/HAL/LINUX/hardware/Gpio.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __PLAT_LINUX__
#include "Gpio.h"
diff --git a/Marlin/src/HAL/LINUX/hardware/Gpio.h b/Marlin/src/HAL/LINUX/hardware/Gpio.h
index 33eea7773..9255ec1df 100644
--- a/Marlin/src/HAL/LINUX/hardware/Gpio.h
+++ b/Marlin/src/HAL/LINUX/hardware/Gpio.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LINUX/hardware/Heater.cpp b/Marlin/src/HAL/LINUX/hardware/Heater.cpp
index 7c9bfaf80..70df81618 100644
--- a/Marlin/src/HAL/LINUX/hardware/Heater.cpp
+++ b/Marlin/src/HAL/LINUX/hardware/Heater.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __PLAT_LINUX__
#include "Clock.h"
diff --git a/Marlin/src/HAL/LINUX/hardware/Heater.h b/Marlin/src/HAL/LINUX/hardware/Heater.h
index bb759da09..b17078d0b 100644
--- a/Marlin/src/HAL/LINUX/hardware/Heater.h
+++ b/Marlin/src/HAL/LINUX/hardware/Heater.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LINUX/hardware/IOLoggerCSV.cpp b/Marlin/src/HAL/LINUX/hardware/IOLoggerCSV.cpp
index a79f14f6f..c11fd1f55 100644
--- a/Marlin/src/HAL/LINUX/hardware/IOLoggerCSV.cpp
+++ b/Marlin/src/HAL/LINUX/hardware/IOLoggerCSV.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __PLAT_LINUX__
#include "IOLoggerCSV.h"
diff --git a/Marlin/src/HAL/LINUX/hardware/IOLoggerCSV.h b/Marlin/src/HAL/LINUX/hardware/IOLoggerCSV.h
index f8bca83e3..d8fe7383b 100644
--- a/Marlin/src/HAL/LINUX/hardware/IOLoggerCSV.h
+++ b/Marlin/src/HAL/LINUX/hardware/IOLoggerCSV.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp b/Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp
index ec58fe77e..c5b3ccc98 100644
--- a/Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp
+++ b/Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __PLAT_LINUX__
#include
diff --git a/Marlin/src/HAL/LINUX/hardware/LinearAxis.h b/Marlin/src/HAL/LINUX/hardware/LinearAxis.h
index 04a5f3d0f..34541e79a 100644
--- a/Marlin/src/HAL/LINUX/hardware/LinearAxis.h
+++ b/Marlin/src/HAL/LINUX/hardware/LinearAxis.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LINUX/hardware/Timer.cpp b/Marlin/src/HAL/LINUX/hardware/Timer.cpp
index e7136bbde..9f0d6a8f3 100644
--- a/Marlin/src/HAL/LINUX/hardware/Timer.cpp
+++ b/Marlin/src/HAL/LINUX/hardware/Timer.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __PLAT_LINUX__
#include "Timer.h"
diff --git a/Marlin/src/HAL/LINUX/hardware/Timer.h b/Marlin/src/HAL/LINUX/hardware/Timer.h
index ebfe8e8b9..757efdcdb 100644
--- a/Marlin/src/HAL/LINUX/hardware/Timer.h
+++ b/Marlin/src/HAL/LINUX/hardware/Timer.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LINUX/inc/Conditionals_LCD.h b/Marlin/src/HAL/LINUX/inc/Conditionals_LCD.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/LINUX/inc/Conditionals_LCD.h
+++ b/Marlin/src/HAL/LINUX/inc/Conditionals_LCD.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LINUX/inc/Conditionals_adv.h b/Marlin/src/HAL/LINUX/inc/Conditionals_adv.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/LINUX/inc/Conditionals_adv.h
+++ b/Marlin/src/HAL/LINUX/inc/Conditionals_adv.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LINUX/inc/Conditionals_post.h b/Marlin/src/HAL/LINUX/inc/Conditionals_post.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/LINUX/inc/Conditionals_post.h
+++ b/Marlin/src/HAL/LINUX/inc/Conditionals_post.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LINUX/inc/SanityCheck.h b/Marlin/src/HAL/LINUX/inc/SanityCheck.h
index a3238b088..8d23cdabb 100644
--- a/Marlin/src/HAL/LINUX/inc/SanityCheck.h
+++ b/Marlin/src/HAL/LINUX/inc/SanityCheck.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LINUX/include/Arduino.h b/Marlin/src/HAL/LINUX/include/Arduino.h
index 55bf0f95e..e28b474ed 100644
--- a/Marlin/src/HAL/LINUX/include/Arduino.h
+++ b/Marlin/src/HAL/LINUX/include/Arduino.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -106,12 +106,6 @@ bool digitalRead(pin_t);
void analogWrite(pin_t, int);
uint16_t analogRead(pin_t);
-// EEPROM
-void eeprom_write_byte(unsigned char *pos, unsigned char value);
-unsigned char eeprom_read_byte(unsigned char *pos);
-void eeprom_read_block(void *__dst, const void *__src, size_t __n);
-void eeprom_update_block(const void *__src, void *__dst, size_t __n);
-
int32_t random(int32_t);
int32_t random(int32_t, int32_t);
void randomSeed(uint32_t);
diff --git a/Marlin/src/HAL/LINUX/include/pinmapping.cpp b/Marlin/src/HAL/LINUX/include/pinmapping.cpp
index 0340e681f..870ab3a96 100644
--- a/Marlin/src/HAL/LINUX/include/pinmapping.cpp
+++ b/Marlin/src/HAL/LINUX/include/pinmapping.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __PLAT_LINUX__
#include
diff --git a/Marlin/src/HAL/LINUX/include/pinmapping.h b/Marlin/src/HAL/LINUX/include/pinmapping.h
index 0d99a3811..98f4b812e 100644
--- a/Marlin/src/HAL/LINUX/include/pinmapping.h
+++ b/Marlin/src/HAL/LINUX/include/pinmapping.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LINUX/include/serial.h b/Marlin/src/HAL/LINUX/include/serial.h
index c881d5dbd..154e95aec 100644
--- a/Marlin/src/HAL/LINUX/include/serial.h
+++ b/Marlin/src/HAL/LINUX/include/serial.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LINUX/main.cpp b/Marlin/src/HAL/LINUX/main.cpp
index 1155f2a87..4eeef318e 100644
--- a/Marlin/src/HAL/LINUX/main.cpp
+++ b/Marlin/src/HAL/LINUX/main.cpp
@@ -14,10 +14,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __PLAT_LINUX__
extern void setup();
diff --git a/Marlin/src/HAL/LINUX/pinsDebug.h b/Marlin/src/HAL/LINUX/pinsDebug.h
index e373d3706..a93ceddc6 100644
--- a/Marlin/src/HAL/LINUX/pinsDebug.h
+++ b/Marlin/src/HAL/LINUX/pinsDebug.h
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/LINUX/servo_private.h b/Marlin/src/HAL/LINUX/servo_private.h
index d576ff926..122cfef3e 100644
--- a/Marlin/src/HAL/LINUX/servo_private.h
+++ b/Marlin/src/HAL/LINUX/servo_private.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LINUX/spi_pins.h b/Marlin/src/HAL/LINUX/spi_pins.h
index 8abeb312f..a444196f0 100644
--- a/Marlin/src/HAL/LINUX/spi_pins.h
+++ b/Marlin/src/HAL/LINUX/spi_pins.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -24,7 +24,7 @@
#include "../../core/macros.h"
#include "../../inc/MarlinConfigPre.h"
-#if HAS_GRAPHICAL_LCD && ENABLED(SDSUPPORT) && (LCD_PINS_D4 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == MOSI_PIN)
+#if BOTH(HAS_GRAPHICAL_LCD, 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/LINUX/timers.cpp b/Marlin/src/HAL/LINUX/timers.cpp
index ebfb95059..66d80f251 100644
--- a/Marlin/src/HAL/LINUX/timers.cpp
+++ b/Marlin/src/HAL/LINUX/timers.cpp
@@ -16,16 +16,14 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __PLAT_LINUX__
#include "hardware/Timer.h"
#include "../../inc/MarlinConfig.h"
-#include "timers.h"
/**
* Use POSIX signals to attempt to emulate Interrupts
diff --git a/Marlin/src/HAL/LINUX/timers.h b/Marlin/src/HAL/LINUX/timers.h
index b65758492..1beaea95a 100644
--- a/Marlin/src/HAL/LINUX/timers.h
+++ b/Marlin/src/HAL/LINUX/timers.h
@@ -15,7 +15,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -37,9 +37,15 @@ typedef uint32_t hal_timer_t;
#define HAL_TIMER_RATE ((SystemCoreClock) / 4) // frequency of timers peripherals
-#define STEP_TIMER_NUM 0 // Timer Index for Stepper
-#define TEMP_TIMER_NUM 1 // Timer Index for Temperature
-#define PULSE_TIMER_NUM STEP_TIMER_NUM
+#ifndef STEP_TIMER_NUM
+ #define STEP_TIMER_NUM 0 // Timer Index for Stepper
+#endif
+#ifndef PULSE_TIMER_NUM
+ #define PULSE_TIMER_NUM STEP_TIMER_NUM
+#endif
+#ifndef TEMP_TIMER_NUM
+ #define TEMP_TIMER_NUM 1 // Timer Index for Temperature
+#endif
#define TEMP_TIMER_RATE 1000000
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
@@ -59,8 +65,12 @@ typedef uint32_t hal_timer_t;
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
-#define HAL_STEP_TIMER_ISR() extern "C" void TIMER0_IRQHandler()
-#define HAL_TEMP_TIMER_ISR() extern "C" void TIMER1_IRQHandler()
+#ifndef HAL_STEP_TIMER_ISR
+ #define HAL_STEP_TIMER_ISR() extern "C" void TIMER0_IRQHandler()
+#endif
+#ifndef HAL_TEMP_TIMER_ISR
+ #define HAL_TEMP_TIMER_ISR() extern "C" void TIMER1_IRQHandler()
+#endif
// PWM timer
#define HAL_PWM_TIMER
diff --git a/Marlin/src/HAL/LINUX/watchdog.cpp b/Marlin/src/HAL/LINUX/watchdog.cpp
index 5ffe860f0..c15b0e311 100644
--- a/Marlin/src/HAL/LINUX/watchdog.cpp
+++ b/Marlin/src/HAL/LINUX/watchdog.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __PLAT_LINUX__
#include "../../inc/MarlinConfig.h"
diff --git a/Marlin/src/HAL/LINUX/watchdog.h b/Marlin/src/HAL/LINUX/watchdog.h
index 4771426a0..472624cc7 100644
--- a/Marlin/src/HAL/LINUX/watchdog.h
+++ b/Marlin/src/HAL/LINUX/watchdog.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LPC1768/DebugMonitor.cpp b/Marlin/src/HAL/LPC1768/DebugMonitor.cpp
index 2a39e5616..783b10cfa 100644
--- a/Marlin/src/HAL/LPC1768/DebugMonitor.cpp
+++ b/Marlin/src/HAL/LPC1768/DebugMonitor.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef TARGET_LPC1768
#include "../../core/macros.h"
@@ -211,11 +210,7 @@ void HardFault_HandlerC(unsigned long *sp, unsigned long lr, unsigned long cause
// Nothing below here is compiled because NVIC_SystemReset loops forever
- for (;;) {
- #if ENABLED(USE_WATCHDOG)
- watchdog_init();
- #endif
- }
+ for (;;) { TERN_(USE_WATCHDOG, watchdog_init()); }
}
extern "C" {
diff --git a/Marlin/src/HAL/LPC1768/HAL.cpp b/Marlin/src/HAL/LPC1768/HAL.cpp
index f206ce7ad..939f1e8a9 100644
--- a/Marlin/src/HAL/LPC1768/HAL.cpp
+++ b/Marlin/src/HAL/LPC1768/HAL.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef TARGET_LPC1768
#include "../../inc/MarlinConfig.h"
@@ -70,9 +69,7 @@ int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
void flashFirmware(const int16_t) { NVIC_SystemReset(); }
void HAL_clear_reset_source(void) {
- #if ENABLED(USE_WATCHDOG)
- watchdog_clear_timeout_flag();
- #endif
+ TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag());
}
uint8_t HAL_get_reset_source(void) {
diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h
index f5ea629f1..0153bacf4 100644
--- a/Marlin/src/HAL/LPC1768/HAL.h
+++ b/Marlin/src/HAL/LPC1768/HAL.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -41,13 +41,15 @@ extern "C" volatile uint32_t _millis;
#include "../shared/HAL_SPI.h"
#include "fastio.h"
#include "watchdog.h"
-#include "timers.h"
#include "MarlinSerial.h"
#include
#include
#include
+// i2c uses 8-bit shifted address
+#define I2C_ADDRESS(A) uint8_t((A) << 1)
+
//
// Default graphical display delays
//
@@ -148,6 +150,8 @@ int freeMemory();
// K = 6, 565 samples, 500Hz sample rate, 1.13s convergence on full range step
// Memory usage per ADC channel (bytes): 4 (32 Bytes for 8 channels)
+#define HAL_ADC_VREF 3.3 // ADC voltage reference
+
#define HAL_ADC_RESOLUTION 12 // 15 bit maximum, raw temperature is stored as int16_t
#define HAL_ADC_FILTERED // Disable oversampling done in Marlin as ADC values already filtered in HAL
@@ -197,6 +201,8 @@ void HAL_idletask();
#define PLATFORM_M997_SUPPORT
void flashFirmware(const int16_t);
+#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment
+
/**
* set_pwm_frequency
* Set the frequency of the timer corresponding to the provided pin
@@ -216,3 +222,8 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255,
// Reset source
void HAL_clear_reset_source(void);
uint8_t HAL_get_reset_source(void);
+
+// Add strcmp_P if missing
+#ifndef strcmp_P
+ #define strcmp_P(a, b) strcmp((a), (b))
+#endif
diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp
index 1c20e7f65..e34a10201 100644
--- a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp
+++ b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -209,11 +209,11 @@
}
-#endif // ENABLED(LPC_SOFTWARE_SPI)
+#endif // LPC_SOFTWARE_SPI
void SPIClass::begin() { spiBegin(); }
-void SPIClass::beginTransaction(SPISettings cfg) {
+void SPIClass::beginTransaction(const SPISettings &cfg) {
uint8_t spiRate;
switch (cfg.spiRate()) {
case 8000000: spiRate = 0; break;
diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.cpp b/Marlin/src/HAL/LPC1768/MarlinSerial.cpp
index 1b80b211f..c3fb3bd0e 100644
--- a/Marlin/src/HAL/LPC1768/MarlinSerial.cpp
+++ b/Marlin/src/HAL/LPC1768/MarlinSerial.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef TARGET_LPC1768
#include "../../inc/MarlinConfigPre.h"
diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.h b/Marlin/src/HAL/LPC1768/MarlinSerial.h
index b6bbf8e45..98ce73d37 100644
--- a/Marlin/src/HAL/LPC1768/MarlinSerial.h
+++ b/Marlin/src/HAL/LPC1768/MarlinSerial.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -44,10 +44,9 @@ public:
MarlinSerial(LPC_UART_TypeDef *UARTx) :
HardwareSerial(UARTx)
#if ENABLED(EMERGENCY_PARSER)
- , emergency_state(EmergencyParser::State::EP_RESET)
+ , emergency_state(EmergencyParser::State::EP_RESET)
#endif
- {
- }
+ { }
void end() {}
diff --git a/Marlin/src/HAL/LPC1768/Servo.h b/Marlin/src/HAL/LPC1768/Servo.h
index 71e2bb569..e953cb920 100644
--- a/Marlin/src/HAL/LPC1768/Servo.h
+++ b/Marlin/src/HAL/LPC1768/Servo.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -60,9 +60,7 @@ class libServo: public Servo {
if (attach(servo_info[servoIndex].Pin.nbr) >= 0) { // try to reattach
write(value);
safe_delay(servo_delay[servoIndex]); // delay to allow servo to reach position
- #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
- detach();
- #endif
+ TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
}
}
diff --git a/Marlin/src/HAL/LPC1768/eeprom_flash.cpp b/Marlin/src/HAL/LPC1768/eeprom_flash.cpp
index 922580748..255848637 100644
--- a/Marlin/src/HAL/LPC1768/eeprom_flash.cpp
+++ b/Marlin/src/HAL/LPC1768/eeprom_flash.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#ifdef TARGET_LPC1768
@@ -40,24 +40,29 @@
#if ENABLED(FLASH_EEPROM_EMULATION)
-#include "eeprom_api.h"
+#include "../shared/eeprom_api.h"
extern "C" {
#include
}
-#define SECTOR_START(sector) ((sector < 16) ? (sector * 0x1000) : ((sector - 14) * 0x8000))
-#define EEPROM_SECTOR 29
-#define EEPROM_SIZE (4096)
-#define SECTOR_SIZE (32768)
-#define EEPROM_SLOTS (SECTOR_SIZE/EEPROM_SIZE)
-#define EEPROM_ERASE (0xFF)
-#define SLOT_ADDRESS(sector, slot) (((uint8_t *)SECTOR_START(sector)) + slot * EEPROM_SIZE)
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE 0x1000 // 4KB
+#endif
-static uint8_t ram_eeprom[EEPROM_SIZE] __attribute__((aligned(4))) = {0};
+#define SECTOR_START(sector) ((sector < 16) ? (sector << 12) : ((sector - 14) << 15))
+#define EEPROM_SECTOR 29
+#define SECTOR_SIZE 32768
+#define EEPROM_SLOTS ((SECTOR_SIZE)/(MARLIN_EEPROM_SIZE))
+#define EEPROM_ERASE 0xFF
+#define SLOT_ADDRESS(sector, slot) (((uint8_t *)SECTOR_START(sector)) + slot * (MARLIN_EEPROM_SIZE))
+
+static uint8_t ram_eeprom[MARLIN_EEPROM_SIZE] __attribute__((aligned(4))) = {0};
static bool eeprom_dirty = false;
static int current_slot = 0;
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+
bool PersistentStore::access_start() {
uint32_t first_nblank_loc, first_nblank_val;
IAP_STATUS_CODE status;
@@ -69,15 +74,15 @@ bool PersistentStore::access_start() {
if (status == CMD_SUCCESS) {
// sector is blank so nothing stored yet
- for (int i = 0; i < EEPROM_SIZE; i++) ram_eeprom[i] = EEPROM_ERASE;
+ for (int i = 0; i < MARLIN_EEPROM_SIZE; i++) ram_eeprom[i] = EEPROM_ERASE;
current_slot = EEPROM_SLOTS;
}
else {
// current slot is the first non blank one
- current_slot = first_nblank_loc / EEPROM_SIZE;
+ current_slot = first_nblank_loc / (MARLIN_EEPROM_SIZE);
uint8_t *eeprom_data = SLOT_ADDRESS(EEPROM_SECTOR, current_slot);
// load current settings
- for (int i = 0; i < EEPROM_SIZE; i++) ram_eeprom[i] = eeprom_data[i];
+ for (int i = 0; i < MARLIN_EEPROM_SIZE; i++) ram_eeprom[i] = eeprom_data[i];
}
eeprom_dirty = false;
@@ -122,7 +127,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
return false; // return true for any error
}
-size_t PersistentStore::capacity() { return EEPROM_SIZE; }
-
#endif // FLASH_EEPROM_EMULATION
#endif // TARGET_LPC1768
diff --git a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp
index d982bd626..9f2475f49 100644
--- a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp
+++ b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#ifdef TARGET_LPC1768
@@ -26,7 +26,7 @@
#if ENABLED(SDCARD_EEPROM_EMULATION)
-#include "eeprom_api.h"
+#include "../shared/eeprom_api.h"
#include
#include
@@ -38,6 +38,11 @@ FATFS fat_fs;
FIL eeprom_file;
bool eeprom_file_open = false;
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE size_t(0x1000) // 4KiB of Emulated EEPROM
+#endif
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+
bool PersistentStore::access_start() {
const char eeprom_erase_value = 0xFF;
MSC_Aquire_Lock();
@@ -79,21 +84,16 @@ static void debug_rw(const bool write, int &pos, const uint8_t *value, const siz
PGM_P const rw_str = write ? PSTR("write") : PSTR("read");
SERIAL_CHAR(' ');
serialprintPGM(rw_str);
- SERIAL_ECHOPAIR("_data(", pos);
- SERIAL_ECHOPAIR(",", (int)value);
- SERIAL_ECHOPAIR(",", (int)size);
- SERIAL_ECHOLNPGM(", ...)");
+ SERIAL_ECHOLNPAIR("_data(", pos, ",", int(value), ",", int(size), ", ...)");
if (total) {
SERIAL_ECHOPGM(" f_");
serialprintPGM(rw_str);
- SERIAL_ECHOPAIR("()=", (int)s);
- SERIAL_ECHOPAIR("\n size=", size);
- SERIAL_ECHOPGM("\n bytes_");
+ SERIAL_ECHOPAIR("()=", int(s), "\n size=", int(size), "\n bytes_");
serialprintPGM(write ? PSTR("written=") : PSTR("read="));
SERIAL_ECHOLN(total);
}
else
- SERIAL_ECHOLNPAIR(" f_lseek()=", (int)s);
+ SERIAL_ECHOLNPAIR(" f_lseek()=", int(s));
}
// File function return codes for type FRESULT. This goes away soon, but
@@ -173,7 +173,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin
return bytes_read != size; // return true for any error
}
-size_t PersistentStore::capacity() { return 4096; } // 4KiB of Emulated EEPROM
-
#endif // SDCARD_EEPROM_EMULATION
#endif // TARGET_LPC1768
diff --git a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp
new file mode 100644
index 000000000..16c15eaf0
--- /dev/null
+++ b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp
@@ -0,0 +1,81 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#ifdef TARGET_LPC1768
+
+#include "../../inc/MarlinConfig.h"
+
+#if USE_WIRED_EEPROM
+
+/**
+ * PersistentStore for Arduino-style EEPROM interface
+ * with implementations supplied by the framework.
+ */
+
+#include "../shared/eeprom_if.h"
+#include "../shared/eeprom_api.h"
+
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE 0x8000 // 32KB
+#endif
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+
+bool PersistentStore::access_start() { eeprom_init(); return true; }
+bool PersistentStore::access_finish() { return true; }
+
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ while (size--) {
+ uint8_t v = *value;
+
+ // EEPROM has only ~100,000 write cycles,
+ // so only write bytes that have changed!
+ uint8_t * const p = (uint8_t * const)pos;
+ if (v != eeprom_read_byte(p)) {
+ eeprom_write_byte(p, v);
+ if (eeprom_read_byte(p) != v) {
+ SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
+ return true;
+ }
+ }
+
+ crc16(crc, &v, 1);
+ pos++;
+ value++;
+ };
+
+ return false;
+}
+
+bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
+ do {
+ // Read from external EEPROM
+ const uint8_t c = eeprom_read_byte((uint8_t*)pos);
+
+ if (writing) *value = c;
+ crc16(crc, &c, 1);
+ pos++;
+ value++;
+ } while (--size);
+ return false;
+}
+
+#endif // USE_WIRED_EEPROM
+#endif // TARGET_LPC1768
diff --git a/Marlin/src/HAL/LPC1768/endstop_interrupts.h b/Marlin/src/HAL/LPC1768/endstop_interrupts.h
index 4c4e9bd3f..b0d0c0ec5 100644
--- a/Marlin/src/HAL/LPC1768/endstop_interrupts.h
+++ b/Marlin/src/HAL/LPC1768/endstop_interrupts.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LPC1768/fast_pwm.cpp b/Marlin/src/HAL/LPC1768/fast_pwm.cpp
index a1feb2590..46507ac0d 100644
--- a/Marlin/src/HAL/LPC1768/fast_pwm.cpp
+++ b/Marlin/src/HAL/LPC1768/fast_pwm.cpp
@@ -16,15 +16,14 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef TARGET_LPC1768
#include "../../inc/MarlinConfigPre.h"
-#if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_PWM
+#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM
#include
diff --git a/Marlin/src/HAL/LPC1768/fastio.h b/Marlin/src/HAL/LPC1768/fastio.h
index 1772881b3..c553ffb18 100644
--- a/Marlin/src/HAL/LPC1768/fastio.h
+++ b/Marlin/src/HAL/LPC1768/fastio.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h
+++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h
+++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h
index 490cfd50e..ce6d3fdde 100644
--- a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h
+++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h
@@ -16,11 +16,13 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
-#if USE_FALLBACK_EEPROM && NONE(SDCARD_EEPROM_EMULATION, SRAM_EEPROM_EMULATION)
+#if USE_FALLBACK_EEPROM
#define FLASH_EEPROM_EMULATION
+#elif EITHER(I2C_EEPROM, SPI_EEPROM)
+ #define USE_SHARED_EEPROM 1
#endif
diff --git a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h
index 949c7f489..964538962 100644
--- a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h
+++ b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -174,7 +174,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o
//
// Flag any i2c pin conflicts
//
-#if ANY(DIGIPOT_I2C, DIGIPOT_MCP4018, DAC_STEPPER_CURRENT, EXPERIMENTAL_I2CBUS, I2C_POSITION_ENCODERS, PCA9632, I2C_EEPROM)
+#if ANY(HAS_I2C_DIGIPOT, DAC_STEPPER_CURRENT, EXPERIMENTAL_I2CBUS, I2C_POSITION_ENCODERS, PCA9632, I2C_EEPROM)
#define USEDI2CDEV_M 1 // /Wire.cpp
#if USEDI2CDEV_M == 0 // P0_27 [D57] (AUX-1) .......... P0_28 [D58] (AUX-1)
@@ -251,3 +251,9 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o
#undef USEDI2CDEV_M
#endif
+
+#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
+ #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on this platform."
+#elif ENABLED(SERIAL_STATS_DROPPED_RX)
+ #error "SERIAL_STATS_DROPPED_RX is not supported on this platform."
+#endif
diff --git a/Marlin/src/HAL/LPC1768/include/SPI.h b/Marlin/src/HAL/LPC1768/include/SPI.h
index af085f29a..4acd9e702 100644
--- a/Marlin/src/HAL/LPC1768/include/SPI.h
+++ b/Marlin/src/HAL/LPC1768/include/SPI.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -31,7 +31,7 @@
class SPISettings {
public:
SPISettings(uint32_t speed, int, int) : spi_speed(speed) {};
- uint32_t spiRate() { return spi_speed; }
+ uint32_t spiRate() const { return spi_speed; }
private:
uint32_t spi_speed;
};
@@ -39,7 +39,7 @@ class SPISettings {
class SPIClass {
public:
void begin();
- void beginTransaction(SPISettings);
+ void beginTransaction(const SPISettings&);
void endTransaction() {};
uint8_t transfer(uint8_t data);
uint16_t transfer16(uint16_t data);
diff --git a/Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.c b/Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.c
index 1e53be5f6..f442ab71c 100644
--- a/Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.c
+++ b/Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.c
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.h b/Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.h
index 6e9ad6f17..9b6c62b05 100644
--- a/Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.h
+++ b/Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LPC1768/include/i2c_util.c b/Marlin/src/HAL/LPC1768/include/i2c_util.c
index b92f3f045..e52fb7c4d 100644
--- a/Marlin/src/HAL/LPC1768/include/i2c_util.c
+++ b/Marlin/src/HAL/LPC1768/include/i2c_util.c
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/LPC1768/include/i2c_util.h b/Marlin/src/HAL/LPC1768/include/i2c_util.h
index eae275e0f..a57f68a40 100644
--- a/Marlin/src/HAL/LPC1768/include/i2c_util.h
+++ b/Marlin/src/HAL/LPC1768/include/i2c_util.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp
index d7b05dce9..0b4045cb9 100644
--- a/Marlin/src/HAL/LPC1768/main.cpp
+++ b/Marlin/src/HAL/LPC1768/main.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#ifdef TARGET_LPC1768
@@ -38,8 +38,6 @@ extern "C" {
#include "../../sd/cardreader.h"
#include "../../inc/MarlinConfig.h"
#include "../../core/millis_t.h"
-#include "HAL.h"
-#include "timers.h"
extern uint32_t MSC_SD_Init(uint8_t pdrv);
extern "C" int isLPC1769();
@@ -124,7 +122,7 @@ void HAL_init() {
delay(1000); // Give OS time to notice
USB_Connect(TRUE);
- #if !BOTH(SHARED_SD_CARD, INIT_SDCARD_ON_BOOT) && DISABLED(NO_SD_HOST_DRIVE)
+ #if DISABLED(NO_SD_HOST_DRIVE)
MSC_SD_Init(0); // Enable USB SD card access
#endif
@@ -142,7 +140,7 @@ void HAL_init() {
// HAL idle task
void HAL_idletask() {
- #if ENABLED(SHARED_SD_CARD)
+ #if HAS_SHARED_MEDIA
// If Marlin is using the SD card we need to lock it to prevent access from
// a PC via USB.
// Other HALs use IS_SD_PRINTING() and IS_SD_FILE_OPEN() to check for access but
diff --git a/Marlin/src/HAL/LPC1768/pinsDebug.h b/Marlin/src/HAL/LPC1768/pinsDebug.h
index 6cc824afa..f80551604 100644
--- a/Marlin/src/HAL/LPC1768/pinsDebug.h
+++ b/Marlin/src/HAL/LPC1768/pinsDebug.h
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/LPC1768/spi_pins.h b/Marlin/src/HAL/LPC1768/spi_pins.h
index 9b983428b..2e6749bf5 100644
--- a/Marlin/src/HAL/LPC1768/spi_pins.h
+++ b/Marlin/src/HAL/LPC1768/spi_pins.h
@@ -16,14 +16,14 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
#include "../../core/macros.h"
-#if ENABLED(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_GRAPHICAL_LCD) && (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.cpp b/Marlin/src/HAL/LPC1768/timers.cpp
index 686b251c6..a7a40584d 100644
--- a/Marlin/src/HAL/LPC1768/timers.cpp
+++ b/Marlin/src/HAL/LPC1768/timers.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -29,7 +29,6 @@
#ifdef TARGET_LPC1768
#include "../../inc/MarlinConfig.h"
-#include "timers.h"
void HAL_timer_init() {
SBI(LPC_SC->PCONP, SBIT_TIMER0); // Power ON Timer 0
diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h
index 30da93352..23dc20e2e 100644
--- a/Marlin/src/HAL/LPC1768/timers.h
+++ b/Marlin/src/HAL/LPC1768/timers.h
@@ -15,7 +15,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -61,10 +61,18 @@ typedef uint32_t hal_timer_t;
#define HAL_TIMER_RATE ((F_CPU) / 4) // frequency of timers peripherals
-#define STEP_TIMER_NUM 0 // Timer Index for Stepper
-#define TEMP_TIMER_NUM 1 // Timer Index for Temperature
-#define PULSE_TIMER_NUM STEP_TIMER_NUM
-#define PWM_TIMER_NUM 3 // Timer Index for PWM
+#ifndef STEP_TIMER_NUM
+ #define STEP_TIMER_NUM 0 // Timer Index for Stepper
+#endif
+#ifndef PULSE_TIMER_NUM
+ #define PULSE_TIMER_NUM STEP_TIMER_NUM
+#endif
+#ifndef TEMP_TIMER_NUM
+ #define TEMP_TIMER_NUM 1 // Timer Index for Temperature
+#endif
+#ifndef PWM_TIMER_NUM
+ #define PWM_TIMER_NUM 3 // Timer Index for PWM
+#endif
#define TEMP_TIMER_RATE 1000000
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
@@ -84,12 +92,16 @@ typedef uint32_t hal_timer_t;
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
-#define HAL_STEP_TIMER_ISR() _HAL_TIMER_ISR(STEP_TIMER_NUM)
-#define HAL_TEMP_TIMER_ISR() _HAL_TIMER_ISR(TEMP_TIMER_NUM)
+#ifndef HAL_STEP_TIMER_ISR
+ #define HAL_STEP_TIMER_ISR() _HAL_TIMER_ISR(STEP_TIMER_NUM)
+#endif
+#ifndef HAL_TEMP_TIMER_ISR
+ #define HAL_TEMP_TIMER_ISR() _HAL_TIMER_ISR(TEMP_TIMER_NUM)
+#endif
// Timer references by index
-#define STEP_TIMER _HAL_TIMER(STEP_TIMER_NUM)
-#define TEMP_TIMER _HAL_TIMER(TEMP_TIMER_NUM)
+#define STEP_TIMER_PTR _HAL_TIMER(STEP_TIMER_NUM)
+#define TEMP_TIMER_PTR _HAL_TIMER(TEMP_TIMER_NUM)
// ------------------------
// Public functions
@@ -99,23 +111,23 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
switch (timer_num) {
- case 0: STEP_TIMER->MR0 = compare; break; // Stepper Timer Match Register 0
- case 1: TEMP_TIMER->MR0 = compare; break; // Temp Timer Match Register 0
+ case 0: STEP_TIMER_PTR->MR0 = compare; break; // Stepper Timer Match Register 0
+ case 1: TEMP_TIMER_PTR->MR0 = compare; break; // Temp Timer Match Register 0
}
}
FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
switch (timer_num) {
- case 0: return STEP_TIMER->MR0; // Stepper Timer Match Register 0
- case 1: return TEMP_TIMER->MR0; // Temp Timer Match Register 0
+ case 0: return STEP_TIMER_PTR->MR0; // Stepper Timer Match Register 0
+ case 1: return TEMP_TIMER_PTR->MR0; // Temp Timer Match Register 0
}
return 0;
}
FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
switch (timer_num) {
- case 0: return STEP_TIMER->TC; // Stepper Timer Count
- case 1: return TEMP_TIMER->TC; // Temp Timer Count
+ case 0: return STEP_TIMER_PTR->TC; // Stepper Timer Count
+ case 1: return TEMP_TIMER_PTR->TC; // Temp Timer Count
}
return 0;
}
@@ -154,8 +166,8 @@ FORCE_INLINE static bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
switch (timer_num) {
- case 0: SBI(STEP_TIMER->IR, SBIT_CNTEN); break;
- case 1: SBI(TEMP_TIMER->IR, SBIT_CNTEN); break;
+ case 0: SBI(STEP_TIMER_PTR->IR, SBIT_CNTEN); break;
+ case 1: SBI(TEMP_TIMER_PTR->IR, SBIT_CNTEN); break;
}
}
diff --git a/Marlin/src/HAL/LPC1768/u8g/LCD_I2C_routines.cpp b/Marlin/src/HAL/LPC1768/u8g/LCD_I2C_routines.cpp
index 6d643f5bf..a48a820dc 100644
--- a/Marlin/src/HAL/LPC1768/u8g/LCD_I2C_routines.cpp
+++ b/Marlin/src/HAL/LPC1768/u8g/LCD_I2C_routines.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/LPC1768/u8g/LCD_I2C_routines.h b/Marlin/src/HAL/LPC1768/u8g/LCD_I2C_routines.h
index 9de3e9327..2d976c92d 100644
--- a/Marlin/src/HAL/LPC1768/u8g/LCD_I2C_routines.h
+++ b/Marlin/src/HAL/LPC1768/u8g/LCD_I2C_routines.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LPC1768/u8g/LCD_defines.h b/Marlin/src/HAL/LPC1768/u8g/LCD_defines.h
index e7518d698..d2260037b 100644
--- a/Marlin/src/HAL/LPC1768/u8g/LCD_defines.h
+++ b/Marlin/src/HAL/LPC1768/u8g/LCD_defines.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LPC1768/u8g/LCD_delay.h b/Marlin/src/HAL/LPC1768/u8g/LCD_delay.h
index 0d9b8d3dc..0b9e2b4fd 100644
--- a/Marlin/src/HAL/LPC1768/u8g/LCD_delay.h
+++ b/Marlin/src/HAL/LPC1768/u8g/LCD_delay.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.c b/Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.c
index 67e78f36f..466fc8020 100644
--- a/Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.c
+++ b/Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.c
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.h b/Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.h
index 8a73b69de..d60d93dad 100644
--- a/Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.h
+++ b/Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
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 c0105bc12..befc348fa 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
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
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 b99abb686..f03be9ab3 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
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
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 5f3da457a..1500c22a0 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
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_sw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_sw_spi.cpp
index a1f8097e5..10d849416 100644
--- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_sw_spi.cpp
+++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_sw_spi.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
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 6eac5daf2..4f52f7dd0 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
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/LPC1768/usb_serial.cpp b/Marlin/src/HAL/LPC1768/usb_serial.cpp
index ddb31da20..63a570efd 100644
--- a/Marlin/src/HAL/LPC1768/usb_serial.cpp
+++ b/Marlin/src/HAL/LPC1768/usb_serial.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef TARGET_LPC1768
#include "../../inc/MarlinConfigPre.h"
diff --git a/Marlin/src/HAL/LPC1768/watchdog.cpp b/Marlin/src/HAL/LPC1768/watchdog.cpp
index 73563a6ba..3cd22d665 100644
--- a/Marlin/src/HAL/LPC1768/watchdog.cpp
+++ b/Marlin/src/HAL/LPC1768/watchdog.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef TARGET_LPC1768
#include "../../inc/MarlinConfig.h"
diff --git a/Marlin/src/HAL/LPC1768/watchdog.h b/Marlin/src/HAL/LPC1768/watchdog.h
index e9e25e4f2..cc170881f 100644
--- a/Marlin/src/HAL/LPC1768/watchdog.h
+++ b/Marlin/src/HAL/LPC1768/watchdog.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/SAMD51/HAL.cpp b/Marlin/src/HAL/SAMD51/HAL.cpp
index b3a741fe1..9f24d3007 100644
--- a/Marlin/src/HAL/SAMD51/HAL.cpp
+++ b/Marlin/src/HAL/SAMD51/HAL.cpp
@@ -15,10 +15,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __SAMD51__
#include "../../inc/MarlinConfig.h"
@@ -29,71 +28,19 @@
// Local defines
// ------------------------
-#if HAS_TEMP_ADC_0
- #define GET_TEMP_0_ADC() PIN_TO_ADC(TEMP_0_PIN)
-#else
- #define GET_TEMP_0_ADC() -1
-#endif
-#if HAS_TEMP_ADC_1
- #define GET_TEMP_1_ADC() PIN_TO_ADC(TEMP_1_PIN)
-#else
- #define GET_TEMP_1_ADC() -1
-#endif
-#if HAS_TEMP_ADC_2
- #define GET_TEMP_2_ADC() PIN_TO_ADC(TEMP_2_PIN)
-#else
- #define GET_TEMP_2_ADC() -1
-#endif
-#if HAS_TEMP_ADC_3
- #define GET_TEMP_3_ADC() PIN_TO_ADC(TEMP_3_PIN)
-#else
- #define GET_TEMP_3_ADC() -1
-#endif
-#if HAS_TEMP_ADC_4
- #define GET_TEMP_4_ADC() PIN_TO_ADC(TEMP_4_PIN)
-#else
- #define GET_TEMP_4_ADC() -1
-#endif
-#if HAS_TEMP_ADC_5
- #define GET_TEMP_5_ADC() PIN_TO_ADC(TEMP_5_PIN)
-#else
- #define GET_TEMP_5_ADC() -1
-#endif
-#if HAS_TEMP_ADC_6
- #define GET_TEMP_6_ADC() PIN_TO_ADC(TEMP_6_PIN)
-#else
- #define GET_TEMP_6_ADC() -1
-#endif
-#if HAS_TEMP_ADC_7
- #define GET_TEMP_7_ADC() PIN_TO_ADC(TEMP_7_PIN)
-#else
- #define GET_TEMP_7_ADC() -1
-#endif
-#if HAS_TEMP_PROBE
- #define GET_PROBE_ADC() PIN_TO_ADC(TEMP_PROBE_PIN)
-#else
- #define GET_PROBE_ADC() -1
-#endif
-#if HAS_TEMP_ADC_BED
- #define GET_BED_ADC() PIN_TO_ADC(TEMP_BED_PIN)
-#else
- #define GET_BED_ADC() -1
-#endif
-#if HAS_TEMP_ADC_CHAMBER
- #define GET_CHAMBER_ADC() PIN_TO_ADC(TEMP_CHAMBER_PIN)
-#else
- #define GET_CHAMBER_ADC() -1
-#endif
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
- #define GET_FILAMENT_WIDTH_ADC() PIN_TO_ADC(FILWIDTH_PIN)
-#else
- #define GET_FILAMENT_WIDTH_ADC() -1
-#endif
-#if HAS_ADC_BUTTONS
- #define GET_BUTTONS_ADC() PIN_TO_ADC(ADC_KEYPAD_PIN)
-#else
- #define GET_BUTTONS_ADC() -1
-#endif
+#define GET_TEMP_0_ADC() TERN(HAS_TEMP_ADC_0, PIN_TO_ADC(TEMP_0_PIN), -1)
+#define GET_TEMP_1_ADC() TERN(HAS_TEMP_ADC_1, PIN_TO_ADC(TEMP_1_PIN), -1)
+#define GET_TEMP_2_ADC() TERN(HAS_TEMP_ADC_2, PIN_TO_ADC(TEMP_2_PIN), -1)
+#define GET_TEMP_3_ADC() TERN(HAS_TEMP_ADC_3, PIN_TO_ADC(TEMP_3_PIN), -1)
+#define GET_TEMP_4_ADC() TERN(HAS_TEMP_ADC_4, PIN_TO_ADC(TEMP_4_PIN), -1)
+#define GET_TEMP_5_ADC() TERN(HAS_TEMP_ADC_5, PIN_TO_ADC(TEMP_5_PIN), -1)
+#define GET_TEMP_6_ADC() TERN(HAS_TEMP_ADC_6, PIN_TO_ADC(TEMP_6_PIN), -1)
+#define GET_TEMP_7_ADC() TERN(HAS_TEMP_ADC_7, PIN_TO_ADC(TEMP_7_PIN), -1)
+#define GET_PROBE_ADC() TERN(HAS_TEMP_PROBE, PIN_TO_ADC(TEMP_PROBE_PIN), -1)
+#define GET_BED_ADC() TERN(HAS_TEMP_ADC_BED, PIN_TO_ADC(TEMP_BED_PIN), -1)
+#define GET_CHAMBER_ADC() TERN(HAS_TEMP_ADC_CHAMBER, PIN_TO_ADC(TEMP_CHAMBER_PIN), -1)
+#define GET_FILAMENT_WIDTH_ADC() TERN(FILAMENT_WIDTH_SENSOR, PIN_TO_ADC(FILWIDTH_PIN), -1)
+#define GET_BUTTONS_ADC() TERN(HAS_ADC_BUTTONS, PIN_TO_ADC(ADC_KEYPAD_PIN), -1)
#define IS_ADC_REQUIRED(n) ( \
GET_TEMP_0_ADC() == n || GET_TEMP_1_ADC() == n || GET_TEMP_2_ADC() == n || GET_TEMP_3_ADC() == n \
@@ -105,21 +52,22 @@
|| GET_BUTTONS_ADC() == n \
)
-#define ADC0_IS_REQUIRED IS_ADC_REQUIRED(0)
-#define ADC1_IS_REQUIRED IS_ADC_REQUIRED(1)
-#define ADC_IS_REQUIRED (ADC0_IS_REQUIRED || ADC1_IS_REQUIRED)
-#if ADC0_IS_REQUIRED
+#if IS_ADC_REQUIRED(0)
+ #define ADC0_IS_REQUIRED 1
#define FIRST_ADC 0
#else
#define FIRST_ADC 1
#endif
-#if ADC1_IS_REQUIRED
+#if IS_ADC_REQUIRED(1)
+ #define ADC1_IS_REQUIRED 1
#define LAST_ADC 1
#else
#define LAST_ADC 0
#endif
-
-#define DMA_IS_REQUIRED ADC_IS_REQUIRED
+#if ADC0_IS_REQUIRED || ADC1_IS_REQUIRED
+ #define ADC_IS_REQUIRED 1
+ #define DMA_IS_REQUIRED 1
+#endif
// ------------------------
// Types
@@ -423,9 +371,7 @@ uint16_t HAL_adc_result;
// HAL initialization task
void HAL_init() {
- #if DMA_IS_REQUIRED
- dma_init();
- #endif
+ TERN_(DMA_IS_REQUIRED, dma_init());
#if ENABLED(SDSUPPORT)
#if SD_CONNECTION_IS(ONBOARD) && PIN_EXISTS(SD_DETECT)
SET_INPUT_PULLUP(SD_DETECT_PIN);
diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h
index f2ee02a22..ea0f694cd 100644
--- a/Marlin/src/HAL/SAMD51/HAL.h
+++ b/Marlin/src/HAL/SAMD51/HAL.h
@@ -15,7 +15,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -27,7 +27,6 @@
#include "../shared/HAL_SPI.h"
#include "fastio.h"
#include "watchdog.h"
-#include "timers.h"
#ifdef ADAFRUIT_GRAND_CENTRAL_M4
#include "MarlinSerial_AGCM4.h"
@@ -113,12 +112,6 @@ typedef int8_t pin_t;
void HAL_clear_reset_source(); // clear reset reason
uint8_t HAL_get_reset_source(); // get reset reason
-//
-// EEPROM
-//
-void eeprom_write_byte(uint8_t *pos, unsigned char value);
-uint8_t eeprom_read_byte(uint8_t *pos);
-
//
// ADC
//
@@ -129,13 +122,13 @@ extern uint16_t HAL_adc_result; // Most recent ADC conversion
void HAL_adc_init();
//#define HAL_ADC_FILTERED // Disable Marlin's oversampling. The HAL filters ADC values.
+#define HAL_ADC_VREF 3.3
#define HAL_ADC_RESOLUTION 10 // ... 12
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true
void HAL_adc_start_conversion(const uint8_t adc_pin);
-inline uint16_t HAL_adc_get_result() { return HAL_adc_result; }
//
// Pin Map
diff --git a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp
index 83226daa4..c3acd3823 100644
--- a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp
+++ b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp
@@ -15,7 +15,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp
index f13b29555..abc5f3acb 100644
--- a/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp
+++ b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp
@@ -15,10 +15,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef ADAFRUIT_GRAND_CENTRAL_M4
/**
diff --git a/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.h b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.h
index a9eb0470a..f3821d8d5 100644
--- a/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.h
+++ b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.h
@@ -15,7 +15,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/SAMD51/QSPIFlash.cpp b/Marlin/src/HAL/SAMD51/QSPIFlash.cpp
index 76a332970..161c04084 100644
--- a/Marlin/src/HAL/SAMD51/QSPIFlash.cpp
+++ b/Marlin/src/HAL/SAMD51/QSPIFlash.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/SAMD51/QSPIFlash.h b/Marlin/src/HAL/SAMD51/QSPIFlash.h
index 7f75286eb..b6f22769f 100644
--- a/Marlin/src/HAL/SAMD51/QSPIFlash.h
+++ b/Marlin/src/HAL/SAMD51/QSPIFlash.h
@@ -29,7 +29,7 @@
#pragma once
-#include "Adafruit_SPIFlashBase.h"
+#include
// This class extends Adafruit_SPIFlashBase by adding caching support.
//
diff --git a/Marlin/src/HAL/SAMD51/SAMD51.h b/Marlin/src/HAL/SAMD51/SAMD51.h
index ef84a2082..783956140 100644
--- a/Marlin/src/HAL/SAMD51/SAMD51.h
+++ b/Marlin/src/HAL/SAMD51/SAMD51.h
@@ -15,7 +15,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/SAMD51/Servo.cpp b/Marlin/src/HAL/SAMD51/Servo.cpp
index b39869ef3..9bab8e89b 100644
--- a/Marlin/src/HAL/SAMD51/Servo.cpp
+++ b/Marlin/src/HAL/SAMD51/Servo.cpp
@@ -15,7 +15,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -29,11 +29,9 @@
#if HAS_SERVOS
-#include "../shared/Marduino.h"
#include "../shared/servo.h"
#include "../shared/servo_private.h"
#include "SAMD51.h"
-#include "timers.h"
#define __TC_GCLK_ID(t) TC##t##_GCLK_ID
#define _TC_GCLK_ID(t) __TC_GCLK_ID(t)
@@ -55,7 +53,7 @@
static volatile int8_t currentServoIndex[_Nbr_16timers]; // index for the servo being pulsed for each timer (or -1 if refresh interval)
FORCE_INLINE static uint16_t getTimerCount() {
- Tc * const tc = TimerConfig[SERVO_TC].pTimer;
+ Tc * const tc = TimerConfig[SERVO_TC].pTc;
tc->COUNT16.CTRLBSET.reg = TC_CTRLBCLR_CMD_READSYNC;
SYNC(tc->COUNT16.SYNCBUSY.bit.CTRLB || tc->COUNT16.SYNCBUSY.bit.COUNT);
@@ -67,7 +65,7 @@ FORCE_INLINE static uint16_t getTimerCount() {
// Interrupt handler for the TC
// ----------------------------
HAL_SERVO_TIMER_ISR() {
- Tc * const tc = TimerConfig[SERVO_TC].pTimer;
+ Tc * const tc = TimerConfig[SERVO_TC].pTc;
const timer16_Sequence_t timer =
#ifndef _useTimer1
_timer2
@@ -127,7 +125,7 @@ HAL_SERVO_TIMER_ISR() {
}
void initISR(timer16_Sequence_t timer) {
- Tc * const tc = TimerConfig[SERVO_TC].pTimer;
+ Tc * const tc = TimerConfig[SERVO_TC].pTc;
const uint8_t tcChannel = TIMER_TCCHANNEL(timer);
static bool initialized = false; // Servo TC has been initialized
@@ -204,7 +202,7 @@ void initISR(timer16_Sequence_t timer) {
}
void finISR(timer16_Sequence_t timer) {
- Tc * const tc = TimerConfig[SERVO_TC].pTimer;
+ Tc * const tc = TimerConfig[SERVO_TC].pTc;
const uint8_t tcChannel = TIMER_TCCHANNEL(timer);
// Disable the match channel interrupt request
diff --git a/Marlin/src/HAL/SAMD51/ServoTimers.h b/Marlin/src/HAL/SAMD51/ServoTimers.h
index 3572c608d..948d51535 100644
--- a/Marlin/src/HAL/SAMD51/ServoTimers.h
+++ b/Marlin/src/HAL/SAMD51/ServoTimers.h
@@ -15,7 +15,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/SAMD51/eeprom_flash.cpp b/Marlin/src/HAL/SAMD51/eeprom_flash.cpp
index fd8973369..429ef1c2d 100644
--- a/Marlin/src/HAL/SAMD51/eeprom_flash.cpp
+++ b/Marlin/src/HAL/SAMD51/eeprom_flash.cpp
@@ -15,10 +15,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __SAMD51__
#include "../../inc/MarlinConfig.h"
diff --git a/Marlin/src/HAL/SAMD51/eeprom_qspi.cpp b/Marlin/src/HAL/SAMD51/eeprom_qspi.cpp
index c6aa383f9..b403f7939 100644
--- a/Marlin/src/HAL/SAMD51/eeprom_qspi.cpp
+++ b/Marlin/src/HAL/SAMD51/eeprom_qspi.cpp
@@ -15,7 +15,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#ifdef __SAMD51__
diff --git a/Marlin/src/HAL/SAMD51/eeprom.cpp b/Marlin/src/HAL/SAMD51/eeprom_wired.cpp
similarity index 76%
rename from Marlin/src/HAL/SAMD51/eeprom.cpp
rename to Marlin/src/HAL/SAMD51/eeprom_wired.cpp
index e167515bf..328319589 100644
--- a/Marlin/src/HAL/SAMD51/eeprom.cpp
+++ b/Marlin/src/HAL/SAMD51/eeprom_wired.cpp
@@ -15,21 +15,29 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __SAMD51__
#include "../../inc/MarlinConfig.h"
-#if ENABLED(EEPROM_SETTINGS) && NONE(QSPI_EEPROM, FLASH_EEPROM_EMULATION)
+#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"
-size_t PersistentStore::capacity() { return E2END + 1; }
+#ifndef MARLIN_EEPROM_SIZE
+ #error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM."
+#endif
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
-bool PersistentStore::access_start() { return true; }
+bool PersistentStore::access_start() { eeprom_init(); return true; }
bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
@@ -62,5 +70,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
return false;
}
-#endif // EEPROM_SETTINGS && !(QSPI_EEPROM || FLASH_EEPROM_EMULATION)
+#endif // USE_WIRED_EEPROM
#endif // __SAMD51__
diff --git a/Marlin/src/HAL/SAMD51/endstop_interrupts.h b/Marlin/src/HAL/SAMD51/endstop_interrupts.h
index 4c8f441ce..03c246945 100644
--- a/Marlin/src/HAL/SAMD51/endstop_interrupts.h
+++ b/Marlin/src/HAL/SAMD51/endstop_interrupts.h
@@ -15,7 +15,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/SAMD51/fastio.h b/Marlin/src/HAL/SAMD51/fastio.h
index d3b3dc1f6..c456dfce3 100644
--- a/Marlin/src/HAL/SAMD51/fastio.h
+++ b/Marlin/src/HAL/SAMD51/fastio.h
@@ -15,7 +15,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/SAMD51/inc/Conditionals_LCD.h b/Marlin/src/HAL/SAMD51/inc/Conditionals_LCD.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/SAMD51/inc/Conditionals_LCD.h
+++ b/Marlin/src/HAL/SAMD51/inc/Conditionals_LCD.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/SAMD51/inc/Conditionals_adv.h b/Marlin/src/HAL/SAMD51/inc/Conditionals_adv.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/SAMD51/inc/Conditionals_adv.h
+++ b/Marlin/src/HAL/SAMD51/inc/Conditionals_adv.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h b/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h
index 490cfd50e..ce6d3fdde 100644
--- a/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h
+++ b/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h
@@ -16,11 +16,13 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
-#if USE_FALLBACK_EEPROM && NONE(SDCARD_EEPROM_EMULATION, SRAM_EEPROM_EMULATION)
+#if USE_FALLBACK_EEPROM
#define FLASH_EEPROM_EMULATION
+#elif EITHER(I2C_EEPROM, SPI_EEPROM)
+ #define USE_SHARED_EEPROM 1
#endif
diff --git a/Marlin/src/HAL/SAMD51/inc/SanityCheck.h b/Marlin/src/HAL/SAMD51/inc/SanityCheck.h
index cc7a10e7a..ee04e2e2e 100644
--- a/Marlin/src/HAL/SAMD51/inc/SanityCheck.h
+++ b/Marlin/src/HAL/SAMD51/inc/SanityCheck.h
@@ -15,7 +15,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -35,6 +35,10 @@
#error "OnBoard SPI BUS can't be shared with other devices."
#endif
+#if SERVO_TC == RTC_TIMER_NUM
+ #error "Servos can't use RTC timer"
+#endif
+
#if ENABLED(EMERGENCY_PARSER)
#error "EMERGENCY_PARSER is not yet implemented for SAMD51. Disable EMERGENCY_PARSER to continue."
#endif
diff --git a/Marlin/src/HAL/SAMD51/pinsDebug.h b/Marlin/src/HAL/SAMD51/pinsDebug.h
index 15b647338..c28937d6c 100644
--- a/Marlin/src/HAL/SAMD51/pinsDebug.h
+++ b/Marlin/src/HAL/SAMD51/pinsDebug.h
@@ -15,7 +15,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/SAMD51/spi_pins.h b/Marlin/src/HAL/SAMD51/spi_pins.h
index 049aacb57..5a9b1275e 100644
--- a/Marlin/src/HAL/SAMD51/spi_pins.h
+++ b/Marlin/src/HAL/SAMD51/spi_pins.h
@@ -15,7 +15,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/SAMD51/timers.cpp b/Marlin/src/HAL/SAMD51/timers.cpp
index 3eb021c25..a68af2e07 100644
--- a/Marlin/src/HAL/SAMD51/timers.cpp
+++ b/Marlin/src/HAL/SAMD51/timers.cpp
@@ -15,17 +15,17 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __SAMD51__
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
+
#include "../../inc/MarlinConfig.h"
-#include "timers.h"
+#include "ServoTimers.h" // for SERVO_TC
// --------------------------------------------------------------------------
// Local defines
@@ -38,15 +38,15 @@
// --------------------------------------------------------------------------
const tTimerConfig TimerConfig[NUM_HARDWARE_TIMERS+1] = {
- { {.pTc=TC0}, TC0_IRQn, TC_PRIORITY(0) }, // 0 - stepper
+ { {.pTc=TC0}, TC0_IRQn, TC_PRIORITY(0) }, // 0 - stepper (assigned priority 2)
{ {.pTc=TC1}, TC1_IRQn, TC_PRIORITY(1) }, // 1 - stepper (needed by 32 bit timers)
- { {.pTc=TC2}, TC2_IRQn, TC_PRIORITY(2) }, // 2 - tone (framework)
- { {.pTc=TC3}, TC3_IRQn, TC_PRIORITY(3) }, // 3 - servo
- { {.pTc=TC4}, TC4_IRQn, TC_PRIORITY(4) }, // 4 - software serial
+ { {.pTc=TC2}, TC2_IRQn, 5 }, // 2 - tone (reserved by framework and fixed assigned priority 5)
+ { {.pTc=TC3}, TC3_IRQn, TC_PRIORITY(3) }, // 3 - servo (assigned priority 1)
+ { {.pTc=TC4}, TC4_IRQn, TC_PRIORITY(4) }, // 4 - software serial (no interrupts used)
{ {.pTc=TC5}, TC5_IRQn, TC_PRIORITY(5) },
{ {.pTc=TC6}, TC6_IRQn, TC_PRIORITY(6) },
{ {.pTc=TC7}, TC7_IRQn, TC_PRIORITY(7) },
- { {.pRtc=RTC}, RTC_IRQn, TC_PRIORITY(8) } // 8 - temperature
+ { {.pRtc=RTC}, RTC_IRQn, TC_PRIORITY(8) } // 8 - temperature (assigned priority 6)
};
// --------------------------------------------------------------------------
@@ -121,14 +121,15 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
tc->COUNT32.CTRLA.bit.SWRST = true;
SYNC(tc->COUNT32.SYNCBUSY.bit.SWRST);
- // Wave mode, reset counter on overflow on 0 (I use count down to prevent double buffer use)
+ // Wave mode, reset counter on compare match
tc->COUNT32.WAVE.reg = TC_WAVE_WAVEGEN_MFRQ;
tc->COUNT32.CTRLA.reg = TC_CTRLA_MODE_COUNT32 | TC_CTRLA_PRESCALER_DIV1;
- tc->COUNT32.CTRLBSET.reg = TC_CTRLBCLR_DIR;
+ tc->COUNT32.CTRLBCLR.reg = TC_CTRLBCLR_DIR;
SYNC(tc->COUNT32.SYNCBUSY.bit.CTRLB);
// Set compare value
- tc->COUNT32.COUNT.reg = tc->COUNT32.CC[0].reg = (HAL_TIMER_RATE) / frequency;
+ tc->COUNT32.CC[0].reg = (HAL_TIMER_RATE) / frequency;
+ tc->COUNT32.COUNT.reg = 0;
// Enable interrupt on compare
tc->COUNT32.INTFLAG.reg = TC_INTFLAG_OVF; // reset pending interrupt
diff --git a/Marlin/src/HAL/SAMD51/timers.h b/Marlin/src/HAL/SAMD51/timers.h
index 4b21e4716..dc6e38b73 100644
--- a/Marlin/src/HAL/SAMD51/timers.h
+++ b/Marlin/src/HAL/SAMD51/timers.h
@@ -15,7 +15,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -32,9 +32,15 @@ typedef uint32_t hal_timer_t;
#define HAL_TIMER_RATE F_CPU // frequency of timers peripherals
-#define STEP_TIMER_NUM 0 // index of timer to use for stepper (also +1 for 32bits counter)
-#define PULSE_TIMER_NUM STEP_TIMER_NUM
-#define TEMP_TIMER_NUM RTC_TIMER_NUM // index of timer to use for temperature
+#ifndef STEP_TIMER_NUM
+ #define STEP_TIMER_NUM 0 // Timer Index for Stepper
+#endif
+#ifndef PULSE_TIMER_NUM
+ #define PULSE_TIMER_NUM STEP_TIMER_NUM
+#endif
+#ifndef TEMP_TIMER_NUM
+ #define TEMP_TIMER_NUM RTC_TIMER_NUM // Timer Index for Temperature
+#endif
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
@@ -53,20 +59,23 @@ typedef uint32_t hal_timer_t;
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
-#define TC_PRIORITY(t) (t == STEP_TIMER_NUM || t == PULSE_TIMER_NUM) ? 2 \
- : (t == TEMP_TIMER_NUM) ? 6 \
+#define TC_PRIORITY(t) t == SERVO_TC ? 1 \
+ : (t == STEP_TIMER_NUM || t == PULSE_TIMER_NUM) ? 2 \
+ : (t == TEMP_TIMER_NUM) ? 6 \
: 7
-#define _TC_HANDLER(t) void TC##t##_Handler()
-#define TC_HANDLER(t) _TC_HANDLER(t)
-#define HAL_STEP_TIMER_ISR() TC_HANDLER(STEP_TIMER_NUM)
+#define _TC_HANDLER(t) void TC##t##_Handler()
+#define TC_HANDLER(t) _TC_HANDLER(t)
+#ifndef HAL_STEP_TIMER_ISR
+ #define HAL_STEP_TIMER_ISR() TC_HANDLER(STEP_TIMER_NUM)
+#endif
#if STEP_TIMER_NUM != PULSE_TIMER_NUM
- #define HAL_PULSE_TIMER_ISR() TC_HANDLER(PULSE_TIMER_NUM)
+ #define HAL_PULSE_TIMER_ISR() TC_HANDLER(PULSE_TIMER_NUM)
#endif
#if TEMP_TIMER_NUM == RTC_TIMER_NUM
- #define HAL_TEMP_TIMER_ISR() void RTC_Handler()
+ #define HAL_TEMP_TIMER_ISR() void RTC_Handler()
#else
- #define HAL_TEMP_TIMER_ISR() TC_HANDLER(TEMP_TIMER_NUM)
+ #define HAL_TEMP_TIMER_ISR() TC_HANDLER(TEMP_TIMER_NUM)
#endif
// --------------------------------------------------------------------------
@@ -97,13 +106,13 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
// Should never be called with timer RTC_TIMER_NUM
Tc * const tc = TimerConfig[timer_num].pTc;
- tc->COUNT32.CC[0].reg = HAL_TIMER_TYPE_MAX - compare;
+ tc->COUNT32.CC[0].reg = compare;
}
FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
// Should never be called with timer RTC_TIMER_NUM
Tc * const tc = TimerConfig[timer_num].pTc;
- return (hal_timer_t)(HAL_TIMER_TYPE_MAX - tc->COUNT32.CC[0].reg);
+ return (hal_timer_t)tc->COUNT32.CC[0].reg;
}
FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
@@ -111,7 +120,7 @@ FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
Tc * const tc = TimerConfig[timer_num].pTc;
tc->COUNT32.CTRLBSET.reg = TC_CTRLBCLR_CMD_READSYNC;
SYNC(tc->COUNT32.SYNCBUSY.bit.CTRLB || tc->COUNT32.SYNCBUSY.bit.COUNT);
- return HAL_TIMER_TYPE_MAX - tc->COUNT32.COUNT.reg;
+ return tc->COUNT32.COUNT.reg;
}
void HAL_timer_enable_interrupt(const uint8_t timer_num);
diff --git a/Marlin/src/HAL/SAMD51/watchdog.cpp b/Marlin/src/HAL/SAMD51/watchdog.cpp
index 13539b4d7..ebc8dffe1 100644
--- a/Marlin/src/HAL/SAMD51/watchdog.cpp
+++ b/Marlin/src/HAL/SAMD51/watchdog.cpp
@@ -15,10 +15,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __SAMD51__
#include "../../inc/MarlinConfig.h"
diff --git a/Marlin/src/HAL/SAMD51/watchdog.h b/Marlin/src/HAL/SAMD51/watchdog.h
index aa8ef3537..2cd478822 100644
--- a/Marlin/src/HAL/SAMD51/watchdog.h
+++ b/Marlin/src/HAL/SAMD51/watchdog.h
@@ -15,7 +15,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp
index 77f8d2764..b1b727ce1 100644
--- a/Marlin/src/HAL/STM32/HAL.cpp
+++ b/Marlin/src/HAL/STM32/HAL.cpp
@@ -17,21 +17,17 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
#include "HAL.h"
+#include "usb_serial.h"
#include "../../inc/MarlinConfig.h"
#include "../shared/Delay.h"
-#if HAS_TMC_SW_SERIAL
- #include "SoftwareSerial.h"
-#endif
-
#if ENABLED(SRAM_EEPROM_EMULATION)
#if STM32F7xx
#include
@@ -67,7 +63,7 @@ uint16_t HAL_adc_result;
void HAL_init() {
FastIO_init();
- #if ENABLED(SDSUPPORT)
+ #if ENABLED(SDSUPPORT) && DISABLED(SDIO_SUPPORT)
OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up
#endif
@@ -76,20 +72,16 @@ void HAL_init() {
#endif
#if ENABLED(SRAM_EEPROM_EMULATION)
- // Enable access to backup SRAM
- __HAL_RCC_PWR_CLK_ENABLE();
- HAL_PWR_EnableBkUpAccess();
- __HAL_RCC_BKPSRAM_CLK_ENABLE();
-
- // Enable backup regulator
- LL_PWR_EnableBkUpRegulator();
- // Wait until backup regulator is initialized
- while (!LL_PWR_IsActiveFlag_BRR());
- #endif // EEPROM_EMULATED_SRAM
-
- #if HAS_TMC_SW_SERIAL
- SoftwareSerial::setInterruptPriority(SWSERIAL_TIMER_IRQ_PRIO, 0);
+ __HAL_RCC_PWR_CLK_ENABLE();
+ HAL_PWR_EnableBkUpAccess(); // Enable access to backup SRAM
+ __HAL_RCC_BKPSRAM_CLK_ENABLE();
+ LL_PWR_EnableBkUpRegulator(); // Enable backup regulator
+ while (!LL_PWR_IsActiveFlag_BRR()); // Wait until backup regulator is initialized
#endif
+
+ SetTimerInterruptPriorities();
+
+ TERN_(EMERGENCY_PARSER, USB_Hook_init());
}
void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); }
diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h
index c310cca74..730ada96c 100644
--- a/Marlin/src/HAL/STM32/HAL.h
+++ b/Marlin/src/HAL/STM32/HAL.h
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -30,6 +30,7 @@
#include "../shared/HAL_SPI.h"
#include "fastio.h"
#include "watchdog.h"
+#include "MarlinSerial.h"
#include "../../inc/MarlinConfigPre.h"
@@ -48,17 +49,17 @@
#elif SERIAL_PORT == -1
#define MYSERIAL0 SerialUSB
#elif SERIAL_PORT == 1
- #define MYSERIAL0 Serial1
+ #define MYSERIAL0 MSerial1
#elif SERIAL_PORT == 2
- #define MYSERIAL0 Serial2
+ #define MYSERIAL0 MSerial2
#elif SERIAL_PORT == 3
- #define MYSERIAL0 Serial3
+ #define MYSERIAL0 MSerial3
#elif SERIAL_PORT == 4
- #define MYSERIAL0 Serial4
+ #define MYSERIAL0 MSerial4
#elif SERIAL_PORT == 5
- #define MYSERIAL0 Serial5
+ #define MYSERIAL0 MSerial5
#elif SERIAL_PORT == 6
- #define MYSERIAL0 Serial6
+ #define MYSERIAL0 MSerial6
#else
#error "SERIAL_PORT must be from -1 to 6. Please update your configuration."
#endif
@@ -72,17 +73,17 @@
#elif SERIAL_PORT_2 == -1
#define MYSERIAL1 SerialUSB
#elif SERIAL_PORT_2 == 1
- #define MYSERIAL1 Serial1
+ #define MYSERIAL1 MSerial1
#elif SERIAL_PORT_2 == 2
- #define MYSERIAL1 Serial2
+ #define MYSERIAL1 MSerial2
#elif SERIAL_PORT_2 == 3
- #define MYSERIAL1 Serial3
+ #define MYSERIAL1 MSerial3
#elif SERIAL_PORT_2 == 4
- #define MYSERIAL1 Serial4
+ #define MYSERIAL1 MSerial4
#elif SERIAL_PORT_2 == 5
- #define MYSERIAL1 Serial5
+ #define MYSERIAL1 MSerial5
#elif SERIAL_PORT_2 == 6
- #define MYSERIAL1 Serial6
+ #define MYSERIAL1 MSerial6
#else
#error "SERIAL_PORT_2 must be from -1 to 6. Please update your configuration."
#endif
@@ -100,17 +101,17 @@
#elif DGUS_SERIAL_PORT == -1
#define DGUS_SERIAL SerialUSB
#elif DGUS_SERIAL_PORT == 1
- #define DGUS_SERIAL Serial1
+ #define DGUS_SERIAL MSerial1
#elif DGUS_SERIAL_PORT == 2
- #define DGUS_SERIAL Serial2
+ #define DGUS_SERIAL MSerial2
#elif DGUS_SERIAL_PORT == 3
- #define DGUS_SERIAL Serial3
+ #define DGUS_SERIAL MSerial3
#elif DGUS_SERIAL_PORT == 4
- #define DGUS_SERIAL Serial4
+ #define DGUS_SERIAL MSerial4
#elif DGUS_SERIAL_PORT == 5
- #define DGUS_SERIAL Serial5
+ #define DGUS_SERIAL MSerial5
#elif DGUS_SERIAL_PORT == 6
- #define DGUS_SERIAL Serial6
+ #define DGUS_SERIAL MSerial6
#else
#error "DGUS_SERIAL_PORT must be from -1 to 6. Please update your configuration."
#endif
@@ -118,7 +119,6 @@
#define DGUS_SERIAL_GET_TX_BUFFER_FREE DGUS_SERIAL.availableForWrite
#endif
-#include "timers.h"
/**
* TODO: review this to return 1 for pins that are not analog input
@@ -191,16 +191,6 @@ static inline int freeMemory() {
#pragma GCC diagnostic pop
-//
-// EEPROM
-//
-
-// Wire library should work for i2c EEPROMs
-void eeprom_write_byte(uint8_t *pos, unsigned char value);
-uint8_t eeprom_read_byte(uint8_t *pos);
-void eeprom_read_block(void *__dst, const void *__src, size_t __n);
-void eeprom_update_block(const void *__src, void *__dst, size_t __n);
-
//
// ADC
//
@@ -209,8 +199,9 @@ void eeprom_update_block(const void *__src, void *__dst, size_t __n);
inline void HAL_adc_init() {}
-#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
+#define HAL_ADC_VREF 3.3
#define HAL_ADC_RESOLUTION 10
+#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true
diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp
index 7b37fff9c..202442a71 100644
--- a/Marlin/src/HAL/STM32/HAL_SPI.cpp
+++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
diff --git a/Marlin/src/HAL/STM32/MarlinSerial.cpp b/Marlin/src/HAL/STM32/MarlinSerial.cpp
new file mode 100644
index 000000000..8d99ab785
--- /dev/null
+++ b/Marlin/src/HAL/STM32/MarlinSerial.cpp
@@ -0,0 +1,88 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../inc/MarlinConfig.h"
+#include "MarlinSerial.h"
+
+#if ENABLED(EMERGENCY_PARSER)
+ #include "../../feature/e_parser.h"
+#endif
+
+#ifndef USART4
+ #define USART4 UART4
+#endif
+
+#ifndef USART5
+ #define USART5 UART5
+#endif
+
+#define DECLARE_SERIAL_PORT(ser_num) \
+ void _rx_complete_irq_ ## ser_num (serial_t * obj); \
+ MarlinSerial MSerial ## ser_num (USART ## ser_num, &_rx_complete_irq_ ## ser_num); \
+ void _rx_complete_irq_ ## ser_num (serial_t * obj) { MSerial ## ser_num ._rx_complete_irq(obj); }
+
+#define DECLARE_SERIAL_PORT_EXP(ser_num) DECLARE_SERIAL_PORT(ser_num)
+
+#if defined(SERIAL_PORT) && SERIAL_PORT >= 0
+ DECLARE_SERIAL_PORT_EXP(SERIAL_PORT)
+#endif
+
+#if defined(SERIAL_PORT_2) && SERIAL_PORT_2 >= 0
+ DECLARE_SERIAL_PORT_EXP(SERIAL_PORT_2)
+#endif
+
+#if defined(DGUS_SERIAL_PORT) && DGUS_SERIAL_PORT >= 0
+ DECLARE_SERIAL_PORT_EXP(DGUS_SERIAL_PORT)
+#endif
+
+void MarlinSerial::begin(unsigned long baud, uint8_t config) {
+ HardwareSerial::begin(baud, config);
+ // replace the IRQ callback with the one we have defined
+ #if ENABLED(EMERGENCY_PARSER)
+ _serial.rx_callback = _rx_callback;
+ #endif
+}
+
+// This function is Copyright (c) 2006 Nicholas Zambetti.
+void MarlinSerial::_rx_complete_irq(serial_t *obj) {
+ // No Parity error, read byte and store it in the buffer if there is room
+ unsigned char c;
+
+ if (uart_getc(obj, &c) == 0) {
+
+ rx_buffer_index_t i = (unsigned int)(obj->rx_head + 1) % SERIAL_RX_BUFFER_SIZE;
+
+ // if we should be storing the received character into the location
+ // just before the tail (meaning that the head would advance to the
+ // current location of the tail), we're about to overflow the buffer
+ // and so we don't write the character or advance the head.
+ if (i != obj->rx_tail) {
+ obj->rx_buff[obj->rx_head] = c;
+ obj->rx_head = i;
+ }
+
+ #if ENABLED(EMERGENCY_PARSER)
+ emergency_parser.update(emergency_state, c);
+ #endif
+ }
+}
+
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/MarlinSerial.h b/Marlin/src/HAL/STM32/MarlinSerial.h
new file mode 100644
index 000000000..5ab97ff3a
--- /dev/null
+++ b/Marlin/src/HAL/STM32/MarlinSerial.h
@@ -0,0 +1,60 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#pragma once
+
+#include "../../inc/MarlinConfigPre.h"
+
+#if ENABLED(EMERGENCY_PARSER)
+ #include "../../feature/e_parser.h"
+#endif
+
+typedef void (*usart_rx_callback_t)(serial_t * obj);
+
+class MarlinSerial : public HardwareSerial {
+public:
+ MarlinSerial(void* peripheral, usart_rx_callback_t rx_callback) :
+ HardwareSerial(peripheral), _rx_callback(rx_callback)
+ #if ENABLED(EMERGENCY_PARSER)
+ , emergency_state(EmergencyParser::State::EP_RESET)
+ #endif
+ { }
+
+ void begin(unsigned long baud, uint8_t config);
+ inline void begin(unsigned long baud) { begin(baud, SERIAL_8N1); }
+
+ void _rx_complete_irq(serial_t* obj);
+
+protected:
+ usart_rx_callback_t _rx_callback;
+ #if ENABLED(EMERGENCY_PARSER)
+ EmergencyParser::State emergency_state;
+ #endif
+};
+
+extern MarlinSerial MSerial1;
+extern MarlinSerial MSerial2;
+extern MarlinSerial MSerial3;
+extern MarlinSerial MSerial4;
+extern MarlinSerial MSerial5;
+extern MarlinSerial MSerial6;
+extern MarlinSerial MSerial7;
+extern MarlinSerial MSerial8;
+extern MarlinSerial MSerial9;
+extern MarlinSerial MSerial10;
+extern MarlinSerial MSerialLP1;
diff --git a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp
index ebe15f939..9d32b342e 100644
--- a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp
+++ b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -27,248 +27,260 @@
#include
#include
-//#include "SdMscDriver.h"
-
-//#include "usbd_msc_bot.h"
-//#include "usbd_msc_scsi.h"
-//#include "usbd_msc_composite.h"
-//#include "usbd_msc_cdc_composite.h"
-
-//#include "usbd_msc_data.h"
-
-#if defined(STM32F103xE) || defined(STM32F103xG)
- #include
- #include
-#elif defined(STM32F4xx)
- #include
- #include
- #include
- #include
-#elif defined(STM32F7xx)
- #include
- #include
- #include
- #include
-#else
+#if NONE(STM32F103xE, STM32F103xG, STM32F4xx, STM32F7xx)
#error "ERROR - Only STM32F103xE, STM32F103xG, STM32F4xx or STM32F7xx CPUs supported"
#endif
-SD_HandleTypeDef hsd; // create SDIO structure
+#ifdef USBD_USE_CDC_COMPOSITE
-#define TRANSFER_CLOCK_DIV ((uint8_t)SDIO_INIT_CLK_DIV/40)
+ // use USB drivers
-#ifndef USBD_OK
- #define USBD_OK 0
-#endif
+ extern "C" { int8_t SD_MSC_Read(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len);
+ int8_t SD_MSC_Write(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len);
+ extern SD_HandleTypeDef hsd;
+ }
-void go_to_transfer_speed() {
+ bool SDIO_Init() {
+ return hsd.State == HAL_SD_STATE_READY; // return pass/fail status
+ }
- SD_InitTypeDef Init;
+ bool SDIO_ReadBlock(uint32_t block, uint8_t *src) {
+ int8_t status = SD_MSC_Read(0, (uint8_t*)src, block, 1); // read one 512 byte block
+ return (bool) status;
+ }
- /* Default SDIO peripheral configuration for SD card initialization */
- Init.ClockEdge = hsd.Init.ClockEdge;
- Init.ClockBypass = hsd.Init.ClockBypass;
- Init.ClockPowerSave = hsd.Init.ClockPowerSave;
- Init.BusWide = hsd.Init.BusWide;
- Init.HardwareFlowControl = hsd.Init.HardwareFlowControl;
- Init.ClockDiv = TRANSFER_CLOCK_DIV;
+ bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) {
+ int8_t status = SD_MSC_Write(0, (uint8_t*)src, block, 1); // write one 512 byte block
+ return (bool) status;
+ }
- /* Initialize SDIO peripheral interface with default configuration */
- SDIO_Init(hsd.Instance, Init);
-}
+#else // !USBD_USE_CDC_COMPOSITE
-void SD_LowLevel_Init(void) {
+ // use local drivers
+ #if defined(STM32F103xE) || defined(STM32F103xG)
+ #include
+ #include
+ #elif defined(STM32F4xx)
+ #include
+ #include
+ #include
+ #include
+ #elif defined(STM32F7xx)
+ #include
+ #include
+ #include
+ #include
+ #else
+ #error "ERROR - Only STM32F103xE, STM32F103xG, STM32F4xx or STM32F7xx CPUs supported"
+ #endif
- uint32_t tempreg;
+ SD_HandleTypeDef hsd; // create SDIO structure
- GPIO_InitTypeDef GPIO_InitStruct;
+ #define TRANSFER_CLOCK_DIV (uint8_t(SDIO_INIT_CLK_DIV) / 40)
- __HAL_RCC_GPIOC_CLK_ENABLE(); //enable GPIO clocks
- __HAL_RCC_GPIOD_CLK_ENABLE(); //enable GPIO clocks
+ #ifndef USBD_OK
+ #define USBD_OK 0
+ #endif
- GPIO_InitStruct.Pin = GPIO_PIN_8 | GPIO_PIN_12; // D0 & SCK
- GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
- GPIO_InitStruct.Pull = 1; //GPIO_NOPULL;
- GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
- GPIO_InitStruct.Alternate = GPIO_AF12_SDIO;
- HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
+ void go_to_transfer_speed() {
+ SD_InitTypeDef Init;
- #if defined(SDIO_D1_PIN) && defined(SDIO_D2_PIN) && defined(SDIO_D3_PIN) // define D1-D3 only if have a four bit wide SDIO bus
- GPIO_InitStruct.Pin = GPIO_PIN_9 | GPIO_PIN_10 | GPIO_PIN_11; // D1-D3
+ /* Default SDIO peripheral configuration for SD card initialization */
+ Init.ClockEdge = hsd.Init.ClockEdge;
+ Init.ClockBypass = hsd.Init.ClockBypass;
+ Init.ClockPowerSave = hsd.Init.ClockPowerSave;
+ Init.BusWide = hsd.Init.BusWide;
+ Init.HardwareFlowControl = hsd.Init.HardwareFlowControl;
+ Init.ClockDiv = TRANSFER_CLOCK_DIV;
+
+ /* Initialize SDIO peripheral interface with default configuration */
+ SDIO_Init(hsd.Instance, Init);
+ }
+
+ void SD_LowLevel_Init(void) {
+ uint32_t tempreg;
+
+ GPIO_InitTypeDef GPIO_InitStruct;
+
+ __HAL_RCC_GPIOC_CLK_ENABLE(); //enable GPIO clocks
+ __HAL_RCC_GPIOD_CLK_ENABLE(); //enable GPIO clocks
+
+ GPIO_InitStruct.Pin = GPIO_PIN_8 | GPIO_PIN_12; // D0 & SCK
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = 1; //GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF12_SDIO;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
- #endif
- // Configure PD.02 CMD line
- GPIO_InitStruct.Pin = GPIO_PIN_2;
- HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
+ #if PINS_EXIST(SDIO_D1, SDIO_D2, SDIO_D3) // define D1-D3 only if have a four bit wide SDIO bus
+ GPIO_InitStruct.Pin = GPIO_PIN_9 | GPIO_PIN_10 | GPIO_PIN_11; // D1-D3
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = 1; // GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF12_SDIO;
+ HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
+ #endif
- RCC->APB2RSTR &= ~RCC_APB2RSTR_SDIORST_Msk; // take SDIO out of reset
- RCC->APB2ENR |= RCC_APB2RSTR_SDIORST_Msk; // enable SDIO clock
+ // Configure PD.02 CMD line
+ GPIO_InitStruct.Pin = GPIO_PIN_2;
+ HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
- // Enable the DMA2 Clock
+ RCC->APB2RSTR &= ~RCC_APB2RSTR_SDIORST_Msk; // take SDIO out of reset
+ RCC->APB2ENR |= RCC_APB2RSTR_SDIORST_Msk; // enable SDIO clock
- //Initialize the SDIO (with initial <400Khz Clock)
- tempreg = 0; //Reset value
- tempreg |= SDIO_CLKCR_CLKEN; //Clock is enabled
- tempreg |= (uint32_t)0x76; //Clock Divider. Clock = 48000/(118+2) = 400Khz
- //Keep the rest at 0 => HW_Flow Disabled, Rising Clock Edge, Disable CLK ByPass, Bus Width = 0, Power save Disable
- SDIO->CLKCR = tempreg;
+ // Enable the DMA2 Clock
- //Power up the SDIO
- SDIO->POWER = 0x03;
-}
+ //Initialize the SDIO (with initial <400Khz Clock)
+ tempreg = 0; //Reset value
+ tempreg |= SDIO_CLKCR_CLKEN; // Clock enabled
+ tempreg |= (uint32_t)0x76; // Clock Divider. Clock = 48000 / (118 + 2) = 400Khz
+ // Keep the rest at 0 => HW_Flow Disabled, Rising Clock Edge, Disable CLK ByPass, Bus Width = 0, Power save Disable
+ SDIO->CLKCR = tempreg;
-
-void HAL_SD_MspInit(SD_HandleTypeDef *hsd) { // application specific init
- UNUSED(hsd); /* Prevent unused argument(s) compilation warning */
- __HAL_RCC_SDIO_CLK_ENABLE(); // turn on SDIO clock
-}
-
-constexpr uint8_t SD_RETRY_COUNT = (1
- #if ENABLED(SD_CHECK_AND_RETRY)
- + 2
- #endif
-);
-
-bool SDIO_Init() {
- //init SDIO and get SD card info
-
- uint8_t retryCnt = SD_RETRY_COUNT;
-
- bool status;
- hsd.Instance = SDIO;
- hsd.State = (HAL_SD_StateTypeDef) 0; // HAL_SD_STATE_RESET
- SD_LowLevel_Init();
-
- uint8_t retry_Cnt = retryCnt;
- for (;;) {
- status = (bool) HAL_SD_Init(&hsd);
- if (!status) break;
- if (!--retry_Cnt) return false; // return failing status if retries are exhausted
+ // Power up the SDIO
+ SDIO->POWER = 0x03;
}
- go_to_transfer_speed();
+ void HAL_SD_MspInit(SD_HandleTypeDef *hsd) { // application specific init
+ UNUSED(hsd); /* Prevent unused argument(s) compilation warning */
+ __HAL_RCC_SDIO_CLK_ENABLE(); // turn on SDIO clock
+ }
- #if defined(SDIO_D1_PIN) && defined(SDIO_D2_PIN) && defined(SDIO_D3_PIN) // go to 4 bit wide mode if pins are defined
- retry_Cnt = retryCnt;
+ constexpr uint8_t SD_RETRY_COUNT = TERN(SD_CHECK_AND_RETRY, 3, 1);
+
+ bool SDIO_Init() {
+ //init SDIO and get SD card info
+
+ uint8_t retryCnt = SD_RETRY_COUNT;
+
+ bool status;
+ hsd.Instance = SDIO;
+ hsd.State = (HAL_SD_StateTypeDef) 0; // HAL_SD_STATE_RESET
+ SD_LowLevel_Init();
+
+ uint8_t retry_Cnt = retryCnt;
for (;;) {
- if (!HAL_SD_ConfigWideBusOperation(&hsd, SDIO_BUS_WIDE_4B)) break; // some cards are only 1 bit wide so a pass here is not required
- if (!--retry_Cnt) break;
+ status = (bool) HAL_SD_Init(&hsd);
+ if (!status) break;
+ if (!--retry_Cnt) return false; // return failing status if retries are exhausted
}
- if (!retry_Cnt) { // wide bus failed, go back to one bit wide mode
- hsd.State = (HAL_SD_StateTypeDef) 0; // HAL_SD_STATE_RESET
- SD_LowLevel_Init();
+
+ go_to_transfer_speed();
+
+ #if PINS_EXIST(SDIO_D1, SDIO_D2, SDIO_D3) // go to 4 bit wide mode if pins are defined
retry_Cnt = retryCnt;
for (;;) {
- status = (bool) HAL_SD_Init(&hsd);
- if (!status) break;
- if (!--retry_Cnt) return false; // return failing status if retries are exhausted
+ if (!HAL_SD_ConfigWideBusOperation(&hsd, SDIO_BUS_WIDE_4B)) break; // some cards are only 1 bit wide so a pass here is not required
+ if (!--retry_Cnt) break;
}
+ if (!retry_Cnt) { // wide bus failed, go back to one bit wide mode
+ hsd.State = (HAL_SD_StateTypeDef) 0; // HAL_SD_STATE_RESET
+ SD_LowLevel_Init();
+ retry_Cnt = retryCnt;
+ for (;;) {
+ status = (bool) HAL_SD_Init(&hsd);
+ if (!status) break;
+ if (!--retry_Cnt) return false; // return failing status if retries are exhausted
+ }
+ }
+ #endif
+
+ return true;
+ }
+
+ void init_SDIO_pins(void) {
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+
+ /**SDIO GPIO Configuration
+ PC8 ------> SDIO_D0
+ PC12 ------> SDIO_CK
+ PD2 ------> SDIO_CMD
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_8;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF12_SDIO;
+ HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
+
+ GPIO_InitStruct.Pin = GPIO_PIN_12;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF12_SDIO;
+ HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
+
+ GPIO_InitStruct.Pin = GPIO_PIN_2;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF12_SDIO;
+ HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
+ }
+
+ //bool SDIO_init() { return (bool) (SD_SDIO_Init() ? 1 : 0);}
+ //bool SDIO_Init_C() { return (bool) (SD_SDIO_Init() ? 1 : 0);}
+
+ bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) {
+ hsd.Instance = SDIO;
+ uint8_t retryCnt = SD_RETRY_COUNT;
+
+ bool status;
+ for (;;) {
+ status = (bool) HAL_SD_ReadBlocks(&hsd, (uint8_t*)dst, block, 1, 1000); // read one 512 byte block with 500mS timeout
+ status |= (bool) HAL_SD_GetCardState(&hsd); // make sure all is OK
+ if (!status) break; // return passing status
+ if (!--retryCnt) break; // return failing status if retries are exhausted
}
- #endif
+ return status;
- return true;
-}
+ /*
+ return (bool) ((status_read | status_card) ? 1 : 0);
-void init_SDIO_pins(void) {
- GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if (SDIO_GetCardState() != SDIO_CARD_TRANSFER) return false;
+ if (blockAddress >= SdCard.LogBlockNbr) return false;
+ if ((0x03 & (uint32_t)data)) return false; // misaligned data
- /**SDIO GPIO Configuration
- PC8 ------> SDIO_D0
- PC12 ------> SDIO_CK
- PD2 ------> SDIO_CMD
- */
- GPIO_InitStruct.Pin = GPIO_PIN_8;
- GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
- GPIO_InitStruct.Pull = GPIO_NOPULL;
- GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
- GPIO_InitStruct.Alternate = GPIO_AF12_SDIO;
- HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
+ if (SdCard.CardType != CARD_SDHC_SDXC) { blockAddress *= 512U; }
- GPIO_InitStruct.Pin = GPIO_PIN_12;
- GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
- GPIO_InitStruct.Pull = GPIO_NOPULL;
- GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
- GPIO_InitStruct.Alternate = GPIO_AF12_SDIO;
- HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
+ if (!SDIO_CmdReadSingleBlock(blockAddress)) {
+ SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS);
+ dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
+ return false;
+ }
- GPIO_InitStruct.Pin = GPIO_PIN_2;
- GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
- GPIO_InitStruct.Pull = GPIO_NOPULL;
- GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
- GPIO_InitStruct.Alternate = GPIO_AF12_SDIO;
- HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
-}
+ while (!SDIO_GET_FLAG(SDIO_STA_DATAEND | SDIO_STA_TRX_ERROR_FLAGS)) {}
-//bool SDIO_init() { return (bool) (SD_SDIO_Init() ? 1 : 0);}
-//bool SDIO_Init_C() { return (bool) (SD_SDIO_Init() ? 1 : 0);}
-
-bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) {
- bool status;
-
- hsd.Instance = SDIO;
-
- uint8_t retryCnt = SD_RETRY_COUNT;
-
- for (;;) {
- bool status = (bool) HAL_SD_ReadBlocks(&hsd, (uint8_t*)dst, block, 1, 1000); // read one 512 byte block with 500mS timeout
- status |= (bool) HAL_SD_GetCardState(&hsd); // make sure all is OK
- if (!status) return false; // return passing status
- if (!--retryCnt) return true; // return failing status if retries are exhausted
- }
-
- /*
- return (bool) ((status_read | status_card) ? 1 : 0);
-
- if (SDIO_GetCardState() != SDIO_CARD_TRANSFER) return false;
- if (blockAddress >= SdCard.LogBlockNbr) return false;
- if ((0x03 & (uint32_t)data)) return false; // misaligned data
-
- if (SdCard.CardType != CARD_SDHC_SDXC) { blockAddress *= 512U; }
-
- if (!SDIO_CmdReadSingleBlock(blockAddress)) {
- SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS);
dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
- return false;
- }
- while (!SDIO_GET_FLAG(SDIO_STA_DATAEND | SDIO_STA_TRX_ERROR_FLAGS)) {}
+ if (SDIO->STA & SDIO_STA_RXDAVL) {
+ while (SDIO->STA & SDIO_STA_RXDAVL) (void)SDIO->FIFO;
+ SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS);
+ return false;
+ }
- dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
-
- if (SDIO->STA & SDIO_STA_RXDAVL) {
- while (SDIO->STA & SDIO_STA_RXDAVL) (void)SDIO->FIFO;
+ if (SDIO_GET_FLAG(SDIO_STA_TRX_ERROR_FLAGS)) {
+ SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS);
+ return false;
+ }
SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS);
- return false;
+ */
+
+ return true;
}
- if (SDIO_GET_FLAG(SDIO_STA_TRX_ERROR_FLAGS)) {
- SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS);
- return false;
+ bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) {
+ hsd.Instance = SDIO;
+ uint8_t retryCnt = SD_RETRY_COUNT;
+ bool status;
+ for (;;) {
+ status = (bool) HAL_SD_WriteBlocks(&hsd, (uint8_t*)src, block, 1, 500); // write one 512 byte block with 500mS timeout
+ status |= (bool) HAL_SD_GetCardState(&hsd); // make sure all is OK
+ if (!status) break; // return passing status
+ if (!--retryCnt) break; // return failing status if retries are exhausted
+ }
+ return status;
}
- SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS);
- */
-
- return true;
-}
-
-bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) {
- bool status;
-
- hsd.Instance = SDIO;
-
- uint8_t retryCnt = SD_RETRY_COUNT;
-
- for (;;) {
- status = (bool) HAL_SD_WriteBlocks(&hsd, (uint8_t*)src, block, 1, 500); // write one 512 byte block with 500mS timeout
- status |= (bool) HAL_SD_GetCardState(&hsd); // make sure all is OK
- if (!status) return (bool) status; // return passing status
- if (!--retryCnt) return (bool) status; // return failing status if retries are exhausted
- }
-}
+#endif // !USBD_USE_CDC_COMPOSITE
#endif // SDIO_SUPPORT
diff --git a/Marlin/src/HAL/STM32/Servo.cpp b/Marlin/src/HAL/STM32/Servo.cpp
index 2dcadb887..1cf117a05 100644
--- a/Marlin/src/HAL/STM32/Servo.cpp
+++ b/Marlin/src/HAL/STM32/Servo.cpp
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
@@ -29,34 +29,82 @@
#include "Servo.h"
static uint_fast8_t servoCount = 0;
+static libServo *servos[NUM_SERVOS] = {0};
constexpr millis_t servoDelay[] = SERVO_DELAY;
static_assert(COUNT(servoDelay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
+// Initialize to the default timer priority. This will be overridden by a call from timers.cpp.
+// This allows all timer interrupt priorities to be managed from a single location in the HAL.
+static uint32_t servo_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), TIM_IRQ_PRIO, TIM_IRQ_SUBPRIO);
+
+// This must be called after the STM32 Servo class has intialized the timer.
+// It may only be needed after the first call to attach(), but it is possible
+// that is is necessary after every detach() call. To be safe this is currently
+// called after every call to attach().
+static void fixServoTimerInterruptPriority() {
+ NVIC_SetPriority(getTimerUpIrq(TIMER_SERVO), servo_interrupt_priority);
+}
+
libServo::libServo()
-: delay(servoDelay[servoCount++])
-{}
+: delay(servoDelay[servoCount]),
+ was_attached_before_pause(false),
+ value_before_pause(0)
+{
+ servos[servoCount++] = this;
+}
int8_t libServo::attach(const int pin) {
if (servoCount >= MAX_SERVOS) return -1;
if (pin > 0) servo_pin = pin;
- return super::attach(servo_pin);
+ auto result = stm32_servo.attach(servo_pin);
+ fixServoTimerInterruptPriority();
+ return result;
}
int8_t libServo::attach(const int pin, const int min, const int max) {
if (servoCount >= MAX_SERVOS) return -1;
if (pin > 0) servo_pin = pin;
- return super::attach(servo_pin, min, max);
+ auto result = stm32_servo.attach(servo_pin, min, max);
+ fixServoTimerInterruptPriority();
+ return result;
}
void libServo::move(const int value) {
if (attach(0) >= 0) {
- write(value);
+ stm32_servo.write(value);
safe_delay(delay);
- #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
- detach();
- #endif
+ TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
}
}
-#endif // HAS_SERVOS
+void libServo::pause() {
+ was_attached_before_pause = stm32_servo.attached();
+ if (was_attached_before_pause) {
+ value_before_pause = stm32_servo.read();
+ stm32_servo.detach();
+ }
+}
+
+void libServo::resume() {
+ if (was_attached_before_pause) {
+ attach();
+ move(value_before_pause);
+ }
+}
+
+void libServo::pause_all_servos() {
+ for (auto& servo : servos)
+ if (servo) servo->pause();
+}
+
+void libServo::resume_all_servos() {
+ for (auto& servo : servos)
+ if (servo) servo->resume();
+}
+
+void libServo::setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority) {
+ servo_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), preemptPriority, subPriority);
+}
+
+#endif // HAS_SERVOS
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/Servo.h b/Marlin/src/HAL/STM32/Servo.h
index e8b3c4b10..1527e753b 100644
--- a/Marlin/src/HAL/STM32/Servo.h
+++ b/Marlin/src/HAL/STM32/Servo.h
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -27,15 +27,28 @@
#include "../../core/millis_t.h"
// Inherit and expand on the official library
-class libServo : public Servo {
+class libServo {
public:
libServo();
- int8_t attach(const int pin);
+ int8_t attach(const int pin = 0); // pin == 0 uses value from previous call
int8_t attach(const int pin, const int min, const int max);
+ void detach() { stm32_servo.detach(); }
+ int read() { return stm32_servo.read(); }
void move(const int value);
+
+ void pause();
+ void resume();
+
+ static void pause_all_servos();
+ static void resume_all_servos();
+ static void setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority);
+
private:
- typedef Servo super;
+ Servo stm32_servo;
int servo_pin = 0;
millis_t delay = 0;
+
+ bool was_attached_before_pause;
+ int value_before_pause;
};
diff --git a/Marlin/src/HAL/STM32/SoftwareSerial.cpp b/Marlin/src/HAL/STM32/SoftwareSerial.cpp
index f6363aa1c..af92548cb 100644
--- a/Marlin/src/HAL/STM32/SoftwareSerial.cpp
+++ b/Marlin/src/HAL/STM32/SoftwareSerial.cpp
@@ -3,14 +3,14 @@
*
* Multi-instance software serial library for Arduino/Wiring
* -- Interrupt-driven receive and other improvements by ladyada
- * (http://ladyada.net)
+ * (https://ladyada.net)
* -- Tuning, circular buffer, derivation from class Print/Stream,
* multi-instance support, porting to 8MHz processors,
* various optimizations, PROGMEM delay tables, inverse logic and
* direct port writing by Mikal Hart (http://www.arduiniana.org)
- * -- Pin change interrupt macros by Paul Stoffregen (http://www.pjrc.com)
+ * -- Pin change interrupt macros by Paul Stoffregen (https://www.pjrc.com)
* -- 20MHz processor support by Garrett Mace (http://www.macetech.com)
- * -- ATmega1280/2560 support by Brett Hagman (http://www.roguerobotics.com/)
+ * -- ATmega1280/2560 support by Brett Hagman (https://www.roguerobotics.com/)
* -- STM32 support by Armin van der Togt
*
* This library is free software; you can redistribute it and/or
@@ -36,8 +36,9 @@
//
#if defined(PLATFORMIO) && defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+#include "../../inc/MarlinConfig.h"
+
#include "SoftwareSerial.h"
-#include "timers.h"
#define OVERSAMPLE 3 // in RX, Timer will generate interruption OVERSAMPLE time during a bit. Thus OVERSAMPLE ticks in a bit. (interrupt not synchonized with edge).
@@ -47,49 +48,49 @@
// The order is based on (lack of) features and compare channels, we choose the simplest available
// because we only need an update interrupt
#if !defined(TIMER_SERIAL)
-#if defined (TIM18_BASE)
+#if defined(TIM18_BASE)
#define TIMER_SERIAL TIM18
-#elif defined (TIM7_BASE)
+#elif defined(TIM7_BASE)
#define TIMER_SERIAL TIM7
-#elif defined (TIM6_BASE)
+#elif defined(TIM6_BASE)
#define TIMER_SERIAL TIM6
-#elif defined (TIM22_BASE)
+#elif defined(TIM22_BASE)
#define TIMER_SERIAL TIM22
-#elif defined (TIM21_BASE)
+#elif defined(TIM21_BASE)
#define TIMER_SERIAL TIM21
-#elif defined (TIM17_BASE)
+#elif defined(TIM17_BASE)
#define TIMER_SERIAL TIM17
-#elif defined (TIM16_BASE)
+#elif defined(TIM16_BASE)
#define TIMER_SERIAL TIM16
-#elif defined (TIM15_BASE)
+#elif defined(TIM15_BASE)
#define TIMER_SERIAL TIM15
-#elif defined (TIM14_BASE)
+#elif defined(TIM14_BASE)
#define TIMER_SERIAL TIM14
-#elif defined (TIM13_BASE)
+#elif defined(TIM13_BASE)
#define TIMER_SERIAL TIM13
-#elif defined (TIM11_BASE)
+#elif defined(TIM11_BASE)
#define TIMER_SERIAL TIM11
-#elif defined (TIM10_BASE)
+#elif defined(TIM10_BASE)
#define TIMER_SERIAL TIM10
-#elif defined (TIM12_BASE)
+#elif defined(TIM12_BASE)
#define TIMER_SERIAL TIM12
-#elif defined (TIM19_BASE)
+#elif defined(TIM19_BASE)
#define TIMER_SERIAL TIM19
-#elif defined (TIM9_BASE)
+#elif defined(TIM9_BASE)
#define TIMER_SERIAL TIM9
-#elif defined (TIM5_BASE)
+#elif defined(TIM5_BASE)
#define TIMER_SERIAL TIM5
-#elif defined (TIM4_BASE)
+#elif defined(TIM4_BASE)
#define TIMER_SERIAL TIM4
-#elif defined (TIM3_BASE)
+#elif defined(TIM3_BASE)
#define TIMER_SERIAL TIM3
-#elif defined (TIM2_BASE)
+#elif defined(TIM2_BASE)
#define TIMER_SERIAL TIM2
-#elif defined (TIM20_BASE)
+#elif defined(TIM20_BASE)
#define TIMER_SERIAL TIM20
-#elif defined (TIM8_BASE)
+#elif defined(TIM8_BASE)
#define TIMER_SERIAL TIM8
-#elif defined (TIM1_BASE)
+#elif defined(TIM1_BASE)
#define TIMER_SERIAL TIM1
#else
#error No suitable timer found for SoftwareSerial, define TIMER_SERIAL in variant.h
diff --git a/Marlin/src/HAL/STM32/SoftwareSerial.h b/Marlin/src/HAL/STM32/SoftwareSerial.h
index 504bd6979..1a4f742c3 100644
--- a/Marlin/src/HAL/STM32/SoftwareSerial.h
+++ b/Marlin/src/HAL/STM32/SoftwareSerial.h
@@ -3,14 +3,14 @@
*
* Multi-instance software serial library for Arduino/Wiring
* -- Interrupt-driven receive and other improvements by ladyada
- * (http://ladyada.net)
+ * (https://ladyada.net)
* -- Tuning, circular buffer, derivation from class Print/Stream,
* multi-instance support, porting to 8MHz processors,
* various optimizations, PROGMEM delay tables, inverse logic and
* direct port writing by Mikal Hart (http://www.arduiniana.org)
- * -- Pin change interrupt macros by Paul Stoffregen (http://www.pjrc.com)
+ * -- Pin change interrupt macros by Paul Stoffregen (https://www.pjrc.com)
* -- 20MHz processor support by Garrett Mace (http://www.macetech.com)
- * -- ATmega1280/2560 support by Brett Hagman (http://www.roguerobotics.com/)
+ * -- ATmega1280/2560 support by Brett Hagman (https://www.roguerobotics.com/)
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp
index 39012f820..0933b9f4e 100644
--- a/Marlin/src/HAL/STM32/eeprom_flash.cpp
+++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp
@@ -17,22 +17,24 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
#include "../../inc/MarlinConfig.h"
-#if BOTH(EEPROM_SETTINGS, FLASH_EEPROM_EMULATION)
+#if ENABLED(FLASH_EEPROM_EMULATION)
#include "../shared/eeprom_api.h"
-
-// Only STM32F4 can support wear leveling at this time
-#ifndef STM32F4xx
- #undef FLASH_EEPROM_LEVELING
+#if HAS_SERVOS
+ #include "Servo.h"
+ #define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos()
+ #define RESUME_SERVO_OUTPUT() libServo::resume_all_servos()
+#else
+ #define PAUSE_SERVO_OUTPUT()
+ #define RESUME_SERVO_OUTPUT()
#endif
/**
@@ -57,8 +59,8 @@
#define DEBUG_OUT ENABLED(EEPROM_CHITCHAT)
#include "src/core/debug_out.h"
- #ifndef EEPROM_SIZE
- #define EEPROM_SIZE 0x1000 // 4kB
+ #ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE 0x1000 // 4KB
#endif
#ifndef FLASH_SECTOR
@@ -68,11 +70,11 @@
#define FLASH_UNIT_SIZE 0x20000 // 128kB
#endif
- #define FLASH_ADDRESS_START (FLASH_END - ((FLASH_SECTOR_TOTAL - FLASH_SECTOR) * FLASH_UNIT_SIZE) + 1)
+ #define FLASH_ADDRESS_START (FLASH_END - ((FLASH_SECTOR_TOTAL - (FLASH_SECTOR)) * (FLASH_UNIT_SIZE)) + 1)
#define FLASH_ADDRESS_END (FLASH_ADDRESS_START + FLASH_UNIT_SIZE - 1)
- #define EEPROM_SLOTS (FLASH_UNIT_SIZE/EEPROM_SIZE)
- #define SLOT_ADDRESS(slot) (FLASH_ADDRESS_START + (slot * EEPROM_SIZE))
+ #define EEPROM_SLOTS ((FLASH_UNIT_SIZE) / (MARLIN_EEPROM_SIZE))
+ #define SLOT_ADDRESS(slot) (FLASH_ADDRESS_START + (slot * (MARLIN_EEPROM_SIZE)))
#define UNLOCK_FLASH() if (!flash_unlocked) { \
HAL_FLASH_Unlock(); \
@@ -85,12 +87,12 @@
#define EMPTY_UINT32 ((uint32_t)-1)
#define EMPTY_UINT8 ((uint8_t)-1)
- static uint8_t ram_eeprom[EEPROM_SIZE] __attribute__((aligned(4))) = {0};
+ static uint8_t ram_eeprom[MARLIN_EEPROM_SIZE] __attribute__((aligned(4))) = {0};
static int current_slot = -1;
- static_assert(0 == EEPROM_SIZE % 4, "EEPROM_SIZE must be a multiple of 4"); // Ensure copying as uint32_t is safe
- static_assert(0 == FLASH_UNIT_SIZE % EEPROM_SIZE, "EEPROM_SIZE must divide evenly into your FLASH_UNIT_SIZE");
- static_assert(FLASH_UNIT_SIZE >= EEPROM_SIZE, "FLASH_UNIT_SIZE must be greater than or equal to your EEPROM_SIZE");
+ static_assert(0 == MARLIN_EEPROM_SIZE % 4, "MARLIN_EEPROM_SIZE must be a multiple of 4"); // Ensure copying as uint32_t is safe
+ static_assert(0 == FLASH_UNIT_SIZE % MARLIN_EEPROM_SIZE, "MARLIN_EEPROM_SIZE must divide evenly into your FLASH_UNIT_SIZE");
+ static_assert(FLASH_UNIT_SIZE >= MARLIN_EEPROM_SIZE, "FLASH_UNIT_SIZE must be greater than or equal to your MARLIN_EEPROM_SIZE");
static_assert(IS_FLASH_SECTOR(FLASH_SECTOR), "FLASH_SECTOR is invalid");
static_assert(IS_POWER_OF_2(FLASH_UNIT_SIZE), "FLASH_UNIT_SIZE should be a power of 2, please check your chip's spec sheet");
@@ -98,6 +100,11 @@
static bool eeprom_data_written = false;
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE size_t(E2END + 1)
+#endif
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+
bool PersistentStore::access_start() {
#if ENABLED(FLASH_EEPROM_LEVELING)
@@ -111,20 +118,20 @@ bool PersistentStore::access_start() {
while (address <= FLASH_ADDRESS_END) {
uint32_t address_value = (*(__IO uint32_t*)address);
if (address_value != EMPTY_UINT32) {
- current_slot = (address - FLASH_ADDRESS_START) / EEPROM_SIZE;
+ current_slot = (address - (FLASH_ADDRESS_START)) / (MARLIN_EEPROM_SIZE);
break;
}
address += sizeof(uint32_t);
}
if (current_slot == -1) {
// We didn't find anything, so we'll just intialize to empty
- for (int i = 0; i < EEPROM_SIZE; i++) ram_eeprom[i] = EMPTY_UINT8;
+ for (int i = 0; i < MARLIN_EEPROM_SIZE; i++) ram_eeprom[i] = EMPTY_UINT8;
current_slot = EEPROM_SLOTS;
}
else {
// load current settings
uint8_t *eeprom_data = (uint8_t *)SLOT_ADDRESS(current_slot);
- for (int i = 0; i < EEPROM_SIZE; i++) ram_eeprom[i] = eeprom_data[i];
+ for (int i = 0; i < MARLIN_EEPROM_SIZE; i++) ram_eeprom[i] = eeprom_data[i];
DEBUG_ECHOLNPAIR("EEPROM loaded from slot ", current_slot, ".");
}
eeprom_data_written = false;
@@ -140,6 +147,11 @@ bool PersistentStore::access_start() {
bool PersistentStore::access_finish() {
if (eeprom_data_written) {
+ #ifdef STM32F4xx
+ // MCU may come up with flash error bits which prevent some flash operations.
+ // Clear flags prior to flash operations to prevent errors.
+ __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
+ #endif
#if ENABLED(FLASH_EEPROM_LEVELING)
@@ -160,7 +172,11 @@ bool PersistentStore::access_finish() {
current_slot = EEPROM_SLOTS - 1;
UNLOCK_FLASH();
+ PAUSE_SERVO_OUTPUT();
+ DISABLE_ISRS();
status = HAL_FLASHEx_Erase(&EraseInitStruct, &SectorError);
+ ENABLE_ISRS();
+ RESUME_SERVO_OUTPUT();
if (status != HAL_OK) {
DEBUG_ECHOLNPAIR("HAL_FLASHEx_Erase=", status);
DEBUG_ECHOLNPAIR("GetError=", HAL_FLASH_GetError());
@@ -174,7 +190,7 @@ bool PersistentStore::access_finish() {
uint32_t offset = 0;
uint32_t address = SLOT_ADDRESS(current_slot);
- uint32_t address_end = address + EEPROM_SIZE;
+ uint32_t address_end = address + MARLIN_EEPROM_SIZE;
uint32_t data = 0;
bool success = true;
@@ -205,7 +221,18 @@ bool PersistentStore::access_finish() {
return success;
#else
+ // The following was written for the STM32F4 but may work with other MCUs as well.
+ // Most STM32F4 flash does not allow reading from flash during erase operations.
+ // This takes about a second on a STM32F407 with a 128kB sector used as EEPROM.
+ // Interrupts during this time can have unpredictable results, such as killing Servo
+ // output. Servo output still glitches with interrupts disabled, but recovers after the
+ // erase.
+ PAUSE_SERVO_OUTPUT();
+ DISABLE_ISRS();
eeprom_buffer_flush();
+ ENABLE_ISRS();
+ RESUME_SERVO_OUTPUT();
+
eeprom_data_written = false;
#endif
}
@@ -236,13 +263,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
do {
- const uint8_t c = (
- #if ENABLED(FLASH_EEPROM_LEVELING)
- ram_eeprom[pos]
- #else
- eeprom_buffered_read_byte(pos)
- #endif
- );
+ const uint8_t c = TERN(FLASH_EEPROM_LEVELING, ram_eeprom[pos], eeprom_buffered_read_byte(pos));
if (writing) *value = c;
crc16(crc, &c, 1);
pos++;
@@ -251,15 +272,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
return false;
}
-size_t PersistentStore::capacity() {
- return (
- #if ENABLED(FLASH_EEPROM_LEVELING)
- EEPROM_SIZE
- #else
- E2END + 1
- #endif
- );
-}
-
-#endif // EEPROM_SETTINGS && FLASH_EEPROM_EMULATION
+#endif // FLASH_EEPROM_EMULATION
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/eeprom_sdcard.cpp b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp
index 2b89c21b8..711a83ed5 100644
--- a/Marlin/src/HAL/STM32/eeprom_sdcard.cpp
+++ b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -31,53 +31,44 @@
#if ENABLED(SDCARD_EEPROM_EMULATION)
#include "../shared/eeprom_api.h"
+#include "../../sd/cardreader.h"
-#ifndef E2END
- #define E2END 0xFFF // 4KB
+#define EEPROM_FILENAME "eeprom.dat"
+
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE 0x1000 // 4KB
#endif
-#define HAL_EEPROM_SIZE int(E2END + 1)
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
#define _ALIGN(x) __attribute__ ((aligned(x)))
-static char _ALIGN(4) HAL_eeprom_data[HAL_EEPROM_SIZE];
+static char _ALIGN(4) HAL_eeprom_data[MARLIN_EEPROM_SIZE];
-#if ENABLED(SDSUPPORT)
+bool PersistentStore::access_start() {
+ if (!card.isMounted()) return false;
- #include "../../sd/cardreader.h"
-
- #define EEPROM_FILENAME "eeprom.dat"
-
- bool PersistentStore::access_start() {
- if (!card.isMounted()) return false;
-
- SdFile file, root = card.getroot();
- if (!file.open(&root, EEPROM_FILENAME, O_RDONLY))
- return true;
-
- int bytes_read = file.read(HAL_eeprom_data, HAL_EEPROM_SIZE);
- if (bytes_read < 0) return false;
- for (; bytes_read < HAL_EEPROM_SIZE; bytes_read++)
- HAL_eeprom_data[bytes_read] = 0xFF;
- file.close();
+ SdFile file, root = card.getroot();
+ if (!file.open(&root, EEPROM_FILENAME, O_RDONLY))
return true;
+
+ int bytes_read = file.read(HAL_eeprom_data, MARLIN_EEPROM_SIZE);
+ if (bytes_read < 0) return false;
+ for (; bytes_read < MARLIN_EEPROM_SIZE; bytes_read++)
+ HAL_eeprom_data[bytes_read] = 0xFF;
+ file.close();
+ return true;
+}
+
+bool PersistentStore::access_finish() {
+ if (!card.isMounted()) return false;
+
+ SdFile file, root = card.getroot();
+ int bytes_written = 0;
+ if (file.open(&root, EEPROM_FILENAME, O_CREAT | O_WRITE | O_TRUNC)) {
+ bytes_written = file.write(HAL_eeprom_data, MARLIN_EEPROM_SIZE);
+ file.close();
}
-
- bool PersistentStore::access_finish() {
- if (!card.isMounted()) return false;
-
- SdFile file, root = card.getroot();
- int bytes_written = 0;
- if (file.open(&root, EEPROM_FILENAME, O_CREAT | O_WRITE | O_TRUNC)) {
- bytes_written = file.write(HAL_eeprom_data, HAL_EEPROM_SIZE);
- file.close();
- }
- return (bytes_written == HAL_EEPROM_SIZE);
- }
-
-#else // !SDSUPPORT
-
- #error "Please define an EEPROM, a SDCARD or disable EEPROM_SETTINGS."
-
-#endif // !SDSUPPORT
+ return (bytes_written == MARLIN_EEPROM_SIZE);
+}
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
for (size_t i = 0; i < size; i++)
@@ -97,7 +88,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin
return false;
}
-size_t PersistentStore::capacity() { return HAL_EEPROM_SIZE; }
-
#endif // SDCARD_EEPROM_EMULATION
#endif // STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/eeprom_impl.cpp b/Marlin/src/HAL/STM32/eeprom_sram.cpp
similarity index 58%
rename from Marlin/src/HAL/STM32/eeprom_impl.cpp
rename to Marlin/src/HAL/STM32/eeprom_sram.cpp
index cd0f93e8d..5f6f26f9c 100644
--- a/Marlin/src/HAL/STM32/eeprom_impl.cpp
+++ b/Marlin/src/HAL/STM32/eeprom_sram.cpp
@@ -17,44 +17,32 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
#include "../../inc/MarlinConfig.h"
-#if EITHER(USE_WIRED_EEPROM, SRAM_EEPROM_EMULATION)
+#if ENABLED(SRAM_EEPROM_EMULATION)
+#include "../shared/eeprom_if.h"
#include "../shared/eeprom_api.h"
-bool PersistentStore::access_start() {
- return true;
-}
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE 0x1000 // 4KB
+#endif
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
-bool PersistentStore::access_finish() {
- return true;
-}
+bool PersistentStore::access_start() { return true; }
+bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
while (size--) {
uint8_t v = *value;
- // Save to either external EEPROM, program flash or Backup SRAM
- #if USE_WIRED_EEPROM
- // EEPROM has only ~100,000 write cycles,
- // so only write bytes that have changed!
- uint8_t * const p = (uint8_t * const)pos;
- if (v != eeprom_read_byte(p)) {
- eeprom_write_byte(p, v);
- if (eeprom_read_byte(p) != v) {
- SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
- return true;
- }
- }
- #else
- *(__IO uint8_t *)(BKPSRAM_BASE + (uint8_t * const)pos) = v;
- #endif
+ // Save to Backup SRAM
+ *(__IO uint8_t *)(BKPSRAM_BASE + (uint8_t * const)pos) = v;
crc16(crc, &v, 1);
pos++;
@@ -67,14 +55,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
do {
// Read from either external EEPROM, program flash or Backup SRAM
- const uint8_t c = (
- #if USE_WIRED_EEPROM
- eeprom_read_byte((uint8_t*)pos)
- #else
- (*(__IO uint8_t *)(BKPSRAM_BASE + ((uint8_t*)pos)))
- #endif
- );
-
+ const uint8_t c = ( *(__IO uint8_t *)(BKPSRAM_BASE + ((uint8_t*)pos)) );
if (writing) *value = c;
crc16(crc, &c, 1);
pos++;
@@ -83,15 +64,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
return false;
}
-size_t PersistentStore::capacity() {
- return (
- #if USE_WIRED_EEPROM
- E2END + 1
- #else
- 4096 // 4kB
- #endif
- );
-}
-
-#endif // USE_WIRED_EEPROM || SRAM_EEPROM_EMULATION
+#endif // SRAM_EEPROM_EMULATION
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/eeprom_wired.cpp b/Marlin/src/HAL/STM32/eeprom_wired.cpp
new file mode 100644
index 000000000..8c46e45f0
--- /dev/null
+++ b/Marlin/src/HAL/STM32/eeprom_wired.cpp
@@ -0,0 +1,81 @@
+/**
+ * Marlin 3D Printer Firmware
+ *
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
+ * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
+ * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../inc/MarlinConfig.h"
+
+#if USE_WIRED_EEPROM
+
+/**
+ * PersistentStore for Arduino-style EEPROM interface
+ * with simple implementations supplied by Marlin.
+ */
+
+#include "../shared/eeprom_if.h"
+#include "../shared/eeprom_api.h"
+
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE size_t(E2END + 1)
+#endif
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+
+bool PersistentStore::access_start() { eeprom_init(); return true; }
+bool PersistentStore::access_finish() { return true; }
+
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ while (size--) {
+ uint8_t v = *value;
+
+ // EEPROM has only ~100,000 write cycles,
+ // so only write bytes that have changed!
+ uint8_t * const p = (uint8_t * const)pos;
+ if (v != eeprom_read_byte(p)) {
+ eeprom_write_byte(p, v);
+ if (eeprom_read_byte(p) != v) {
+ SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
+ return true;
+ }
+ }
+
+ crc16(crc, &v, 1);
+ pos++;
+ value++;
+ };
+
+ return false;
+}
+
+bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
+ do {
+ // Read from either external EEPROM, program flash or Backup SRAM
+ const uint8_t c = eeprom_read_byte((uint8_t*)pos);
+ if (writing) *value = c;
+ crc16(crc, &c, 1);
+ pos++;
+ value++;
+ } while (--size);
+ return false;
+}
+
+#endif // USE_WIRED_EEPROM
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/endstop_interrupts.h b/Marlin/src/HAL/STM32/endstop_interrupts.h
index 0b97c3c77..fdff8cc64 100644
--- a/Marlin/src/HAL/STM32/endstop_interrupts.h
+++ b/Marlin/src/HAL/STM32/endstop_interrupts.h
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -28,43 +28,22 @@
void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts() {
- #if HAS_X_MAX
- attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_X_MIN
- attachInterrupt(X_MIN_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Y_MAX
- attachInterrupt(Y_MAX_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Y_MIN
- attachInterrupt(Y_MIN_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z_MAX
- attachInterrupt(Z_MAX_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z_MIN
- attachInterrupt(Z_MIN_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z2_MAX
- attachInterrupt(Z2_MAX_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z2_MIN
- attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z3_MAX
- attachInterrupt(Z3_MAX_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z3_MIN
- attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z4_MAX
- attachInterrupt(Z4_MAX_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z4_MIN
- attachInterrupt(Z4_MIN_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z_MIN_PROBE_PIN
- attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
- #endif
+ #define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE)
+ TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN));
+ TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN));
+ TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN));
+ TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN));
+ TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN));
+ TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN));
+ TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN));
+ TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN));
+ TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN));
+ TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN));
+ TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN));
+ TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN));
+ TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN));
+ TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN));
+ TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
+ TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
+ TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
}
diff --git a/Marlin/src/HAL/STM32/fastio.cpp b/Marlin/src/HAL/STM32/fastio.cpp
index c51effaa0..0d55579d8 100644
--- a/Marlin/src/HAL/STM32/fastio.cpp
+++ b/Marlin/src/HAL/STM32/fastio.cpp
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
diff --git a/Marlin/src/HAL/STM32/fastio.h b/Marlin/src/HAL/STM32/fastio.h
index c17901fa9..d90b2fbeb 100644
--- a/Marlin/src/HAL/STM32/fastio.h
+++ b/Marlin/src/HAL/STM32/fastio.h
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -64,12 +64,14 @@ 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_OD(IO) pinMode(IO, OUTPUT_OPEN_DRAIN)
#define WRITE(IO,V) _WRITE(IO,V)
#define READ(IO) _READ(IO)
#define TOGGLE(IO) _TOGGLE(IO)
#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
+#define OUT_WRITE_OD(IO,V) do{ _SET_OUTPUT_OD(IO); WRITE(IO,V); }while(0)
#define SET_INPUT(IO) _SET_MODE(IO, INPUT) /*!< Input Floating Mode */
#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) /*!< Input with Pull-up activation */
@@ -81,6 +83,7 @@ void FastIO_init(); // Must be called before using fast io macros
#define IS_OUTPUT(IO)
#define PWM_PIN(P) digitalPinHasPWM(P)
+#define NO_COMPILE_TIME_PWM
// digitalRead/Write wrappers
#define extDigitalRead(IO) digitalRead(IO)
diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_LCD.h b/Marlin/src/HAL/STM32/inc/Conditionals_LCD.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/STM32/inc/Conditionals_LCD.h
+++ b/Marlin/src/HAL/STM32/inc/Conditionals_LCD.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_adv.h b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/STM32/inc/Conditionals_adv.h
+++ b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_post.h b/Marlin/src/HAL/STM32/inc/Conditionals_post.h
index 11603c9ef..18826e11d 100644
--- a/Marlin/src/HAL/STM32/inc/Conditionals_post.h
+++ b/Marlin/src/HAL/STM32/inc/Conditionals_post.h
@@ -16,12 +16,14 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
-// If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation
-#if ENABLED(EEPROM_SETTINGS) && NONE(USE_WIRED_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION)
+// If no real or emulated EEPROM selected, fall back to SD emulation
+#if USE_FALLBACK_EEPROM
#define SDCARD_EEPROM_EMULATION
+#elif EITHER(I2C_EEPROM, SPI_EEPROM)
+ #define USE_SHARED_EEPROM 1
#endif
diff --git a/Marlin/src/HAL/STM32/inc/SanityCheck.h b/Marlin/src/HAL/STM32/inc/SanityCheck.h
index b1d0029ba..37ca3d5a3 100644
--- a/Marlin/src/HAL/STM32/inc/SanityCheck.h
+++ b/Marlin/src/HAL/STM32/inc/SanityCheck.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -28,10 +28,29 @@
// #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector"
//#endif
-#if ENABLED(EMERGENCY_PARSER)
- #error "EMERGENCY_PARSER is not yet implemented for STM32. Disable EMERGENCY_PARSER to continue."
-#endif
-
#if ENABLED(FAST_PWM_FAN)
#error "FAST_PWM_FAN is not yet implemented for this platform."
#endif
+
+#if ENABLED(SDCARD_EEPROM_EMULATION) && DISABLED(SDSUPPORT)
+ #undef SDCARD_EEPROM_EMULATION // Avoid additional error noise
+ #if USE_FALLBACK_EEPROM
+ #warning "EEPROM type not specified. Fallback is SDCARD_EEPROM_EMULATION."
+ #endif
+ #error "SDCARD_EEPROM_EMULATION requires SDSUPPORT. Enable SDSUPPORT or choose another EEPROM emulation."
+#endif
+
+#if defined(STM32F4xx) && BOTH(PRINTCOUNTER, FLASH_EEPROM_EMULATION)
+ #warning "FLASH_EEPROM_EMULATION may cause long delays when writing and should not be used while printing."
+ #error "Disable PRINTCOUNTER or choose another EEPROM emulation."
+#endif
+
+#if !defined(STM32F4xx) && ENABLED(FLASH_EEPROM_LEVELING)
+ #error "FLASH_EEPROM_LEVELING is currently only supported on STM32F4 hardware."
+#endif
+
+#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
+ #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on this platform."
+#elif ENABLED(SERIAL_STATS_DROPPED_RX)
+ #error "SERIAL_STATS_DROPPED_RX is not supported on this platform."
+#endif
diff --git a/Marlin/src/HAL/STM32/pinsDebug.h b/Marlin/src/HAL/STM32/pinsDebug.h
index 8c5d1ec2b..ec08e3fd7 100644
--- a/Marlin/src/HAL/STM32/pinsDebug.h
+++ b/Marlin/src/HAL/STM32/pinsDebug.h
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h b/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h
index e3d28aed0..5ff40debe 100644
--- a/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h
+++ b/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32/pinsDebug_STM32duino.h b/Marlin/src/HAL/STM32/pinsDebug_STM32duino.h
index 58b8c32cc..09f2bb54e 100644
--- a/Marlin/src/HAL/STM32/pinsDebug_STM32duino.h
+++ b/Marlin/src/HAL/STM32/pinsDebug_STM32duino.h
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32/pins_Xref.h b/Marlin/src/HAL/STM32/pins_Xref.h
index 7e88ec76b..890e56186 100644
--- a/Marlin/src/HAL/STM32/pins_Xref.h
+++ b/Marlin/src/HAL/STM32/pins_Xref.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/STM32/spi_pins.h b/Marlin/src/HAL/STM32/spi_pins.h
index 8f46ca12c..176e2a7b2 100644
--- a/Marlin/src/HAL/STM32/spi_pins.h
+++ b/Marlin/src/HAL/STM32/spi_pins.h
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp
index b7b65f714..119673144 100644
--- a/Marlin/src/HAL/STM32/timers.cpp
+++ b/Marlin/src/HAL/STM32/timers.cpp
@@ -16,15 +16,12 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
-#include "HAL.h"
-
-#include "timers.h"
+#include "../../inc/MarlinConfig.h"
// ------------------------
// Local defines
@@ -32,11 +29,82 @@
#define NUM_HARDWARE_TIMERS 2
+// Default timer priorities. Override by specifying alternate priorities in the board pins file.
+// The TONE timer is not present here, as it currently cannot be set programmatically. It is set
+// by defining TIM_IRQ_PRIO in the variant.h or platformio.ini file, which adjusts the default
+// priority for STM32 HardwareTimer objects.
+#define SWSERIAL_TIMER_IRQ_PRIO_DEFAULT 1 // Requires tight bit timing to communicate reliably with TMC drivers
+#define SERVO_TIMER_IRQ_PRIO_DEFAULT 1 // Requires tight PWM timing to control a BLTouch reliably
+#define STEP_TIMER_IRQ_PRIO_DEFAULT 2
+#define TEMP_TIMER_IRQ_PRIO_DEFAULT 14 // Low priority avoids interference with other hardware and timers
+
+#ifndef STEP_TIMER_IRQ_PRIO
+ #define STEP_TIMER_IRQ_PRIO STEP_TIMER_IRQ_PRIO_DEFAULT
+#endif
+#ifndef TEMP_TIMER_IRQ_PRIO
+ #define TEMP_TIMER_IRQ_PRIO TEMP_TIMER_IRQ_PRIO_DEFAULT
+#endif
+#if HAS_TMC_SW_SERIAL
+ #include
+ #ifndef SWSERIAL_TIMER_IRQ_PRIO
+ #define SWSERIAL_TIMER_IRQ_PRIO SWSERIAL_TIMER_IRQ_PRIO_DEFAULT
+ #endif
+#endif
+#if HAS_SERVOS
+ #include "Servo.h"
+ #ifndef SERVO_TIMER_IRQ_PRIO
+ #define SERVO_TIMER_IRQ_PRIO SERVO_TIMER_IRQ_PRIO_DEFAULT
+ #endif
+#endif
+#if ENABLED(SPEAKER)
+ // Ensure the default timer priority is somewhere between the STEP and TEMP priorities.
+ // The STM32 framework defaults to interrupt 14 for all timers. This should be increased so that
+ // timing-sensitive operations such as speaker output are not impacted by the long-running
+ // temperature ISR. This must be defined in the platformio.ini file or the board's variant.h,
+ // so that it will be consumed by framework code.
+ #if !(TIM_IRQ_PRIO > STEP_TIMER_IRQ_PRIO && TIM_IRQ_PRIO < TEMP_TIMER_IRQ_PRIO)
+ #error "Default timer interrupt priority is unspecified or set to a value which may degrade performance."
+ #endif
+#endif
+
+#ifdef STM32F0xx
+ #define MCU_TIMER_RATE (F_CPU) // Frequency of timer peripherals
+ #define MCU_STEP_TIMER 16
+ #define MCU_TEMP_TIMER 17
+#elif defined(STM32F1xx)
+ #define MCU_TIMER_RATE (F_CPU)
+ #define MCU_STEP_TIMER 4
+ #define MCU_TEMP_TIMER 2
+#elif defined(STM32F401xC) || defined(STM32F401xE)
+ #define MCU_TIMER_RATE (F_CPU / 2)
+ #define MCU_STEP_TIMER 9
+ #define MCU_TEMP_TIMER 10
+#elif defined(STM32F4xx) || defined(STM32F7xx)
+ #define MCU_TIMER_RATE (F_CPU / 2)
+ #define MCU_STEP_TIMER 6 // STM32F401 has no TIM6, TIM7, or TIM8
+ #define MCU_TEMP_TIMER 14 // TIM7 is consumed by Software Serial if used.
+#endif
+
+#ifndef HAL_TIMER_RATE
+ #define HAL_TIMER_RATE MCU_TIMER_RATE
+#endif
+#ifndef STEP_TIMER
+ #define STEP_TIMER MCU_STEP_TIMER
+#endif
+#ifndef TEMP_TIMER
+ #define TEMP_TIMER MCU_TEMP_TIMER
+#endif
+
#define __TIMER_DEV(X) TIM##X
#define _TIMER_DEV(X) __TIMER_DEV(X)
#define STEP_TIMER_DEV _TIMER_DEV(STEP_TIMER)
#define TEMP_TIMER_DEV _TIMER_DEV(TEMP_TIMER)
+#define __TIMER_IRQ_NAME(X) TIM##X##_IRQn
+#define _TIMER_IRQ_NAME(X) __TIMER_IRQ_NAME(X)
+#define STEP_TIMER_IRQ_NAME _TIMER_IRQ_NAME(STEP_TIMER)
+#define TEMP_TIMER_IRQ_NAME _TIMER_IRQ_NAME(TEMP_TIMER)
+
// ------------------------
// Private Variables
// ------------------------
@@ -136,4 +204,9 @@ TIM_TypeDef * HAL_timer_device(const uint8_t timer_num) {
return nullptr;
}
+void SetTimerInterruptPriorities() {
+ TERN_(HAS_TMC_SW_SERIAL, SoftwareSerial::setInterruptPriority(SWSERIAL_TIMER_IRQ_PRIO, 0));
+ TERN_(HAS_SERVOS, libServo::setInterruptPriority(SERVO_TIMER_IRQ_PRIO, 0));
+}
+
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h
index 8a0950a4d..000f86043 100644
--- a/Marlin/src/HAL/STM32/timers.h
+++ b/Marlin/src/HAL/STM32/timers.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -33,84 +33,16 @@
#define hal_timer_t uint32_t
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF // Timers can be 16 or 32 bit
-#ifdef STM32F0xx
-
- #define HAL_TIMER_RATE (F_CPU) // frequency of timer peripherals
-
- #ifndef STEP_TIMER
- #define STEP_TIMER 16
- #endif
-
- #ifndef TEMP_TIMER
- #define TEMP_TIMER 17
- #endif
-
-#elif defined(STM32F1xx)
-
- #define HAL_TIMER_RATE (F_CPU) // frequency of timer peripherals
-
- #ifndef STEP_TIMER
- #define STEP_TIMER 4
- #endif
-
- #ifndef TEMP_TIMER
- #define TEMP_TIMER 2
- #endif
-
-#elif defined(STM32F401xC) || defined(STM32F401xE)
-
- #define HAL_TIMER_RATE (F_CPU / 2) // frequency of timer peripherals
-
- #ifndef STEP_TIMER
- #define STEP_TIMER 9
- #endif
-
- #ifndef TEMP_TIMER
- #define TEMP_TIMER 10
- #endif
-
-#elif defined(STM32F4xx)
-
- #define HAL_TIMER_RATE (F_CPU / 2) // frequency of timer peripherals
-
- #ifndef STEP_TIMER
- #define STEP_TIMER 6 // STM32F401 has no TIM6, TIM7, or TIM8
- #endif
-
- #ifndef TEMP_TIMER
- #define TEMP_TIMER 14 // TIM7 is consumed by Software Serial if used.
- #endif
-
-#elif defined(STM32F7xx)
-
- #define HAL_TIMER_RATE (F_CPU / 2) // frequency of timer peripherals
-
- #ifndef STEP_TIMER
- #define STEP_TIMER 6 // the RIGHT timer!
- #endif
-
- #ifndef TEMP_TIMER
- #define TEMP_TIMER 14
- #endif
-
+#ifndef STEP_TIMER_NUM
+ #define STEP_TIMER_NUM 0 // Timer Index for Stepper
#endif
-
-#ifndef SWSERIAL_TIMER_IRQ_PRIO
- #define SWSERIAL_TIMER_IRQ_PRIO 1
+#ifndef PULSE_TIMER_NUM
+ #define PULSE_TIMER_NUM STEP_TIMER_NUM
#endif
-
-#ifndef STEP_TIMER_IRQ_PRIO
- #define STEP_TIMER_IRQ_PRIO 2
+#ifndef TEMP_TIMER_NUM
+ #define TEMP_TIMER_NUM 1 // Timer Index for Temperature
#endif
-#ifndef TEMP_TIMER_IRQ_PRIO
- #define TEMP_TIMER_IRQ_PRIO 14 // 14 = after hardware ISRs
-#endif
-
-#define STEP_TIMER_NUM 0 // index of timer to use for stepper
-#define TEMP_TIMER_NUM 1 // index of timer to use for temperature
-#define PULSE_TIMER_NUM STEP_TIMER_NUM
-
#define TEMP_TIMER_FREQUENCY 1000 // Temperature::isr() is expected to be called at around 1kHz
// TODO: get rid of manual rate/prescale/ticks/cycles taken for procedures in stepper.cpp
@@ -122,12 +54,6 @@
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
-#define __TIMER_IRQ_NAME(X) TIM##X##_IRQn
-#define _TIMER_IRQ_NAME(X) __TIMER_IRQ_NAME(X)
-
-#define STEP_TIMER_IRQ_NAME _TIMER_IRQ_NAME(STEP_TIMER)
-#define TEMP_TIMER_IRQ_NAME _TIMER_IRQ_NAME(TEMP_TIMER)
-
#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM)
#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
@@ -137,8 +63,13 @@
extern void Step_Handler(HardwareTimer *htim);
extern void Temp_Handler(HardwareTimer *htim);
-#define HAL_STEP_TIMER_ISR() void Step_Handler(HardwareTimer *htim)
-#define HAL_TEMP_TIMER_ISR() void Temp_Handler(HardwareTimer *htim)
+
+#ifndef HAL_STEP_TIMER_ISR
+ #define HAL_STEP_TIMER_ISR() void Step_Handler(HardwareTimer *htim)
+#endif
+#ifndef HAL_TEMP_TIMER_ISR
+ #define HAL_TEMP_TIMER_ISR() void Temp_Handler(HardwareTimer *htim)
+#endif
// ------------------------
// Public Variables
@@ -155,6 +86,10 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num);
void HAL_timer_disable_interrupt(const uint8_t timer_num);
bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
+// Configure timer priorities for peripherals such as Software Serial or Servos.
+// Exposed here to allow all timer priority information to reside in timers.cpp
+void SetTimerInterruptPriorities();
+
//TIM_TypeDef* HAL_timer_device(const uint8_t timer_num); no need to be public for now. not public = not used externally
// FORCE_INLINE because these are used in performance-critical situations
diff --git a/Marlin/src/HAL/STM32/usb_serial.cpp b/Marlin/src/HAL/STM32/usb_serial.cpp
new file mode 100644
index 000000000..2dd1bef12
--- /dev/null
+++ b/Marlin/src/HAL/STM32/usb_serial.cpp
@@ -0,0 +1,55 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../inc/MarlinConfigPre.h"
+
+#if ENABLED(EMERGENCY_PARSER)
+
+#include "usb_serial.h"
+#include "../../feature/e_parser.h"
+
+EmergencyParser::State emergency_state = EmergencyParser::State::EP_RESET;
+
+int8_t (*USBD_CDC_Receive_original) (uint8_t *Buf, uint32_t *Len) = nullptr;
+
+static int8_t USBD_CDC_Receive_hook(uint8_t *Buf, uint32_t *Len) {
+ for (uint32_t i = 0; i < *Len; i++)
+ emergency_parser.update(emergency_state, Buf[i]);
+ return USBD_CDC_Receive_original(Buf, Len);
+}
+
+typedef struct _USBD_CDC_Itf {
+ int8_t (* Init)(void);
+ int8_t (* DeInit)(void);
+ int8_t (* Control)(uint8_t cmd, uint8_t *pbuf, uint16_t length);
+ int8_t (* Receive)(uint8_t *Buf, uint32_t *Len);
+ int8_t (* Transferred)(void);
+} USBD_CDC_ItfTypeDef;
+
+extern USBD_CDC_ItfTypeDef USBD_CDC_fops;
+
+void USB_Hook_init() {
+ USBD_CDC_Receive_original = USBD_CDC_fops.Receive;
+ USBD_CDC_fops.Receive = USBD_CDC_Receive_hook;
+}
+
+#endif // EMERGENCY_PARSER
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/usb_serial.h b/Marlin/src/HAL/STM32/usb_serial.h
new file mode 100644
index 000000000..ca61b9ed2
--- /dev/null
+++ b/Marlin/src/HAL/STM32/usb_serial.h
@@ -0,0 +1,21 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#pragma once
+
+void USB_Hook_init();
diff --git a/Marlin/src/HAL/STM32/watchdog.cpp b/Marlin/src/HAL/STM32/watchdog.cpp
index 2c6b583e8..37e5638b0 100644
--- a/Marlin/src/HAL/STM32/watchdog.cpp
+++ b/Marlin/src/HAL/STM32/watchdog.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
#include "../../inc/MarlinConfigPre.h"
diff --git a/Marlin/src/HAL/STM32/watchdog.h b/Marlin/src/HAL/STM32/watchdog.h
index efa7d2b3d..49a0d9c63 100644
--- a/Marlin/src/HAL/STM32/watchdog.h
+++ b/Marlin/src/HAL/STM32/watchdog.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp
index 01fd2c8fc..d7f9264be 100644
--- a/Marlin/src/HAL/STM32F1/HAL.cpp
+++ b/Marlin/src/HAL/STM32F1/HAL.cpp
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -100,7 +100,7 @@ const uint8_t adc_pins[] = {
#if HAS_HEATED_BED
TEMP_BED_PIN,
#endif
- #if HAS_HEATED_CHAMBER
+ #if HAS_TEMP_CHAMBER
TEMP_CHAMBER_PIN,
#endif
#if HAS_TEMP_ADC_1
@@ -139,16 +139,22 @@ const uint8_t adc_pins[] = {
#if HAS_JOY_ADC_Z
JOY_Z_PIN,
#endif
+ #if ENABLED(POWER_MONITOR_CURRENT)
+ POWER_MONITOR_CURRENT_PIN,
+ #endif
+ #if ENABLED(POWER_MONITOR_VOLTAGE)
+ POWER_MONITOR_VOLTAGE_PIN,
+ #endif
};
-enum TEMP_PINS : char {
+enum TempPinIndex : char {
#if HAS_TEMP_ADC_0
TEMP_0,
#endif
#if HAS_HEATED_BED
TEMP_BED,
#endif
- #if HAS_HEATED_CHAMBER
+ #if HAS_TEMP_CHAMBER
TEMP_CHAMBER,
#endif
#if HAS_TEMP_ADC_1
@@ -187,6 +193,12 @@ enum TEMP_PINS : char {
#if HAS_JOY_ADC_Z
JOY_Z,
#endif
+ #if ENABLED(POWER_MONITOR_CURRENT)
+ POWERMON_CURRENT,
+ #endif
+ #if ENABLED(POWER_MONITOR_VOLTAGE)
+ POWERMON_VOLTS,
+ #endif
ADC_PIN_COUNT
};
@@ -246,7 +258,7 @@ void HAL_init() {
// HAL idle task
void HAL_idletask() {
#ifdef USE_USB_COMPOSITE
- #if ENABLED(SHARED_SD_CARD)
+ #if HAS_SHARED_MEDIA
// If Marlin is using the SD card we need to lock it to prevent access from
// a PC via USB.
// Other HALs use IS_SD_PRINTING() and IS_SD_FILE_OPEN() to check for access but
@@ -254,7 +266,7 @@ void HAL_idletask() {
// the disk if Marlin has it mounted. Unfortunately there is currently no way
// to unmount the disk from the LCD menu.
// if (IS_SD_PRINTING() || IS_SD_FILE_OPEN())
- /* copy from lpc1768 framework, should be fixed later for process SHARED_SD_CARD*/
+ /* copy from lpc1768 framework, should be fixed later for process HAS_SHARED_MEDIA*/
#endif
// process USB mass storage device class loop
MarlinMSC.loop();
@@ -265,9 +277,8 @@ void HAL_clear_reset_source() { }
/**
* TODO: Check this and change or remove.
- * currently returns 1 that's equal to poweron reset.
*/
-uint8_t HAL_get_reset_source() { return 1; }
+uint8_t HAL_get_reset_source() { return RST_POWER_ON; }
void _delay_ms(const int delay_ms) { delay(delay_ms); }
@@ -323,7 +334,8 @@ void HAL_adc_init() {
}
void HAL_adc_start_conversion(const uint8_t adc_pin) {
- TEMP_PINS pin_index;
+ //TEMP_PINS pin_index;
+ TempPinIndex pin_index;
switch (adc_pin) {
default: return;
#if HAS_TEMP_ADC_0
@@ -332,7 +344,7 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) {
#if HAS_HEATED_BED
case TEMP_BED_PIN: pin_index = TEMP_BED; break;
#endif
- #if HAS_HEATED_CHAMBER
+ #if HAS_TEMP_CHAMBER
case TEMP_CHAMBER_PIN: pin_index = TEMP_CHAMBER; break;
#endif
#if HAS_TEMP_ADC_1
@@ -371,6 +383,12 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) {
#if ENABLED(ADC_KEYPAD)
case ADC_KEYPAD_PIN: pin_index = ADC_KEY; break;
#endif
+ #if ENABLED(POWER_MONITOR_CURRENT)
+ case POWER_MONITOR_CURRENT_PIN: pin_index = POWERMON_CURRENT; break;
+ #endif
+ #if ENABLED(POWER_MONITOR_VOLTAGE)
+ case POWER_MONITOR_VOLTAGE_PIN: pin_index = POWERMON_VOLTS; break;
+ #endif
}
HAL_adc_result = (HAL_adc_results[(int)pin_index] >> 2) & 0x3FF; // shift to get 10 bits only.
}
diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h
index ff42beb92..5a0b04600 100644
--- a/Marlin/src/HAL/STM32F1/HAL.h
+++ b/Marlin/src/HAL/STM32F1/HAL.h
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -36,7 +36,6 @@
#include "fastio.h"
#include "watchdog.h"
-#include "timers.h"
#include
#include
@@ -52,7 +51,7 @@
// ------------------------
#ifndef STM32_FLASH_SIZE
- #ifdef MCU_STM32F103RE
+ #if defined(MCU_STM32F103RE) || defined(MCU_STM32F103VE)
#define STM32_FLASH_SIZE 512
#else
#define STM32_FLASH_SIZE 256
@@ -248,19 +247,6 @@ static int freeMemory() {
#pragma GCC diagnostic pop
-//
-// EEPROM
-//
-
-/**
- * TODO: Write all this EEPROM stuff. Can emulate EEPROM in flash as last resort.
- * Wire library should work for i2c EEPROMs.
- */
-void eeprom_write_byte(uint8_t *pos, unsigned char value);
-uint8_t eeprom_read_byte(uint8_t *pos);
-void eeprom_read_block(void *__dst, const void *__src, size_t __n);
-void eeprom_update_block(const void *__src, void *__dst, size_t __n);
-
//
// ADC
//
@@ -269,8 +255,9 @@ void eeprom_update_block(const void *__src, void *__dst, size_t __n);
void HAL_adc_init();
-#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
+#define HAL_ADC_VREF 3.3
#define HAL_ADC_RESOLUTION 10
+#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true
diff --git a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp
index bfbdf6af4..4d72473e7 100644
--- a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp
+++ b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/STM32F1/SPI.cpp b/Marlin/src/HAL/STM32F1/SPI.cpp
index 1cd064c35..80095ba1d 100644
--- a/Marlin/src/HAL/STM32F1/SPI.cpp
+++ b/Marlin/src/HAL/STM32F1/SPI.cpp
@@ -243,7 +243,7 @@ void SPIClass::setDataMode(uint8_t dataMode) {
_currentSetting->spi_d->regs->CR1 = cr1 | (dataMode & (SPI_CR1_CPOL|SPI_CR1_CPHA));
}
-void SPIClass::beginTransaction(uint8_t pin, SPISettings settings) {
+void SPIClass::beginTransaction(uint8_t pin, const SPISettings &settings) {
setBitOrder(settings.bitOrder);
setDataMode(settings.dataMode);
setDataSize(settings.dataSize);
@@ -251,7 +251,7 @@ void SPIClass::beginTransaction(uint8_t pin, SPISettings settings) {
begin();
}
-void SPIClass::beginTransactionSlave(SPISettings settings) {
+void SPIClass::beginTransactionSlave(const SPISettings &settings) {
setBitOrder(settings.bitOrder);
setDataMode(settings.dataMode);
setDataSize(settings.dataSize);
@@ -266,7 +266,7 @@ void SPIClass::endTransaction() { }
uint16_t SPIClass::read() {
while (!spi_is_rx_nonempty(_currentSetting->spi_d)) { /* nada */ }
- return (uint16)spi_rx_reg(_currentSetting->spi_d);
+ return (uint16_t)spi_rx_reg(_currentSetting->spi_d);
}
void SPIClass::read(uint8_t *buf, uint32_t len) {
diff --git a/Marlin/src/HAL/STM32F1/SPI.h b/Marlin/src/HAL/STM32F1/SPI.h
index 0162ac13b..dc2a21586 100644
--- a/Marlin/src/HAL/STM32F1/SPI.h
+++ b/Marlin/src/HAL/STM32F1/SPI.h
@@ -126,6 +126,7 @@ private:
bitOrder = inBitOrder;
dataMode = inDataMode;
dataSize = inDataSize;
+ //state = SPI_STATE_IDLE;
}
uint32_t clock;
uint32_t dataSize;
@@ -187,11 +188,11 @@ public:
*/
void end();
- void beginTransaction(SPISettings settings) { beginTransaction(BOARD_SPI_DEFAULT_SS, settings); }
- void beginTransaction(uint8_t pin, SPISettings settings);
+ void beginTransaction(const SPISettings &settings) { beginTransaction(BOARD_SPI_DEFAULT_SS, settings); }
+ void beginTransaction(uint8_t pin, const SPISettings &settings);
void endTransaction();
- void beginTransactionSlave(SPISettings settings);
+ void beginTransactionSlave(const SPISettings &settings);
void setClockDivider(uint32_t clockDivider);
void setBitOrder(BitOrder bitOrder);
diff --git a/Marlin/src/HAL/STM32F1/Servo.cpp b/Marlin/src/HAL/STM32F1/Servo.cpp
index 06abb2c2b..e1ee83149 100644
--- a/Marlin/src/HAL/STM32F1/Servo.cpp
+++ b/Marlin/src/HAL/STM32F1/Servo.cpp
@@ -17,10 +17,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __STM32F1__
#include "../../inc/MarlinConfig.h"
@@ -30,7 +29,6 @@
uint8_t ServoCount = 0;
#include "Servo.h"
-#include "timers.h"
//#include "Servo.h"
@@ -76,6 +74,7 @@ void libServo::servoWrite(uint8_t inPin, uint16_t duty_cycle) {
libServo::libServo() {
servoIndex = ServoCount < MAX_SERVOS ? ServoCount++ : INVALID_SERVO;
+ timer_set_interrupt_priority(SERVO0_TIMER_NUM, SERVO0_TIMER_IRQ_PRIO);
}
bool libServo::attach(const int32_t inPin, const int32_t inMinAngle, const int32_t inMaxAngle) {
@@ -138,9 +137,7 @@ void libServo::move(const int32_t value) {
angle = constrain(value, minAngle, maxAngle);
servoWrite(pin, US_TO_COMPARE(ANGLE_TO_US(angle)));
safe_delay(servo_delay[servoIndex]);
- #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
- detach();
- #endif
+ TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
}
}
diff --git a/Marlin/src/HAL/STM32F1/Servo.h b/Marlin/src/HAL/STM32F1/Servo.h
index b3ca09f23..b6143de81 100644
--- a/Marlin/src/HAL/STM32F1/Servo.h
+++ b/Marlin/src/HAL/STM32F1/Servo.h
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32F1/SoftwareSerial.cpp b/Marlin/src/HAL/STM32F1/SoftwareSerial.cpp
index e9e4a162a..3641c9fdf 100644
--- a/Marlin/src/HAL/STM32F1/SoftwareSerial.cpp
+++ b/Marlin/src/HAL/STM32F1/SoftwareSerial.cpp
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#if defined(__STM32F1__) && !defined(HAVE_SW_SERIAL)
diff --git a/Marlin/src/HAL/STM32F1/SoftwareSerial.h b/Marlin/src/HAL/STM32F1/SoftwareSerial.h
index 1899a2ae0..1c8058665 100644
--- a/Marlin/src/HAL/STM32F1/SoftwareSerial.h
+++ b/Marlin/src/HAL/STM32F1/SoftwareSerial.h
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_fsmc.cpp b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_fsmc.cpp
index cc26a003d..0f3887d29 100644
--- a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_fsmc.cpp
+++ b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_fsmc.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -291,7 +291,7 @@ uint32_t LCD_IO_ReadData(uint16_t RegValue, uint8_t ReadSize) {
return uint32_t(data);
}
-#if ENABLED(LCD_USE_DMA_FSMC)
+#ifdef LCD_USE_DMA_FSMC
void LCD_IO_WriteMultiple(uint16_t color, uint32_t count) {
while (count > 0) {
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 2e9d11f97..894abb882 100644
--- a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp
+++ b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp
@@ -13,14 +13,14 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#ifdef __STM32F1__
#include "../../../inc/MarlinConfig.h"
-#if HAS_GRAPHICAL_LCD && ENABLED(FORCE_SOFT_SPI)
+#if BOTH(HAS_GRAPHICAL_LCD, FORCE_SOFT_SPI)
#include "../HAL.h"
#include
diff --git a/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp b/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp
new file mode 100644
index 000000000..f77306a88
--- /dev/null
+++ b/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp
@@ -0,0 +1,81 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+
+/**
+ * PersistentStore for Arduino-style EEPROM interface
+ * with simple implementations supplied by Marlin.
+ */
+
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(IIC_BL24CXX_EEPROM)
+
+#include "../shared/eeprom_if.h"
+#include "../shared/eeprom_api.h"
+
+//
+// PersistentStore
+//
+
+#ifndef MARLIN_EEPROM_SIZE
+ #error "MARLIN_EEPROM_SIZE is required for IIC_BL24CXX_EEPROM."
+#endif
+
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+
+bool PersistentStore::access_start() { eeprom_init(); return true; }
+bool PersistentStore::access_finish() { return true; }
+
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ while (size--) {
+ uint8_t v = *value;
+ uint8_t * const p = (uint8_t * const)pos;
+ // EEPROM has only ~100,000 write cycles,
+ // so only write bytes that have changed!
+ if (v != eeprom_read_byte(p)) {
+ eeprom_write_byte(p, v);
+ delay(2);
+ if (eeprom_read_byte(p) != v) {
+ SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
+ return true;
+ }
+ }
+ crc16(crc, &v, 1);
+ pos++;
+ value++;
+ }
+ return false;
+}
+
+bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
+ do {
+ uint8_t * const p = (uint8_t * const)pos;
+ uint8_t c = eeprom_read_byte(p);
+ if (writing) *value = c;
+ crc16(crc, &c, 1);
+ pos++;
+ value++;
+ } while (--size);
+ return false;
+}
+
+#endif // IIC_BL24CXX_EEPROM
diff --git a/Marlin/src/HAL/STM32F1/eeprom_flash.cpp b/Marlin/src/HAL/STM32F1/eeprom_flash.cpp
index 9c8173046..8db8c8638 100644
--- a/Marlin/src/HAL/STM32F1/eeprom_flash.cpp
+++ b/Marlin/src/HAL/STM32F1/eeprom_flash.cpp
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -39,18 +39,20 @@
#include
// Store settings in the last two pages
-#define EEPROM_SIZE (EEPROM_PAGE_SIZE * 2)
-#define ACCESS_FINISHED(TF) do{ FLASH_Lock(); eeprom_dirty = false; return TF; }while(0)
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE ((EEPROM_PAGE_SIZE) * 2)
+#endif
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
-static uint8_t ram_eeprom[EEPROM_SIZE] __attribute__((aligned(4))) = {0};
+static uint8_t ram_eeprom[MARLIN_EEPROM_SIZE] __attribute__((aligned(4))) = {0};
static bool eeprom_dirty = false;
bool PersistentStore::access_start() {
const uint32_t* source = reinterpret_cast(EEPROM_PAGE0_BASE);
uint32_t* destination = reinterpret_cast(ram_eeprom);
- static_assert(0 == EEPROM_SIZE % 4, "EEPROM_SIZE is corrupted. (Must be a multiple of 4.)"); // Ensure copying as uint32_t is safe
- constexpr size_t eeprom_size_u32 = EEPROM_SIZE / 4;
+ static_assert(0 == (MARLIN_EEPROM_SIZE) % 4, "MARLIN_EEPROM_SIZE is corrupted. (Must be a multiple of 4.)"); // Ensure copying as uint32_t is safe
+ constexpr size_t eeprom_size_u32 = (MARLIN_EEPROM_SIZE) / 4;
for (size_t i = 0; i < eeprom_size_u32; ++i, ++destination, ++source)
*destination = *source;
@@ -72,13 +74,15 @@ bool PersistentStore::access_finish() {
// page changes...either way, something to look at later.
FLASH_Unlock();
+ #define ACCESS_FINISHED(TF) { FLASH_Lock(); eeprom_dirty = false; return TF; }
+
status = FLASH_ErasePage(EEPROM_PAGE0_BASE);
if (status != FLASH_COMPLETE) ACCESS_FINISHED(true);
status = FLASH_ErasePage(EEPROM_PAGE1_BASE);
if (status != FLASH_COMPLETE) ACCESS_FINISHED(true);
const uint16_t *source = reinterpret_cast(ram_eeprom);
- for (size_t i = 0; i < EEPROM_SIZE; i += 2, ++source) {
+ for (size_t i = 0; i < MARLIN_EEPROM_SIZE; i += 2, ++source) {
if (FLASH_ProgramHalfWord(EEPROM_PAGE0_BASE + i, *source) != FLASH_COMPLETE)
ACCESS_FINISHED(false);
}
@@ -105,7 +109,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin
return false; // return true for any error
}
-size_t PersistentStore::capacity() { return EEPROM_SIZE; }
-
#endif // FLASH_EEPROM_EMULATION
#endif // __STM32F1__
diff --git a/Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp b/Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp
new file mode 100644
index 000000000..33dd277ad
--- /dev/null
+++ b/Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp
@@ -0,0 +1,51 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+
+/**
+ * Platform-independent Arduino functions for I2C EEPROM.
+ * Enable USE_SHARED_EEPROM if not supplied by the framework.
+ */
+
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(IIC_BL24CXX_EEPROM)
+
+#include "../../libs/BL24CXX.h"
+#include "../shared/eeprom_if.h"
+
+void eeprom_init() { BL24CXX::init(); }
+
+// ------------------------
+// Public functions
+// ------------------------
+
+void eeprom_write_byte(uint8_t *pos, unsigned char value) {
+ const unsigned eeprom_address = (unsigned)pos;
+ return BL24CXX::writeOneByte(eeprom_address, value);
+}
+
+uint8_t eeprom_read_byte(uint8_t *pos) {
+ const unsigned eeprom_address = (unsigned)pos;
+ return BL24CXX::readOneByte(eeprom_address);
+}
+
+#endif // IIC_BL24CXX_EEPROM
diff --git a/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp b/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp
index 7894e6978..11959191f 100644
--- a/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp
+++ b/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -32,53 +32,44 @@
#if ENABLED(SDCARD_EEPROM_EMULATION)
#include "../shared/eeprom_api.h"
+#include "../../sd/cardreader.h"
-#ifndef E2END
- #define E2END 0xFFF // 4KB
+#define EEPROM_FILENAME "eeprom.dat"
+
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE 0x1000 // 4KB
#endif
-#define HAL_EEPROM_SIZE (E2END + 1)
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
#define _ALIGN(x) __attribute__ ((aligned(x))) // SDIO uint32_t* compat.
-static char _ALIGN(4) HAL_eeprom_data[HAL_EEPROM_SIZE];
+static char _ALIGN(4) HAL_eeprom_data[MARLIN_EEPROM_SIZE];
-#if ENABLED(SDSUPPORT)
+bool PersistentStore::access_start() {
+ if (!card.isMounted()) return false;
- #include "../../sd/cardreader.h"
+ SdFile file, root = card.getroot();
+ if (!file.open(&root, EEPROM_FILENAME, O_RDONLY))
+ return true; // false aborts the save
- #define EEPROM_FILENAME "eeprom.dat"
+ int bytes_read = file.read(HAL_eeprom_data, MARLIN_EEPROM_SIZE);
+ if (bytes_read < 0) return false;
+ for (; bytes_read < MARLIN_EEPROM_SIZE; bytes_read++)
+ HAL_eeprom_data[bytes_read] = 0xFF;
+ file.close();
+ return true;
+}
- bool PersistentStore::access_start() {
- if (!card.isMounted()) return false;
+bool PersistentStore::access_finish() {
+ if (!card.isMounted()) return false;
- SdFile file, root = card.getroot();
- if (!file.open(&root, EEPROM_FILENAME, O_RDONLY))
- return true; // false aborts the save
-
- int bytes_read = file.read(HAL_eeprom_data, HAL_EEPROM_SIZE);
- if (bytes_read < 0) return false;
- for (; bytes_read < HAL_EEPROM_SIZE; bytes_read++)
- HAL_eeprom_data[bytes_read] = 0xFF;
+ SdFile file, root = card.getroot();
+ int bytes_written = 0;
+ if (file.open(&root, EEPROM_FILENAME, O_CREAT | O_WRITE | O_TRUNC)) {
+ bytes_written = file.write(HAL_eeprom_data, MARLIN_EEPROM_SIZE);
file.close();
- return true;
}
-
- bool PersistentStore::access_finish() {
- if (!card.isMounted()) return false;
-
- SdFile file, root = card.getroot();
- int bytes_written = 0;
- if (file.open(&root, EEPROM_FILENAME, O_CREAT | O_WRITE | O_TRUNC)) {
- bytes_written = file.write(HAL_eeprom_data, HAL_EEPROM_SIZE);
- file.close();
- }
- return (bytes_written == HAL_EEPROM_SIZE);
- }
-
-#else // !SDSUPPORT
-
- #error "Please define SPI_EEPROM (in Configuration.h) or disable EEPROM_SETTINGS."
-
-#endif // !SDSUPPORT
+ return (bytes_written == MARLIN_EEPROM_SIZE);
+}
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
for (size_t i = 0; i < size; i++)
@@ -98,7 +89,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin
return false;
}
-size_t PersistentStore::capacity() { return HAL_EEPROM_SIZE; }
-
#endif // SDCARD_EEPROM_EMULATION
#endif // __STM32F1__
diff --git a/Marlin/src/HAL/STM32F1/eeprom.cpp b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp
similarity index 83%
rename from Marlin/src/HAL/STM32F1/eeprom.cpp
rename to Marlin/src/HAL/STM32F1/eeprom_wired.cpp
index ed5d50cbd..b4699d00d 100644
--- a/Marlin/src/HAL/STM32F1/eeprom.cpp
+++ b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp
@@ -14,19 +14,32 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#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"
+#ifndef MARLIN_EEPROM_SIZE
+ #error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM."
+#endif
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+
+bool PersistentStore::access_finish() { return true; }
+
bool PersistentStore::access_start() {
+ eeprom_init();
#if ENABLED(SPI_EEPROM)
#if SPI_CHAN_EEPROM1 == 1
SET_OUTPUT(BOARD_SPI1_SCK_PIN);
@@ -38,7 +51,6 @@ bool PersistentStore::access_start() {
#endif
return true;
}
-bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
while (size--) {
@@ -56,7 +68,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
crc16(crc, &v, 1);
pos++;
value++;
- };
+ }
return false;
}
@@ -71,7 +83,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
return false;
}
-size_t PersistentStore::capacity() { return E2END + 1; }
-
#endif // USE_WIRED_EEPROM
#endif // __STM32F1__
diff --git a/Marlin/src/HAL/STM32F1/endstop_interrupts.h b/Marlin/src/HAL/STM32F1/endstop_interrupts.h
index 246e29298..bcb07d991 100644
--- a/Marlin/src/HAL/STM32F1/endstop_interrupts.h
+++ b/Marlin/src/HAL/STM32F1/endstop_interrupts.h
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -53,43 +53,22 @@
void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts() {
- #if HAS_X_MAX
- attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE); // assign it
- #endif
- #if HAS_X_MIN
- attachInterrupt(X_MIN_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Y_MAX
- attachInterrupt(Y_MAX_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Y_MIN
- attachInterrupt(Y_MIN_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z_MAX
- attachInterrupt(Z_MAX_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z_MIN
- attachInterrupt(Z_MIN_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z2_MAX
- attachInterrupt(Z2_MAX_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z2_MIN
- attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z3_MAX
- attachInterrupt(Z3_MAX_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z3_MIN
- attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z4_MAX
- attachInterrupt(Z4_MAX_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z4_MIN
- attachInterrupt(Z4_MIN_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z_MIN_PROBE_PIN
- attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
- #endif
+ #define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE)
+ TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN));
+ TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN));
+ TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN));
+ TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN));
+ TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN));
+ TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN));
+ TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN));
+ TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN));
+ TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN));
+ TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN));
+ TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN));
+ TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN));
+ TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN));
+ TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN));
+ TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
+ TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
+ TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
}
diff --git a/Marlin/src/HAL/STM32F1/fastio.h b/Marlin/src/HAL/STM32F1/fastio.h
index 9bf78d425..e0e2e03a1 100644
--- a/Marlin/src/HAL/STM32F1/fastio.h
+++ b/Marlin/src/HAL/STM32F1/fastio.h
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32F1/inc/Conditionals_LCD.h b/Marlin/src/HAL/STM32F1/inc/Conditionals_LCD.h
index 0285c52ee..f52e6fec2 100644
--- a/Marlin/src/HAL/STM32F1/inc/Conditionals_LCD.h
+++ b/Marlin/src/HAL/STM32F1/inc/Conditionals_LCD.h
@@ -16,7 +16,12 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
+
+#if ENABLED(USE_USB_COMPOSITE)
+ //#warning "SD_CHECK_AND_RETRY isn't needed with USE_USB_COMPOSITE."
+ #undef SD_CHECK_AND_RETRY
+#endif
diff --git a/Marlin/src/HAL/STM32F1/inc/Conditionals_adv.h b/Marlin/src/HAL/STM32F1/inc/Conditionals_adv.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/STM32F1/inc/Conditionals_adv.h
+++ b/Marlin/src/HAL/STM32F1/inc/Conditionals_adv.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h b/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h
index 0285c52ee..656fbe1ce 100644
--- a/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h
+++ b/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h
@@ -16,7 +16,19 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
+
+// If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation
+#if USE_FALLBACK_EEPROM
+ #define SDCARD_EEPROM_EMULATION
+#elif EITHER(I2C_EEPROM, SPI_EEPROM)
+ #define USE_SHARED_EEPROM 1
+#endif
+
+// Allow SDSUPPORT to be disabled
+#if DISABLED(SDSUPPORT)
+ #undef SDIO_SUPPORT
+#endif
diff --git a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h
index b8ebc446d..5559b3d4a 100644
--- a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h
+++ b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -29,10 +29,6 @@
#error "EMERGENCY_PARSER is not yet implemented for STM32F1. Disable EMERGENCY_PARSER to continue."
#endif
-#if ENABLED(SDIO_SUPPORT) && DISABLED(SDSUPPORT)
- #error "SDIO_SUPPORT requires SDSUPPORT. Enable SDSUPPORT to continue."
-#endif
-
#if ENABLED(FAST_PWM_FAN)
#error "FAST_PWM_FAN is not yet implemented for this platform."
#endif
@@ -41,3 +37,17 @@
#warning "With TMC2208/9 consider using SoftwareSerialM with HAVE_SW_SERIAL and appropriate SS_TIMER."
#error "Missing SoftwareSerial implementation."
#endif
+
+#if ENABLED(SDCARD_EEPROM_EMULATION) && DISABLED(SDSUPPORT)
+ #undef SDCARD_EEPROM_EMULATION // Avoid additional error noise
+ #if USE_FALLBACK_EEPROM
+ #warning "EEPROM type not specified. Fallback is SDCARD_EEPROM_EMULATION."
+ #endif
+ #error "SDCARD_EEPROM_EMULATION requires SDSUPPORT. Enable SDSUPPORT or choose another EEPROM emulation."
+#endif
+
+#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
+ #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on this platform."
+#elif ENABLED(SERIAL_STATS_DROPPED_RX)
+ #error "SERIAL_STATS_DROPPED_RX is not supported on this platform."
+#endif
diff --git a/Marlin/src/HAL/STM32F1/msc_sd.cpp b/Marlin/src/HAL/STM32F1/msc_sd.cpp
index a086b82bc..ab5530174 100644
--- a/Marlin/src/HAL/STM32F1/msc_sd.cpp
+++ b/Marlin/src/HAL/STM32F1/msc_sd.cpp
@@ -10,7 +10,7 @@
* (at your option) any later version.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#ifdef USE_USB_COMPOSITE
@@ -25,7 +25,7 @@ USBCompositeSerial MarlinCompositeSerial;
#include "../../inc/MarlinConfig.h"
-#ifdef HAS_ONBOARD_SD
+#if SD_CONNECTION_IS(ONBOARD)
#include "onboard_sd.h"
@@ -47,7 +47,7 @@ void MSC_SD_init() {
USBComposite.end();
USBComposite.clear();
// Set api and register mass storage
- #ifdef HAS_ONBOARD_SD
+ #if SD_CONNECTION_IS(ONBOARD)
uint32_t cardSize;
if (disk_initialize(0) == RES_OK) {
if (disk_ioctl(0, GET_SECTOR_COUNT, (void *)(&cardSize)) == RES_OK) {
diff --git a/Marlin/src/HAL/STM32F1/msc_sd.h b/Marlin/src/HAL/STM32F1/msc_sd.h
index 125ba3646..8715888f4 100644
--- a/Marlin/src/HAL/STM32F1/msc_sd.h
+++ b/Marlin/src/HAL/STM32F1/msc_sd.h
@@ -10,7 +10,7 @@
* (at your option) any later version.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32F1/onboard_sd.cpp b/Marlin/src/HAL/STM32F1/onboard_sd.cpp
index 0fd94a919..099e2a068 100644
--- a/Marlin/src/HAL/STM32F1/onboard_sd.cpp
+++ b/Marlin/src/HAL/STM32F1/onboard_sd.cpp
@@ -14,13 +14,13 @@
#include "../../inc/MarlinConfig.h"
-#ifdef HAS_ONBOARD_SD
+#if SD_CONNECTION_IS(ONBOARD)
#include "onboard_sd.h"
#include "SPI.h"
#include "fastio.h"
-#ifdef SHARED_SD_CARD
+#if HAS_SHARED_MEDIA
#ifndef ON_BOARD_SPI_DEVICE
#define ON_BOARD_SPI_DEVICE SPI_DEVICE
#endif
@@ -553,4 +553,4 @@ DRESULT disk_read (
#endif // _DISKIO_IOCTL
-#endif // HAS_ONBOARD_SD
+#endif // SD_CONNECTION_IS(ONBOARD)
diff --git a/Marlin/src/HAL/STM32F1/pinsDebug.h b/Marlin/src/HAL/STM32F1/pinsDebug.h
index 913cb62af..2d63ebd77 100644
--- a/Marlin/src/HAL/STM32F1/pinsDebug.h
+++ b/Marlin/src/HAL/STM32F1/pinsDebug.h
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32F1/sdio.cpp b/Marlin/src/HAL/STM32F1/sdio.cpp
index da6beda85..0e8a74581 100644
--- a/Marlin/src/HAL/STM32F1/sdio.cpp
+++ b/Marlin/src/HAL/STM32F1/sdio.cpp
@@ -17,10 +17,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef ARDUINO_ARCH_STM32F1
#include
@@ -102,7 +101,23 @@ bool SDIO_ReadBlock_DMA(uint32_t blockAddress, uint8_t *data) {
return false;
}
- while (!SDIO_GET_FLAG(SDIO_STA_DATAEND | SDIO_STA_TRX_ERROR_FLAGS)) {}
+ while (!SDIO_GET_FLAG(SDIO_STA_DATAEND | SDIO_STA_TRX_ERROR_FLAGS)) { /* wait */ }
+
+ //If there were SDIO errors, do not wait DMA.
+ if (SDIO->STA & SDIO_STA_TRX_ERROR_FLAGS) {
+ SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS);
+ dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
+ return false;
+ }
+
+ //Wait for DMA transaction to complete
+ while ((DMA2_BASE->ISR & (DMA_ISR_TEIF4|DMA_ISR_TCIF4)) == 0 ) { /* wait */ }
+
+ if (DMA2_BASE->ISR & DMA_ISR_TEIF4) {
+ dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
+ SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS);
+ return false;
+ }
dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
@@ -121,7 +136,7 @@ bool SDIO_ReadBlock_DMA(uint32_t blockAddress, uint8_t *data) {
}
bool SDIO_ReadBlock(uint32_t blockAddress, uint8_t *data) {
- uint32_t retries = 3;
+ uint32_t retries = SDIO_READ_RETRIES;
while (retries--) if (SDIO_ReadBlock_DMA(blockAddress, data)) return true;
return false;
}
@@ -147,7 +162,7 @@ bool SDIO_WriteBlock(uint32_t blockAddress, const uint8_t *data) {
sdio_setup_transfer(SDIO_DATA_TIMEOUT * (F_CPU / 1000U), 512U, SDIO_BLOCKSIZE_512 | SDIO_DCTRL_DMAEN | SDIO_DCTRL_DTEN);
- while (!SDIO_GET_FLAG(SDIO_STA_DATAEND | SDIO_STA_TRX_ERROR_FLAGS)) {}
+ while (!SDIO_GET_FLAG(SDIO_STA_DATAEND | SDIO_STA_TRX_ERROR_FLAGS)) { /* wait */ }
dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
diff --git a/Marlin/src/HAL/STM32F1/sdio.h b/Marlin/src/HAL/STM32F1/sdio.h
index f51ba6d0a..8777299f0 100644
--- a/Marlin/src/HAL/STM32F1/sdio.h
+++ b/Marlin/src/HAL/STM32F1/sdio.h
@@ -16,12 +16,12 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
-#include "../shared/Marduino.h"
+#include "../../inc/MarlinConfig.h" // Allow pins/pins.h to override SDIO clock / retries
#include
#include
@@ -100,7 +100,13 @@
#define SDIO_DATA_TIMEOUT 100U /* Read data transfer timeout */
#define SDIO_WRITE_TIMEOUT 200U /* Write data transfer timeout */
-#define SDIO_CLOCK 18000000 /* 18 MHz */
+#ifndef SDIO_CLOCK
+ #define SDIO_CLOCK 18000000 /* 18 MHz */
+#endif
+
+#ifndef SDIO_READ_RETRIES
+ #define SDIO_READ_RETRIES 3
+#endif
// ------------------------
// Types
diff --git a/Marlin/src/HAL/STM32F1/spi_pins.h b/Marlin/src/HAL/STM32F1/spi_pins.h
index e8e4cbba1..8f2b324f6 100644
--- a/Marlin/src/HAL/STM32F1/spi_pins.h
+++ b/Marlin/src/HAL/STM32F1/spi_pins.h
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32F1/timers.cpp b/Marlin/src/HAL/STM32F1/timers.cpp
index 720bd37ba..8c2df1e21 100644
--- a/Marlin/src/HAL/STM32F1/timers.cpp
+++ b/Marlin/src/HAL/STM32F1/timers.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -27,8 +27,6 @@
#ifdef __STM32F1__
#include "../../inc/MarlinConfig.h"
-#include "HAL.h"
-#include "timers.h"
// ------------------------
// Local defines
@@ -49,7 +47,10 @@
* TODO: Calculate Timer prescale value, so we get the 32bit to adjust
*/
-void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
+
+
+
+void timer_set_interrupt_priority(uint_fast8_t timer_num, uint_fast8_t priority) {
nvic_irq_num irq_num;
switch (timer_num) {
case 1: irq_num = NVIC_TIMER1_CC; break;
@@ -66,9 +67,14 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
* This should never happen. Add a Sanitycheck for timer number.
* Should be a general timer since basic timers have no CC channels.
*/
- break;
+ return;
}
+ nvic_irq_set_priority(irq_num, priority);
+}
+
+
+void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
/**
* Give the Stepper ISR a higher priority (lower number)
* so it automatically preempts the Temperature ISR.
@@ -85,7 +91,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
timer_set_compare(STEP_TIMER_DEV, STEP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (STEPPER_TIMER_RATE) / frequency));
timer_no_ARR_preload_ARPE(STEP_TIMER_DEV); // Need to be sure no preload on ARR register
timer_attach_interrupt(STEP_TIMER_DEV, STEP_TIMER_CHAN, stepTC_Handler);
- nvic_irq_set_priority(irq_num, STEP_TIMER_IRQ_PRIO);
+ timer_set_interrupt_priority(STEP_TIMER_NUM, STEP_TIMER_IRQ_PRIO);
timer_generate_update(STEP_TIMER_DEV);
timer_resume(STEP_TIMER_DEV);
break;
@@ -97,7 +103,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
timer_set_reload(TEMP_TIMER_DEV, 0xFFFF);
timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (F_CPU) / (TEMP_TIMER_PRESCALE) / frequency));
timer_attach_interrupt(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, tempTC_Handler);
- nvic_irq_set_priority(irq_num, TEMP_TIMER_IRQ_PRIO);
+ timer_set_interrupt_priority(TEMP_TIMER_NUM, TEMP_TIMER_IRQ_PRIO);
timer_generate_update(TEMP_TIMER_DEV);
timer_resume(TEMP_TIMER_DEV);
break;
diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h
index e5733cc56..6f360f6bf 100644
--- a/Marlin/src/HAL/STM32F1/timers.h
+++ b/Marlin/src/HAL/STM32F1/timers.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -44,8 +44,12 @@ typedef uint16_t hal_timer_t;
#define HAL_TIMER_RATE uint32_t(F_CPU) // frequency of timers peripherals
-#define STEP_TIMER_CHAN 1 // Channel of the timer to use for compare and interrupts
-#define TEMP_TIMER_CHAN 1 // Channel of the timer to use for compare and interrupts
+#ifndef STEP_TIMER_CHAN
+ #define STEP_TIMER_CHAN 1 // Channel of the timer to use for compare and interrupts
+#endif
+#ifndef TEMP_TIMER_CHAN
+ #define TEMP_TIMER_CHAN 1 // Channel of the timer to use for compare and interrupts
+#endif
/**
* Note: Timers may be used by platforms and libraries
@@ -61,14 +65,20 @@ typedef uint16_t hal_timer_t;
* - Otherwise it uses Timer 8 on boards with STM32_HIGH_DENSITY
* or Timer 4 on other boards.
*/
-#if defined(MCU_STM32F103CB) || defined(MCU_STM32F103C8)
- #define STEP_TIMER_NUM 4 // For C8/CB boards, use timer 4
-#else
- #define STEP_TIMER_NUM 5 // for other boards, five is fine.
+#ifndef STEP_TIMER_NUM
+ #if defined(MCU_STM32F103CB) || defined(MCU_STM32F103C8)
+ #define STEP_TIMER_NUM 4 // For C8/CB boards, use timer 4
+ #else
+ #define STEP_TIMER_NUM 5 // for other boards, five is fine.
+ #endif
+#endif
+#ifndef PULSE_TIMER_NUM
+ #define PULSE_TIMER_NUM STEP_TIMER_NUM
+#endif
+#ifndef TEMP_TIMER_NUM
+ #define TEMP_TIMER_NUM 2 // Timer Index for Temperature
+ //#define TEMP_TIMER_NUM 4 // 2->4, Timer 2 for Stepper Current PWM
#endif
-#define TEMP_TIMER_NUM 2 // index of timer to use for temperature
-//#define TEMP_TIMER_NUM 4 // 2->4, Timer 2 for Stepper Current PWM
-#define PULSE_TIMER_NUM STEP_TIMER_NUM
#if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_E3_DIP, BTT_SKR_MINI_E3_V1_2, MKS_ROBIN_LITE)
// SKR Mini E3 boards use PA8 as FAN_PIN, so TIMER 1 is used for Fan PWM.
@@ -81,8 +91,9 @@ typedef uint16_t hal_timer_t;
#define SERVO0_TIMER_NUM 1 // SERVO0 or BLTOUCH
#endif
-#define STEP_TIMER_IRQ_PRIO 1
-#define TEMP_TIMER_IRQ_PRIO 2
+#define STEP_TIMER_IRQ_PRIO 2
+#define TEMP_TIMER_IRQ_PRIO 3
+#define SERVO0_TIMER_IRQ_PRIO 1
#define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
@@ -111,8 +122,12 @@ timer_dev* get_timer_dev(int number);
// TODO change this
-#define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler()
-#define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler()
+#ifndef HAL_TEMP_TIMER_ISR
+ #define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler()
+#endif
+#ifndef HAL_STEP_TIMER_ISR
+ #define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler()
+#endif
extern "C" void tempTC_Handler();
extern "C" void stepTC_Handler();
@@ -179,4 +194,6 @@ FORCE_INLINE static void timer_no_ARR_preload_ARPE(timer_dev *dev) {
bb_peri_set_bit(&(dev->regs).gen->CR1, TIMER_CR1_ARPE_BIT, 0);
}
+void timer_set_interrupt_priority(uint_fast8_t timer_num, uint_fast8_t priority);
+
#define TIMER_OC_NO_PRELOAD 0 // Need to disable preload also on compare registers.
diff --git a/Marlin/src/HAL/STM32F1/watchdog.cpp b/Marlin/src/HAL/STM32F1/watchdog.cpp
index 9556d1fa6..4123bc3ef 100644
--- a/Marlin/src/HAL/STM32F1/watchdog.cpp
+++ b/Marlin/src/HAL/STM32F1/watchdog.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/STM32F1/watchdog.h b/Marlin/src/HAL/STM32F1/watchdog.h
index 7218b1a72..7185d6977 100644
--- a/Marlin/src/HAL/STM32F1/watchdog.h
+++ b/Marlin/src/HAL/STM32F1/watchdog.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32_F4_F7/HAL.cpp b/Marlin/src/HAL/STM32_F4_F7/HAL.cpp
index 5acda8af4..b4629d2af 100644
--- a/Marlin/src/HAL/STM32_F4_F7/HAL.cpp
+++ b/Marlin/src/HAL/STM32_F4_F7/HAL.cpp
@@ -17,10 +17,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
#include "HAL.h"
diff --git a/Marlin/src/HAL/STM32_F4_F7/HAL.h b/Marlin/src/HAL/STM32_F4_F7/HAL.h
index b5d8ac29c..5601400c5 100644
--- a/Marlin/src/HAL/STM32_F4_F7/HAL.h
+++ b/Marlin/src/HAL/STM32_F4_F7/HAL.h
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -31,7 +31,6 @@
#include "../shared/HAL_SPI.h"
#include "fastio.h"
-#include "timers.h"
#include "watchdog.h"
#include
@@ -51,6 +50,8 @@
#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
@@ -74,6 +75,8 @@
#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
@@ -103,6 +106,8 @@
#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
@@ -206,19 +211,6 @@ static inline int freeMemory() {
#pragma GCC diagnostic pop
-//
-// EEPROM
-//
-
-/**
- * TODO: Write all this EEPROM stuff. Can emulate EEPROM in flash as last resort.
- * Wire library should work for i2c EEPROMs.
- */
-void eeprom_write_byte(uint8_t *pos, unsigned char value);
-uint8_t eeprom_read_byte(uint8_t *pos);
-void eeprom_read_block (void *__dst, const void *__src, size_t __n);
-void eeprom_update_block (const void *__src, void *__dst, size_t __n);
-
//
// ADC
//
@@ -227,8 +219,9 @@ void eeprom_update_block (const void *__src, void *__dst, size_t __n);
inline void HAL_adc_init() {}
-#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
+#define HAL_ADC_VREF 3.3
#define HAL_ADC_RESOLUTION 10
+#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true
diff --git a/Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp b/Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp
index deb14f2cf..6fe81819a 100644
--- a/Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp
+++ b/Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp
@@ -17,9 +17,10 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
+#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
/**
* Software SPI functions originally from Arduino Sd2Card Library
@@ -30,8 +31,6 @@
* Adapted to the Marlin STM32F4/7 HAL
*/
-#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
-
#include "../../inc/MarlinConfig.h"
#include
@@ -121,7 +120,7 @@ uint8_t spiRec() {
*/
void spiRead(uint8_t* buf, uint16_t nbyte) {
SPI.beginTransaction(spiConfig);
- #ifdef STM32GENERIC
+ #ifndef STM32GENERIC
SPI.dmaTransfer(0, const_cast(buf), nbyte);
#else
SPI.transfer((uint8_t*)buf, nbyte);
@@ -153,7 +152,7 @@ void spiSend(uint8_t b) {
void spiSendBlock(uint8_t token, const uint8_t* buf) {
SPI.beginTransaction(spiConfig);
SPI.transfer(token);
- #ifdef STM32GENERIC
+ #ifndef STM32GENERIC
SPI.dmaSend(const_cast(buf), 512);
#else
SPI.transfer((uint8_t*)buf, nullptr, 512);
diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp b/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp
index ffd46dae6..dc41f8913 100644
--- a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp
+++ b/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp
@@ -16,14 +16,12 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#if defined(STM32GENERIC) && defined(STM32F4)
-#include "../HAL.h"
-#include "timers.h"
+#include "../../../inc/MarlinConfig.h"
// ------------------------
// Local defines
diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h b/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h
index c52f5ea21..a4a7ad82c 100644
--- a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h
+++ b/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -34,9 +34,15 @@
#define HAL_TIMER_RATE (HAL_RCC_GetSysClockFreq() / 2) // frequency of timer peripherals
-#define STEP_TIMER_NUM 0 // index of timer to use for stepper
-#define TEMP_TIMER_NUM 1 // index of timer to use for temperature
-#define PULSE_TIMER_NUM STEP_TIMER_NUM
+#ifndef STEP_TIMER_NUM
+ #define STEP_TIMER_NUM 0 // Timer Index for Stepper
+#endif
+#ifndef PULSE_TIMER_NUM
+ #define PULSE_TIMER_NUM STEP_TIMER_NUM
+#endif
+#ifndef TEMP_TIMER_NUM
+ #define TEMP_TIMER_NUM 1 // Timer Index for Temperature
+#endif
#define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
@@ -59,17 +65,19 @@
// TODO change this
#ifdef STM32GENERIC
- extern void TC5_Handler();
- extern void TC7_Handler();
- #define HAL_STEP_TIMER_ISR() void TC5_Handler()
- #define HAL_TEMP_TIMER_ISR() void TC7_Handler()
+ #define TC_TIMER_ARGS
#else
- extern void TC5_Handler(stimer_t *htim);
- extern void TC7_Handler(stimer_t *htim);
- #define HAL_STEP_TIMER_ISR() void TC5_Handler(stimer_t *htim)
- #define HAL_TEMP_TIMER_ISR() void TC7_Handler(stimer_t *htim)
+ #define TC_TIMER_ARGS stimer_t *htim
#endif
+extern void TC5_Handler(TC_TIMER_ARGS);
+extern void TC7_Handler(TC_TIMER_ARGS);
+#ifndef HAL_STEP_TIMER_ISR
+ #define HAL_STEP_TIMER_ISR() void TC5_Handler(TC_TIMER_ARGS)
+#endif
+#ifndef HAL_TEMP_TIMER_ISR
+ #define HAL_TEMP_TIMER_ISR() void TC7_Handler(TC_TIMER_ARGS)
+#endif
// ------------------------
// Types
diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp b/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp
index d90f22e03..f7ded7454 100644
--- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp
+++ b/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp
@@ -16,14 +16,12 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#if defined(STM32GENERIC) && defined(STM32F7)
-#include "../HAL.h"
-#include "timers.h"
+#include "../../../inc/MarlinConfig.h"
// ------------------------
// Local defines
diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h b/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h
index 00428c54f..d2f78259d 100644
--- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h
+++ b/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -34,9 +34,15 @@
#define HAL_TIMER_RATE (HAL_RCC_GetSysClockFreq() / 2) // frequency of timer peripherals
-#define STEP_TIMER_NUM 0 // index of timer to use for stepper
-#define TEMP_TIMER_NUM 1 // index of timer to use for temperature
-#define PULSE_TIMER_NUM STEP_TIMER_NUM
+#ifndef STEP_TIMER_NUM
+ #define STEP_TIMER_NUM 0 // Timer Index for Stepper
+#endif
+#ifndef PULSE_TIMER_NUM
+ #define PULSE_TIMER_NUM STEP_TIMER_NUM
+#endif
+#ifndef TEMP_TIMER_NUM
+ #define TEMP_TIMER_NUM 1 // Timer Index for Temperature
+#endif
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
#define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz
@@ -62,8 +68,12 @@
extern void TC5_Handler();
extern void TC7_Handler();
-#define HAL_STEP_TIMER_ISR() void TC5_Handler()
-#define HAL_TEMP_TIMER_ISR() void TC7_Handler()
+#ifndef HAL_STEP_TIMER_ISR
+ #define HAL_STEP_TIMER_ISR() void TC5_Handler()
+#endif
+#ifndef HAL_TEMP_TIMER_ISR
+ #define HAL_TEMP_TIMER_ISR() void TC7_Handler()
+#endif
// ------------------------
// Types
diff --git a/Marlin/src/HAL/STM32_F4_F7/Servo.cpp b/Marlin/src/HAL/STM32_F4_F7/Servo.cpp
index e7fb15e6b..7185468f5 100644
--- a/Marlin/src/HAL/STM32_F4_F7/Servo.cpp
+++ b/Marlin/src/HAL/STM32_F4_F7/Servo.cpp
@@ -17,10 +17,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
#include "../../inc/MarlinConfig.h"
@@ -44,9 +43,7 @@ void libServo::move(const int value) {
if (attach(0) >= 0) {
write(value);
safe_delay(servo_delay[servoIndex]);
- #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
- detach();
- #endif
+ TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
}
}
diff --git a/Marlin/src/HAL/STM32_F4_F7/Servo.h b/Marlin/src/HAL/STM32_F4_F7/Servo.h
index 076a547bb..e42cc6084 100644
--- a/Marlin/src/HAL/STM32_F4_F7/Servo.h
+++ b/Marlin/src/HAL/STM32_F4_F7/Servo.h
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp
index 3358fa3df..e0726c7cd 100644
--- a/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp
+++ b/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp
@@ -1,6 +1,6 @@
/**
******************************************************************************
- * @file EEPROM/EEPROM_Emulation/src/eeprom.c
+ * @file eeprom_emul.cpp
* @author MCD Application Team
* @version V1.2.6
* @date 04-November-2016
@@ -49,6 +49,10 @@
*/
#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(FLASH_EEPROM_EMULATION)
+
/* Includes ------------------------------------------------------------------*/
#include "eeprom_emul.h"
@@ -61,7 +65,7 @@ uint16_t DataVar = 0;
uint16_t VirtAddVarTab[NB_OF_VAR];
/* Private function prototypes -----------------------------------------------*/
-/* Private functions ---------------------------------------------------------*/
+
static HAL_StatusTypeDef EE_Format();
static uint16_t EE_FindValidPage(uint8_t Operation);
static uint16_t EE_VerifyPageFullWriteVariable(uint16_t VirtAddress, uint16_t Data);
@@ -75,6 +79,9 @@ static uint16_t EE_VerifyPageFullyErased(uint32_t Address);
* @retval - Flash error code: on write Flash error
* - FLASH_COMPLETE: on success
*/
+
+/* Private functions ---------------------------------------------------------*/
+
uint16_t EE_Initialize() {
/* Get Page0 and Page1 status */
uint16_t PageStatus0 = (*(__IO uint16_t*)PAGE0_BASE_ADDRESS),
@@ -329,7 +336,7 @@ uint16_t EE_WriteVariable(uint16_t VirtAddress, uint16_t Data) {
* @brief Erases PAGE and PAGE1 and writes VALID_PAGE header to PAGE
* @param None
* @retval Status of the last operation (Flash write or erase) done during
- * EEPROM formating
+ * EEPROM formatting
*/
static HAL_StatusTypeDef EE_Format() {
FLASH_EraseInitTypeDef pEraseInit;
@@ -518,6 +525,7 @@ static uint16_t EE_PageTransfer(uint16_t VirtAddress, uint16_t Data) {
return HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, NewPageAddress, VALID_PAGE);
}
+#endif // FLASH_EEPROM_EMULATION
#endif // STM32GENERIC && (STM32F4 || STM32F7)
/**
diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h b/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h
index e4094f8e1..84c4c6e3d 100644
--- a/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h
+++ b/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h
@@ -50,7 +50,6 @@
// ------------------------
#include "../../inc/MarlinConfig.h"
-#include "HAL.h"
/* Exported constants --------------------------------------------------------*/
/* EEPROM emulation firmware error codes */
diff --git a/Marlin/src/HAL/STM32_F4_F7/EmulatedEeprom.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp
similarity index 57%
rename from Marlin/src/HAL/STM32_F4_F7/EmulatedEeprom.cpp
rename to Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp
index cc1a1bb01..00b808fd4 100644
--- a/Marlin/src/HAL/STM32_F4_F7/EmulatedEeprom.cpp
+++ b/Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp
@@ -13,33 +13,18 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
-/**
- * Description: Functions for a Flash emulated EEPROM
- * Not platform dependent.
- */
-
-// Include configs and pins to get all EEPROM flags
#include "../../inc/MarlinConfig.h"
#if ENABLED(FLASH_EEPROM_EMULATION)
-// ------------------------
-// Includes
-// ------------------------
-
-#include "HAL.h"
+#include "../shared/eeprom_api.h"
#include "eeprom_emul.h"
-// ------------------------
-// Local defines
-// ------------------------
-
// FLASH_FLAG_PGSERR (Programming Sequence Error) was renamed to
// FLASH_FLAG_ERSERR (Erasing Sequence Error) in STM32F4/7
@@ -49,18 +34,34 @@
//#define FLASH_FLAG_PGSERR FLASH_FLAG_ERSERR
#endif
-// ------------------------
-// Private Variables
-// ------------------------
+void ee_write_byte(uint8_t *pos, unsigned char value) {
+ HAL_FLASH_Unlock();
+ __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
-static bool eeprom_initialized = false;
+ const unsigned eeprom_address = (unsigned)pos;
+ if (EE_WriteVariable(eeprom_address, uint16_t(value)) != EE_OK)
+ for (;;) HAL_Delay(1); // Spin forever until watchdog reset
-// ------------------------
-// Public functions
-// ------------------------
+ HAL_FLASH_Lock();
+}
-void eeprom_init() {
- if (!eeprom_initialized) {
+uint8_t ee_read_byte(uint8_t *pos) {
+ uint16_t data = 0xFF;
+ const unsigned eeprom_address = (unsigned)pos;
+ (void)EE_ReadVariable(eeprom_address, &data); // Data unchanged on error
+ return uint8_t(data);
+}
+
+#ifndef MARLIN_EEPROM_SIZE
+ #error "MARLIN_EEPROM_SIZE is required for Flash-based EEPROM."
+#endif
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+
+bool PersistentStore::access_finish() { return true; }
+
+bool PersistentStore::access_start() {
+ static bool ee_initialized = false;
+ if (!ee_initialized) {
HAL_FLASH_Unlock();
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
@@ -70,46 +71,40 @@ void eeprom_init() {
for (;;) HAL_Delay(1); // Spin forever until watchdog reset
HAL_FLASH_Lock();
- eeprom_initialized = true;
+ ee_initialized = true;
}
+ return true;
}
-void eeprom_write_byte(uint8_t *pos, unsigned char value) {
- eeprom_init();
-
- HAL_FLASH_Unlock();
- __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
-
- uint16_t eeprom_address = unsigned(pos);
- if (EE_WriteVariable(eeprom_address, uint16_t(value)) != EE_OK)
- for (;;) HAL_Delay(1); // Spin forever until watchdog reset
-
- HAL_FLASH_Lock();
-}
-
-uint8_t eeprom_read_byte(uint8_t *pos) {
- eeprom_init();
-
- uint16_t data = 0xFF;
- uint16_t eeprom_address = unsigned(pos);
- (void)EE_ReadVariable(eeprom_address, &data); // Data unchanged on error
-
- return uint8_t(data);
-}
-
-void eeprom_read_block(void *__dst, const void *__src, size_t __n) {
- eeprom_init();
-
- uint16_t data = 0xFF;
- uint16_t eeprom_address = unsigned(__src);
- LOOP_L_N(c, __n) {
- EE_ReadVariable(eeprom_address+c, &data);
- *((uint8_t*)__dst + c) = data;
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ while (size--) {
+ uint8_t * const p = (uint8_t * const)pos;
+ uint8_t v = *value;
+ // EEPROM has only ~100,000 write cycles,
+ // so only write bytes that have changed!
+ if (v != ee_read_byte(p)) {
+ ee_write_byte(p, v);
+ if (ee_read_byte(p) != v) {
+ SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
+ return true;
+ }
+ }
+ crc16(crc, &v, 1);
+ pos++;
+ value++;
}
+ return false;
}
-void eeprom_update_block(const void *__src, void *__dst, size_t __n) {
-
+bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
+ do {
+ uint8_t c = ee_read_byte((uint8_t*)pos);
+ if (writing) *value = c;
+ crc16(crc, &c, 1);
+ pos++;
+ value++;
+ } while (--size);
+ return false;
}
#endif // FLASH_EEPROM_EMULATION
diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp
similarity index 77%
rename from Marlin/src/HAL/STM32_F4_F7/eeprom.cpp
rename to Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp
index b957aae6a..c0d82dbd0 100644
--- a/Marlin/src/HAL/STM32_F4_F7/eeprom.cpp
+++ b/Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp
@@ -17,19 +17,29 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
-#include "../../inc/MarlinConfigPre.h"
+#include "../../inc/MarlinConfig.h"
-#if ENABLED(EEPROM_SETTINGS)
+#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"
-bool PersistentStore::access_start() { return true; }
+#ifndef MARLIN_EEPROM_SIZE
+ #error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM."
+#endif
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+
+bool PersistentStore::access_start() { eeprom_init(); return true; }
bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
@@ -48,7 +58,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
crc16(crc, &v, 1);
pos++;
value++;
- };
+ }
return false;
}
@@ -63,7 +73,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
return false;
}
-size_t PersistentStore::capacity() { return E2END + 1; }
-
-#endif // EEPROM_SETTINGS
+#endif // USE_WIRED_EEPROM
#endif // STM32GENERIC && (STM32F4 || STM32F7)
diff --git a/Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h b/Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h
index 0b97c3c77..fdff8cc64 100644
--- a/Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h
+++ b/Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -28,43 +28,22 @@
void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts() {
- #if HAS_X_MAX
- attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_X_MIN
- attachInterrupt(X_MIN_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Y_MAX
- attachInterrupt(Y_MAX_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Y_MIN
- attachInterrupt(Y_MIN_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z_MAX
- attachInterrupt(Z_MAX_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z_MIN
- attachInterrupt(Z_MIN_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z2_MAX
- attachInterrupt(Z2_MAX_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z2_MIN
- attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z3_MAX
- attachInterrupt(Z3_MAX_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z3_MIN
- attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z4_MAX
- attachInterrupt(Z4_MAX_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z4_MIN
- attachInterrupt(Z4_MIN_PIN, endstop_ISR, CHANGE);
- #endif
- #if HAS_Z_MIN_PROBE_PIN
- attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
- #endif
+ #define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE)
+ TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN));
+ TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN));
+ TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN));
+ TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN));
+ TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN));
+ TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN));
+ TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN));
+ TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN));
+ TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN));
+ TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN));
+ TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN));
+ TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN));
+ TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN));
+ TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN));
+ TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
+ TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
+ TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
}
diff --git a/Marlin/src/HAL/STM32_F4_F7/fastio.h b/Marlin/src/HAL/STM32_F4_F7/fastio.h
index ee64ca833..f42be5835 100644
--- a/Marlin/src/HAL/STM32_F4_F7/fastio.h
+++ b/Marlin/src/HAL/STM32_F4_F7/fastio.h
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_LCD.h b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_LCD.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_LCD.h
+++ b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_LCD.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_adv.h b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_adv.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_adv.h
+++ b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_adv.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h
index d21624955..b5d808e21 100644
--- a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h
+++ b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32_F4_F7/inc/SanityCheck.h b/Marlin/src/HAL/STM32_F4_F7/inc/SanityCheck.h
index e04258fa0..53b15ba19 100644
--- a/Marlin/src/HAL/STM32_F4_F7/inc/SanityCheck.h
+++ b/Marlin/src/HAL/STM32_F4_F7/inc/SanityCheck.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32_F4_F7/pinsDebug.h b/Marlin/src/HAL/STM32_F4_F7/pinsDebug.h
index 208a3524f..973abb1b0 100644
--- a/Marlin/src/HAL/STM32_F4_F7/pinsDebug.h
+++ b/Marlin/src/HAL/STM32_F4_F7/pinsDebug.h
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32_F4_F7/spi_pins.h b/Marlin/src/HAL/STM32_F4_F7/spi_pins.h
index f120e7178..75a6a2b25 100644
--- a/Marlin/src/HAL/STM32_F4_F7/spi_pins.h
+++ b/Marlin/src/HAL/STM32_F4_F7/spi_pins.h
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32_F4_F7/timers.h b/Marlin/src/HAL/STM32_F4_F7/timers.h
index 632c05a5a..4e8c81783 100644
--- a/Marlin/src/HAL/STM32_F4_F7/timers.h
+++ b/Marlin/src/HAL/STM32_F4_F7/timers.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/STM32_F4_F7/watchdog.cpp b/Marlin/src/HAL/STM32_F4_F7/watchdog.cpp
index 347edcd49..cb12ec7aa 100644
--- a/Marlin/src/HAL/STM32_F4_F7/watchdog.cpp
+++ b/Marlin/src/HAL/STM32_F4_F7/watchdog.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
#include "../../inc/MarlinConfig.h"
diff --git a/Marlin/src/HAL/STM32_F4_F7/watchdog.h b/Marlin/src/HAL/STM32_F4_F7/watchdog.h
index ece6ef016..3dbc2d08c 100644
--- a/Marlin/src/HAL/STM32_F4_F7/watchdog.h
+++ b/Marlin/src/HAL/STM32_F4_F7/watchdog.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.cpp b/Marlin/src/HAL/TEENSY31_32/HAL.cpp
index f226a4a90..d276a4c88 100644
--- a/Marlin/src/HAL/TEENSY31_32/HAL.cpp
+++ b/Marlin/src/HAL/TEENSY31_32/HAL.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h
index 15e9ab71b..890930f7f 100644
--- a/Marlin/src/HAL/TEENSY31_32/HAL.h
+++ b/Marlin/src/HAL/TEENSY31_32/HAL.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -34,7 +34,6 @@
#include "fastio.h"
#include "watchdog.h"
-#include "timers.h"
#include
@@ -108,8 +107,9 @@ extern "C" {
void HAL_adc_init();
-#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
+#define HAL_ADC_VREF 3.3
#define HAL_ADC_RESOLUTION 10
+#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_get_result()
#define HAL_ADC_READY() true
diff --git a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp
index 83d4d00bf..cdb3f4701 100644
--- a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp
+++ b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#ifdef __MK20DX256__
diff --git a/Marlin/src/HAL/TEENSY31_32/Servo.cpp b/Marlin/src/HAL/TEENSY31_32/Servo.cpp
index 2b01d3d87..544892cb7 100644
--- a/Marlin/src/HAL/TEENSY31_32/Servo.cpp
+++ b/Marlin/src/HAL/TEENSY31_32/Servo.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#ifdef __MK20DX256__
@@ -46,9 +46,7 @@ void libServo::move(const int value) {
if (attach(0) >= 0) {
write(value);
safe_delay(servo_delay[servoIndex]);
- #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
- detach();
- #endif
+ TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
}
}
diff --git a/Marlin/src/HAL/TEENSY31_32/Servo.h b/Marlin/src/HAL/TEENSY31_32/Servo.h
index 9243291e4..82b601d95 100644
--- a/Marlin/src/HAL/TEENSY31_32/Servo.h
+++ b/Marlin/src/HAL/TEENSY31_32/Servo.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/TEENSY31_32/eeprom_impl.cpp b/Marlin/src/HAL/TEENSY31_32/eeprom.cpp
similarity index 78%
rename from Marlin/src/HAL/TEENSY31_32/eeprom_impl.cpp
rename to Marlin/src/HAL/TEENSY31_32/eeprom.cpp
index 96499d4f1..f66313225 100644
--- a/Marlin/src/HAL/TEENSY31_32/eeprom_impl.cpp
+++ b/Marlin/src/HAL/TEENSY31_32/eeprom.cpp
@@ -13,18 +13,29 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#ifdef __MK20DX256__
#include "../../inc/MarlinConfig.h"
-#if ENABLED(EEPROM_SETTINGS)
+#if USE_WIRED_EEPROM
+
+/**
+ * PersistentStore for Arduino-style EEPROM interface
+ * with implementations supplied by the framework.
+ */
#include "../shared/eeprom_api.h"
+#include
-bool PersistentStore::access_start() { return true; }
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE size_t(E2END + 1)
+#endif
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+
+bool PersistentStore::access_start() { return true; }
bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
@@ -43,7 +54,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
crc16(crc, &v, 1);
pos++;
value++;
- };
+ }
return false;
}
@@ -58,5 +69,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
return false;
}
-#endif // EEPROM_SETTINGS
+#endif // USE_WIRED_EEPROM
#endif // __MK20DX256__
diff --git a/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h b/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h
index 21fea5bd0..999ada512 100644
--- a/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h
+++ b/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -47,31 +47,21 @@ void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
- #if HAS_X_MAX
- _ATTACH(X_MAX_PIN);
- #endif
- #if HAS_X_MIN
- _ATTACH(X_MIN_PIN);
- #endif
- #if HAS_Y_MAX
- _ATTACH(Y_MAX_PIN);
- #endif
- #if HAS_Y_MIN
- _ATTACH(Y_MIN_PIN);
- #endif
- #if HAS_Z_MAX
- _ATTACH(Z_MAX_PIN);
- #endif
- #if HAS_Z_MIN
- _ATTACH(Z_MIN_PIN);
- #endif
- #if HAS_Z2_MAX
- _ATTACH(Z2_MAX_PIN);
- #endif
- #if HAS_Z2_MIN
- _ATTACH(Z2_MIN_PIN);
- #endif
- #if HAS_Z_MIN_PROBE_PIN
- _ATTACH(Z_MIN_PROBE_PIN);
- #endif
+ TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN));
+ TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN));
+ TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN));
+ TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN));
+ TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN));
+ TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN));
+ TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN));
+ TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN));
+ TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN));
+ TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN));
+ TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN));
+ TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN));
+ TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN));
+ TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN));
+ TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
+ TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
+ TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
}
diff --git a/Marlin/src/HAL/TEENSY31_32/fastio.h b/Marlin/src/HAL/TEENSY31_32/fastio.h
index 5bfb8d3a0..9a299de9c 100644
--- a/Marlin/src/HAL/TEENSY31_32/fastio.h
+++ b/Marlin/src/HAL/TEENSY31_32/fastio.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_LCD.h b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_LCD.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_LCD.h
+++ b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_LCD.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_adv.h b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_adv.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_adv.h
+++ b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_adv.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_post.h b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_post.h
index 11603c9ef..998f1dcc0 100644
--- a/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_post.h
+++ b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_post.h
@@ -16,12 +16,11 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
-// If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation
-#if ENABLED(EEPROM_SETTINGS) && NONE(USE_WIRED_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION)
- #define SDCARD_EEPROM_EMULATION
+#if USE_FALLBACK_EEPROM
+ #define USE_WIRED_EEPROM 1
#endif
diff --git a/Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h b/Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h
index 926886859..0b731a61d 100644
--- a/Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h
+++ b/Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/TEENSY31_32/spi_pins.h b/Marlin/src/HAL/TEENSY31_32/spi_pins.h
index 79230f3d4..5754fbfee 100644
--- a/Marlin/src/HAL/TEENSY31_32/spi_pins.h
+++ b/Marlin/src/HAL/TEENSY31_32/spi_pins.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/TEENSY31_32/timers.cpp b/Marlin/src/HAL/TEENSY31_32/timers.cpp
index 92641742f..bf756af8a 100644
--- a/Marlin/src/HAL/TEENSY31_32/timers.cpp
+++ b/Marlin/src/HAL/TEENSY31_32/timers.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -26,8 +26,7 @@
#ifdef __MK20DX256__
-#include "HAL.h"
-#include "timers.h"
+#include "../../inc/MarlinConfig.h"
/** \brief Instruction Synchronization Barrier
Instruction Synchronization Barrier flushes the pipeline in the processor,
diff --git a/Marlin/src/HAL/TEENSY31_32/timers.h b/Marlin/src/HAL/TEENSY31_32/timers.h
index 00f9f0740..4f004ef75 100644
--- a/Marlin/src/HAL/TEENSY31_32/timers.h
+++ b/Marlin/src/HAL/TEENSY31_32/timers.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -47,9 +47,15 @@ typedef uint32_t hal_timer_t;
#define HAL_TIMER_RATE (FTM0_TIMER_RATE)
-#define STEP_TIMER_NUM 0
-#define TEMP_TIMER_NUM 1
-#define PULSE_TIMER_NUM STEP_TIMER_NUM
+#ifndef STEP_TIMER_NUM
+ #define STEP_TIMER_NUM 0 // Timer Index for Stepper
+#endif
+#ifndef PULSE_TIMER_NUM
+ #define PULSE_TIMER_NUM STEP_TIMER_NUM
+#endif
+#ifndef TEMP_TIMER_NUM
+ #define TEMP_TIMER_NUM 1 // Timer Index for Temperature
+#endif
#define TEMP_TIMER_FREQUENCY 1000
@@ -68,8 +74,12 @@ typedef uint32_t hal_timer_t;
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
-#define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler()
-#define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler()
+#ifndef HAL_STEP_TIMER_ISR
+ #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler()
+#endif
+#ifndef HAL_TEMP_TIMER_ISR
+ #define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler()
+#endif
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
diff --git a/Marlin/src/HAL/TEENSY31_32/watchdog.cpp b/Marlin/src/HAL/TEENSY31_32/watchdog.cpp
index 618294591..9f7b70d9f 100644
--- a/Marlin/src/HAL/TEENSY31_32/watchdog.cpp
+++ b/Marlin/src/HAL/TEENSY31_32/watchdog.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#ifdef __MK20DX256__
#include "../../inc/MarlinConfig.h"
diff --git a/Marlin/src/HAL/TEENSY31_32/watchdog.h b/Marlin/src/HAL/TEENSY31_32/watchdog.h
index cb881f859..b8b46a403 100644
--- a/Marlin/src/HAL/TEENSY31_32/watchdog.h
+++ b/Marlin/src/HAL/TEENSY31_32/watchdog.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.cpp b/Marlin/src/HAL/TEENSY35_36/HAL.cpp
index 86ba40870..bcbee1d4c 100644
--- a/Marlin/src/HAL/TEENSY35_36/HAL.cpp
+++ b/Marlin/src/HAL/TEENSY35_36/HAL.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h
index 7e5be1081..5442ae2d3 100644
--- a/Marlin/src/HAL/TEENSY35_36/HAL.h
+++ b/Marlin/src/HAL/TEENSY35_36/HAL.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -34,8 +34,6 @@
#include "fastio.h"
#include "watchdog.h"
-#include "timers.h"
-
#include
#include
@@ -114,8 +112,9 @@ extern "C" {
void HAL_adc_init();
-#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
+#define HAL_ADC_VREF 3.3
#define HAL_ADC_RESOLUTION 10
+#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_get_result()
#define HAL_ADC_READY() true
diff --git a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp
index b35533aa9..0b1ae4afa 100644
--- a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp
+++ b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
diff --git a/Marlin/src/HAL/TEENSY35_36/Servo.cpp b/Marlin/src/HAL/TEENSY35_36/Servo.cpp
index f2fd5fe7f..d1390187a 100644
--- a/Marlin/src/HAL/TEENSY35_36/Servo.cpp
+++ b/Marlin/src/HAL/TEENSY35_36/Servo.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
@@ -46,9 +46,7 @@ void libServo::move(const int value) {
if (attach(0) >= 0) {
write(value);
safe_delay(servo_delay[servoIndex]);
- #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
- detach();
- #endif
+ TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
}
}
diff --git a/Marlin/src/HAL/TEENSY35_36/Servo.h b/Marlin/src/HAL/TEENSY35_36/Servo.h
index 4962105d7..ae904f0e2 100644
--- a/Marlin/src/HAL/TEENSY35_36/Servo.h
+++ b/Marlin/src/HAL/TEENSY35_36/Servo.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp
index c66a45e2a..d2d7324cd 100644
--- a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp
+++ b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp
@@ -17,20 +17,29 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
#include "../../inc/MarlinConfig.h"
-#if ENABLED(EEPROM_SETTINGS)
+#if USE_WIRED_EEPROM
+
+/**
+ * PersistentStore for Arduino-style EEPROM interface
+ * with implementations supplied by the framework.
+ */
#include "../shared/eeprom_api.h"
#include
-bool PersistentStore::access_start() { return true; }
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE size_t(E2END + 1)
+#endif
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+
+bool PersistentStore::access_start() { return true; }
bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
@@ -49,7 +58,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
crc16(crc, &v, 1);
pos++;
value++;
- };
+ }
return false;
}
@@ -64,7 +73,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
return false;
}
-size_t PersistentStore::capacity() { return E2END + 1; }
-
-#endif // EEPROM_SETTINGS
+#endif // USE_WIRED_EEPROM
#endif // __MK64FX512__ || __MK66FX1M0__
diff --git a/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h b/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h
index eaaf297ea..92e22efc0 100644
--- a/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h
+++ b/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -46,43 +46,21 @@ void endstop_ISR() { endstops.update(); }
*/
void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
- #if HAS_X_MAX
- _ATTACH(X_MAX_PIN);
- #endif
- #if HAS_X_MIN
- _ATTACH(X_MIN_PIN);
- #endif
- #if HAS_Y_MAX
- _ATTACH(Y_MAX_PIN);
- #endif
- #if HAS_Y_MIN
- _ATTACH(Y_MIN_PIN);
- #endif
- #if HAS_Z_MAX
- _ATTACH(Z_MAX_PIN);
- #endif
- #if HAS_Z_MIN
- _ATTACH(Z_MIN_PIN);
- #endif
- #if HAS_Z2_MAX
- _ATTACH(Z2_MAX_PIN);
- #endif
- #if HAS_Z2_MIN
- _ATTACH(Z2_MIN_PIN);
- #endif
- #if HAS_Z3_MAX
- _ATTACH(Z3_MAX_PIN);
- #endif
- #if HAS_Z3_MIN
- _ATTACH(Z3_MIN_PIN);
- #endif
- #if HAS_Z4_MAX
- _ATTACH(Z4_MAX_PIN);
- #endif
- #if HAS_Z4_MIN
- _ATTACH(Z4_MIN_PIN);
- #endif
- #if HAS_Z_MIN_PROBE_PIN
- _ATTACH(Z_MIN_PROBE_PIN);
- #endif
+ TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN));
+ TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN));
+ TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN));
+ TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN));
+ TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN));
+ TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN));
+ TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN));
+ TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN));
+ TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN));
+ TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN));
+ TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN));
+ TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN));
+ TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN));
+ TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN));
+ TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
+ TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
+ TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
}
diff --git a/Marlin/src/HAL/TEENSY35_36/fastio.h b/Marlin/src/HAL/TEENSY35_36/fastio.h
index 5bfb8d3a0..9a299de9c 100644
--- a/Marlin/src/HAL/TEENSY35_36/fastio.h
+++ b/Marlin/src/HAL/TEENSY35_36/fastio.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_LCD.h b/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_LCD.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_LCD.h
+++ b/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_LCD.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_adv.h b/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_adv.h
index 0285c52ee..5f1c4b160 100644
--- a/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_adv.h
+++ b/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_adv.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_post.h b/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_post.h
index 0285c52ee..998f1dcc0 100644
--- a/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_post.h
+++ b/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_post.h
@@ -16,7 +16,11 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
+
+#if USE_FALLBACK_EEPROM
+ #define USE_WIRED_EEPROM 1
+#endif
diff --git a/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h b/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h
index f42bd63b1..36b801808 100644
--- a/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h
+++ b/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/TEENSY35_36/pinsDebug.h b/Marlin/src/HAL/TEENSY35_36/pinsDebug.h
index 61a54f15e..e57c73c59 100644
--- a/Marlin/src/HAL/TEENSY35_36/pinsDebug.h
+++ b/Marlin/src/HAL/TEENSY35_36/pinsDebug.h
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/TEENSY35_36/spi_pins.h b/Marlin/src/HAL/TEENSY35_36/spi_pins.h
index b29a9346a..276d4f456 100644
--- a/Marlin/src/HAL/TEENSY35_36/spi_pins.h
+++ b/Marlin/src/HAL/TEENSY35_36/spi_pins.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/TEENSY35_36/timers.cpp b/Marlin/src/HAL/TEENSY35_36/timers.cpp
index 81e23e4d1..5725e83a8 100644
--- a/Marlin/src/HAL/TEENSY35_36/timers.cpp
+++ b/Marlin/src/HAL/TEENSY35_36/timers.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -27,8 +27,7 @@
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
-#include "HAL.h"
-#include "timers.h"
+#include "../../inc/MarlinConfig.h"
/** \brief Instruction Synchronization Barrier
Instruction Synchronization Barrier flushes the pipeline in the processor,
diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h
index 6dc26a966..68060d0e1 100644
--- a/Marlin/src/HAL/TEENSY35_36/timers.h
+++ b/Marlin/src/HAL/TEENSY35_36/timers.h
@@ -15,7 +15,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*/
#pragma once
@@ -46,9 +46,15 @@ typedef uint32_t hal_timer_t;
#define HAL_TIMER_RATE (FTM0_TIMER_RATE)
-#define STEP_TIMER_NUM 0
-#define TEMP_TIMER_NUM 1
-#define PULSE_TIMER_NUM STEP_TIMER_NUM
+#ifndef STEP_TIMER_NUM
+ #define STEP_TIMER_NUM 0 // Timer Index for Stepper
+#endif
+#ifndef PULSE_TIMER_NUM
+ #define PULSE_TIMER_NUM STEP_TIMER_NUM
+#endif
+#ifndef TEMP_TIMER_NUM
+ #define TEMP_TIMER_NUM 1 // Timer Index for Temperature
+#endif
#define TEMP_TIMER_FREQUENCY 1000
@@ -67,8 +73,12 @@ typedef uint32_t hal_timer_t;
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
-#define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler()
-#define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler()
+#ifndef HAL_STEP_TIMER_ISR
+ #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler()
+#endif
+#ifndef HAL_TEMP_TIMER_ISR
+ #define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler()
+#endif
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
diff --git a/Marlin/src/HAL/TEENSY35_36/watchdog.cpp b/Marlin/src/HAL/TEENSY35_36/watchdog.cpp
index 69afa04a5..e735ee792 100644
--- a/Marlin/src/HAL/TEENSY35_36/watchdog.cpp
+++ b/Marlin/src/HAL/TEENSY35_36/watchdog.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
#include "../../inc/MarlinConfig.h"
diff --git a/Marlin/src/HAL/TEENSY35_36/watchdog.h b/Marlin/src/HAL/TEENSY35_36/watchdog.h
index ec3f18f09..981b1f0bd 100644
--- a/Marlin/src/HAL/TEENSY35_36/watchdog.h
+++ b/Marlin/src/HAL/TEENSY35_36/watchdog.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/platforms.h b/Marlin/src/HAL/platforms.h
index cc462f37c..d4cec6426 100644
--- a/Marlin/src/HAL/platforms.h
+++ b/Marlin/src/HAL/platforms.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/shared/Delay.h b/Marlin/src/HAL/shared/Delay.h
index 5cb68b150..d98e96084 100644
--- a/Marlin/src/HAL/shared/Delay.h
+++ b/Marlin/src/HAL/shared/Delay.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -36,7 +36,7 @@
#if __CORTEX_M == 7
// Cortex-M3 through M7 can use the cycle counter of the DWT unit
- // http://www.anthonyvh.com/2017/05/18/cortex_m-cycle_counter/
+ // https://www.anthonyvh.com/2017/05/18/cortex_m-cycle_counter/
FORCE_INLINE static void enableCycleCounter() {
CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
diff --git a/Marlin/src/HAL/shared/HAL_SPI.h b/Marlin/src/HAL/shared/HAL_SPI.h
index 0410d70c9..59af55480 100644
--- a/Marlin/src/HAL/shared/HAL_SPI.h
+++ b/Marlin/src/HAL/shared/HAL_SPI.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/shared/HAL_ST7920.h b/Marlin/src/HAL/shared/HAL_ST7920.h
index 69c1d741a..05e8a1f2c 100644
--- a/Marlin/src/HAL/shared/HAL_ST7920.h
+++ b/Marlin/src/HAL/shared/HAL_ST7920.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -27,7 +27,7 @@
* (bypassing U8G), it will allow the LIGHTWEIGHT_UI to operate.
*/
-#if HAS_GRAPHICAL_LCD && ENABLED(LIGHTWEIGHT_UI)
+#if BOTH(HAS_GRAPHICAL_LCD, LIGHTWEIGHT_UI)
void ST7920_cs();
void ST7920_ncs();
void ST7920_set_cmd();
diff --git a/Marlin/src/HAL/shared/HAL_spi_L6470.cpp b/Marlin/src/HAL/shared/HAL_spi_L6470.cpp
index 46e7b71f8..bd85dbe7b 100644
--- a/Marlin/src/HAL/shared/HAL_spi_L6470.cpp
+++ b/Marlin/src/HAL/shared/HAL_spi_L6470.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/HAL/shared/Marduino.h b/Marlin/src/HAL/shared/Marduino.h
index c022fc72e..3003f3cc2 100644
--- a/Marlin/src/HAL/shared/Marduino.h
+++ b/Marlin/src/HAL/shared/Marduino.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/shared/backtrace/backtrace.cpp b/Marlin/src/HAL/shared/backtrace/backtrace.cpp
index 7264969c7..6cf5e055e 100644
--- a/Marlin/src/HAL/shared/backtrace/backtrace.cpp
+++ b/Marlin/src/HAL/shared/backtrace/backtrace.cpp
@@ -16,10 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-
#if defined(__arm__) || defined(__thumb__)
#include "backtrace.h"
diff --git a/Marlin/src/HAL/shared/backtrace/backtrace.h b/Marlin/src/HAL/shared/backtrace/backtrace.h
index 636eb09a7..fccadedaa 100644
--- a/Marlin/src/HAL/shared/backtrace/backtrace.h
+++ b/Marlin/src/HAL/shared/backtrace/backtrace.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/shared/backtrace/unwarm_thumb.cpp b/Marlin/src/HAL/shared/backtrace/unwarm_thumb.cpp
index d5449f863..26ca8b260 100644
--- a/Marlin/src/HAL/shared/backtrace/unwarm_thumb.cpp
+++ b/Marlin/src/HAL/shared/backtrace/unwarm_thumb.cpp
@@ -807,7 +807,7 @@ UnwResult UnwStartThumb(UnwState * const state) {
case 2: /* MOV */
UnwPrintd5("MOV r%d, r%d\t; r%d %s", rhd, rhs, rhd, M_Origin2Str(state->regData[rhs].o));
state->regData[rhd].v = state->regData[rhs].v;
- state->regData[rhd].o = state->regData[rhd].o;
+ state->regData[rhd].o = state->regData[rhs].o;
break;
case 3: /* BX */
diff --git a/Marlin/src/HAL/shared/eeprom_api.cpp b/Marlin/src/HAL/shared/eeprom_api.cpp
index d8839e3d9..47cfa5a2d 100644
--- a/Marlin/src/HAL/shared/eeprom_api.cpp
+++ b/Marlin/src/HAL/shared/eeprom_api.cpp
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#include "../../inc/MarlinConfigPre.h"
diff --git a/Marlin/src/HAL/shared/eeprom_api.h b/Marlin/src/HAL/shared/eeprom_api.h
index d7bee8a5f..6445f7a4a 100644
--- a/Marlin/src/HAL/shared/eeprom_api.h
+++ b/Marlin/src/HAL/shared/eeprom_api.h
@@ -17,7 +17,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -29,20 +29,38 @@
class PersistentStore {
public:
- static bool access_start();
- static bool access_finish();
- static bool write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc);
- static bool read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing=true);
+
+ // Total available persistent storage space (in bytes)
static size_t capacity();
+ // Prepare to read or write
+ static bool access_start();
+
+ // Housecleaning after read or write
+ static bool access_finish();
+
+ // Write one or more bytes of data and update the CRC
+ // Return 'true' on write error
+ static bool write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc);
+
+ // Read one or more bytes of data and update the CRC
+ // Return 'true' on read error
+ static bool read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing=true);
+
+ // Write one or more bytes of data
+ // Return 'true' on write error
static inline bool write_data(const int pos, const uint8_t* value, const size_t size=sizeof(uint8_t)) {
int data_pos = pos;
uint16_t crc = 0;
return write_data(data_pos, value, size, &crc);
}
+ // Write a single byte of data
+ // Return 'true' on write error
static inline bool write_data(const int pos, const uint8_t value) { return write_data(pos, &value); }
+ // Read one or more bytes of data
+ // Return 'true' on read error
static inline bool read_data(const int pos, uint8_t* value, const size_t size=1) {
int data_pos = pos;
uint16_t crc = 0;
diff --git a/Marlin/src/HAL/shared/eeprom_i2c.cpp b/Marlin/src/HAL/shared/eeprom_i2c.cpp
deleted file mode 100644
index 3eb72194a..000000000
--- a/Marlin/src/HAL/shared/eeprom_i2c.cpp
+++ /dev/null
@@ -1,123 +0,0 @@
-/**
- * Marlin 3D Printer Firmware
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
- *
- * Based on Sprinter and grbl.
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
- *
- * This program is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * This program is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
- *
- */
-
-/**
- * Description: functions for I2C connected external EEPROM.
- * Not platform dependent.
- *
- * TODO: Some platform Arduino libraries define these functions
- * so Marlin needs to add a glue layer to prevent the conflict.
- */
-
-#include "../../inc/MarlinConfig.h"
-
-#if ENABLED(I2C_EEPROM)
-
-#include "../HAL.h"
-#include
-
-// ------------------------
-// Private Variables
-// ------------------------
-
-static uint8_t eeprom_device_address = 0x50;
-
-// ------------------------
-// Public functions
-// ------------------------
-
-static void eeprom_init() {
- Wire.begin();
-}
-
-void eeprom_write_byte(uint8_t *pos, unsigned char value) {
- unsigned eeprom_address = (unsigned) pos;
-
- eeprom_init();
-
- Wire.beginTransmission(I2C_ADDRESS(eeprom_device_address));
- Wire.write((int)(eeprom_address >> 8)); // MSB
- Wire.write((int)(eeprom_address & 0xFF)); // LSB
- Wire.write(value);
- Wire.endTransmission();
-
- // wait for write cycle to complete
- // this could be done more efficiently with "acknowledge polling"
- delay(5);
-}
-
-// WARNING: address is a page address, 6-bit end will wrap around
-// also, data can be maximum of about 30 bytes, because the Wire library has a buffer of 32 bytes
-void eeprom_update_block(const void *pos, void* eeprom_address, size_t n) {
- eeprom_init();
-
- Wire.beginTransmission(I2C_ADDRESS(eeprom_device_address));
- Wire.write((int)((unsigned)eeprom_address >> 8)); // MSB
- Wire.write((int)((unsigned)eeprom_address & 0xFF)); // LSB
- Wire.endTransmission();
-
- uint8_t *ptr = (uint8_t*)pos;
- uint8_t flag = 0;
- Wire.requestFrom(eeprom_device_address, (byte)n);
- for (byte c = 0; c < n && Wire.available(); c++)
- flag |= Wire.read() ^ ptr[c];
-
- if (flag) {
- Wire.beginTransmission(I2C_ADDRESS(eeprom_device_address));
- Wire.write((int)((unsigned)eeprom_address >> 8)); // MSB
- Wire.write((int)((unsigned)eeprom_address & 0xFF)); // LSB
- Wire.write((uint8_t*)pos, n);
- Wire.endTransmission();
-
- // wait for write cycle to complete
- // this could be done more efficiently with "acknowledge polling"
- delay(5);
- }
-}
-
-uint8_t eeprom_read_byte(uint8_t *pos) {
- unsigned eeprom_address = (unsigned)pos;
-
- eeprom_init();
-
- Wire.beginTransmission(I2C_ADDRESS(eeprom_device_address));
- Wire.write((int)(eeprom_address >> 8)); // MSB
- Wire.write((int)(eeprom_address & 0xFF)); // LSB
- Wire.endTransmission();
- Wire.requestFrom(eeprom_device_address, (byte)1);
- return Wire.available() ? Wire.read() : 0xFF;
-}
-
-// Don't read more than 30..32 bytes at a time!
-void eeprom_read_block(void* pos, const void* eeprom_address, size_t n) {
- eeprom_init();
-
- Wire.beginTransmission(I2C_ADDRESS(eeprom_device_address));
- Wire.write((int)((unsigned)eeprom_address >> 8)); // MSB
- Wire.write((int)((unsigned)eeprom_address & 0xFF)); // LSB
- Wire.endTransmission();
- Wire.requestFrom(eeprom_device_address, (byte)n);
- for (byte c = 0; c < n; c++ )
- if (Wire.available()) *((uint8_t*)pos + c) = Wire.read();
-}
-
-#endif // I2C_EEPROM
diff --git a/Marlin/src/HAL/shared/eeprom_if.h b/Marlin/src/HAL/shared/eeprom_if.h
new file mode 100644
index 000000000..e44da801d
--- /dev/null
+++ b/Marlin/src/HAL/shared/eeprom_if.h
@@ -0,0 +1,29 @@
+/**
+ * Marlin 3D Printer Firmware
+ *
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
+ * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#pragma once
+
+//
+// EEPROM
+//
+void eeprom_init();
+void eeprom_write_byte(uint8_t *pos, unsigned char value);
+uint8_t eeprom_read_byte(uint8_t *pos);
diff --git a/Marlin/src/HAL/shared/eeprom_if_i2c.cpp b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp
new file mode 100644
index 000000000..cc22bf7d9
--- /dev/null
+++ b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp
@@ -0,0 +1,78 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+
+/**
+ * Platform-independent Arduino functions for I2C EEPROM.
+ * Enable USE_SHARED_EEPROM if not supplied by the framework.
+ */
+
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(I2C_EEPROM)
+
+#include "eeprom_if.h"
+#include
+
+void eeprom_init() { Wire.begin(); }
+
+#if ENABLED(USE_SHARED_EEPROM)
+
+#ifndef EEPROM_WRITE_DELAY
+ #define EEPROM_WRITE_DELAY 5
+#endif
+#ifndef EEPROM_DEVICE_ADDRESS
+ #define EEPROM_DEVICE_ADDRESS 0x50
+#endif
+
+static constexpr uint8_t eeprom_device_address = I2C_ADDRESS(EEPROM_DEVICE_ADDRESS);
+
+// ------------------------
+// Public functions
+// ------------------------
+
+void eeprom_write_byte(uint8_t *pos, unsigned char value) {
+ const unsigned eeprom_address = (unsigned)pos;
+
+ Wire.beginTransmission(eeprom_device_address);
+ Wire.write(int(eeprom_address >> 8)); // MSB
+ Wire.write(int(eeprom_address & 0xFF)); // LSB
+ Wire.write(value);
+ Wire.endTransmission();
+
+ // wait for write cycle to complete
+ // this could be done more efficiently with "acknowledge polling"
+ delay(EEPROM_WRITE_DELAY);
+}
+
+uint8_t eeprom_read_byte(uint8_t *pos) {
+ const unsigned eeprom_address = (unsigned)pos;
+
+ Wire.beginTransmission(eeprom_device_address);
+ Wire.write(int(eeprom_address >> 8)); // MSB
+ Wire.write(int(eeprom_address & 0xFF)); // LSB
+ Wire.endTransmission();
+ Wire.requestFrom(eeprom_device_address, (byte)1);
+ return Wire.available() ? Wire.read() : 0xFF;
+}
+
+#endif // USE_SHARED_EEPROM
+#endif // I2C_EEPROM
diff --git a/Marlin/src/HAL/shared/eeprom_spi.cpp b/Marlin/src/HAL/shared/eeprom_if_spi.cpp
similarity index 57%
rename from Marlin/src/HAL/shared/eeprom_spi.cpp
rename to Marlin/src/HAL/shared/eeprom_if_spi.cpp
index ce7479aed..a341fef9d 100644
--- a/Marlin/src/HAL/shared/eeprom_spi.cpp
+++ b/Marlin/src/HAL/shared/eeprom_if_spi.cpp
@@ -16,25 +16,33 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
/**
- * Description: functions for SPI connected external EEPROM.
- * Not platform dependent.
+ * Platform-independent Arduino functions for SPI EEPROM.
+ * Enable USE_SHARED_EEPROM if not supplied by the framework.
*/
#include "../../inc/MarlinConfig.h"
#if ENABLED(SPI_EEPROM)
-#include "../HAL.h"
+#include "eeprom_if.h"
+
+void eeprom_init() {}
+
+#if ENABLED(USE_SHARED_EEPROM)
#define CMD_WREN 6 // WREN
#define CMD_READ 2 // WRITE
#define CMD_WRITE 2 // WRITE
+#ifndef EEPROM_WRITE_DELAY
+ #define EEPROM_WRITE_DELAY 7
+#endif
+
uint8_t eeprom_read_byte(uint8_t* pos) {
uint8_t v;
uint8_t eeprom_temp[3];
@@ -53,24 +61,6 @@ uint8_t eeprom_read_byte(uint8_t* pos) {
return v;
}
-void eeprom_read_block(void* dest, const void* eeprom_address, size_t n) {
- uint8_t eeprom_temp[3];
-
- // set read location
- // begin transmission from device
- eeprom_temp[0] = CMD_READ;
- eeprom_temp[1] = ((unsigned)eeprom_address>>8) & 0xFF; // addr High
- eeprom_temp[2] = (unsigned)eeprom_address& 0xFF; // addr Low
- WRITE(SPI_EEPROM1_CS, HIGH);
- WRITE(SPI_EEPROM1_CS, LOW);
- spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 3);
-
- uint8_t *p_dest = (uint8_t *)dest;
- while (n--)
- *p_dest++ = spiRec(SPI_CHAN_EEPROM1);
- WRITE(SPI_EEPROM1_CS, HIGH);
-}
-
void eeprom_write_byte(uint8_t* pos, uint8_t value) {
uint8_t eeprom_temp[3];
@@ -90,29 +80,8 @@ void eeprom_write_byte(uint8_t* pos, uint8_t value) {
spiSend(SPI_CHAN_EEPROM1, value);
WRITE(SPI_EEPROM1_CS, HIGH);
- delay(7); // wait for page write to complete
+ delay(EEPROM_WRITE_DELAY); // wait for page write to complete
}
-void eeprom_update_block(const void* src, void* eeprom_address, size_t n) {
- uint8_t eeprom_temp[3];
-
- /*write enable*/
- eeprom_temp[0] = CMD_WREN;
- WRITE(SPI_EEPROM1_CS, LOW);
- spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 1);
- WRITE(SPI_EEPROM1_CS, HIGH);
- delay(1);
-
- /*write addr*/
- eeprom_temp[0] = CMD_WRITE;
- eeprom_temp[1] = ((unsigned)eeprom_address>>8) & 0xFF; //addr High
- eeprom_temp[2] = (unsigned)eeprom_address & 0xFF; //addr Low
- WRITE(SPI_EEPROM1_CS, LOW);
- spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 3);
-
- spiSend(SPI_CHAN_EEPROM1, (const uint8_t*)src, n);
- WRITE(SPI_EEPROM1_CS, HIGH);
- delay(7); // wait for page write to complete
-}
-
-#endif // SPI_EEPROM
+#endif // USE_SHARED_EEPROM
+#endif // I2C_EEPROM
diff --git a/Marlin/src/HAL/shared/esp_wifi.cpp b/Marlin/src/HAL/shared/esp_wifi.cpp
new file mode 100644
index 000000000..a55f5ca39
--- /dev/null
+++ b/Marlin/src/HAL/shared/esp_wifi.cpp
@@ -0,0 +1,43 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+
+#include "../../inc/MarlinConfig.h"
+#include "Delay.h"
+
+void esp_wifi_init(void) { // init ESP01 WIFI module pins
+ #if PIN_EXISTS(ESP_WIFI_MODULE_GPIO0)
+ OUT_WRITE(ESP_WIFI_MODULE_GPIO0_PIN, HIGH);
+ #endif
+ #if PIN_EXISTS(ESP_WIFI_MODULE_GPIO2)
+ OUT_WRITE(ESP_WIFI_MODULE_GPIO2_PIN, HIGH);
+ #endif
+ #if PIN_EXISTS(ESP_WIFI_MODULE_RESET)
+ delay(1); // power up delay (0.1mS minimum)
+ OUT_WRITE(ESP_WIFI_MODULE_RESET_PIN, LOW);
+ delay(1);
+ OUT_WRITE(ESP_WIFI_MODULE_RESET_PIN, HIGH);
+ #endif
+ #if PIN_EXISTS(ESP_WIFI_MODULE_ENABLE)
+ delay(1); // delay after reset released (0.1mS minimum)
+ OUT_WRITE(ESP_WIFI_MODULE_ENABLE_PIN, HIGH);
+ #endif
+}
diff --git a/Marlin/src/HAL/LPC1768/eeprom_api.h b/Marlin/src/HAL/shared/esp_wifi.h
similarity index 85%
rename from Marlin/src/HAL/LPC1768/eeprom_api.h
rename to Marlin/src/HAL/shared/esp_wifi.h
index f874eac58..84a50a941 100644
--- a/Marlin/src/HAL/LPC1768/eeprom_api.h
+++ b/Marlin/src/HAL/shared/esp_wifi.h
@@ -16,11 +16,9 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
-#include "../shared/eeprom_api.h"
-
-#define FLASH_EEPROM_EMULATION
+void esp_wifi_init();
diff --git a/Marlin/src/HAL/shared/math_32bit.h b/Marlin/src/HAL/shared/math_32bit.h
index d93ab9caf..87e9e6406 100644
--- a/Marlin/src/HAL/shared/math_32bit.h
+++ b/Marlin/src/HAL/shared/math_32bit.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/shared/servo.cpp b/Marlin/src/HAL/shared/servo.cpp
index 2c3d7bb7d..d69cf2fe2 100644
--- a/Marlin/src/HAL/shared/servo.cpp
+++ b/Marlin/src/HAL/shared/servo.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -150,9 +150,7 @@ void Servo::move(const int value) {
if (attach(0) >= 0) {
write(value);
safe_delay(servo_delay[servoIndex]);
- #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
- detach();
- #endif
+ TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
}
}
diff --git a/Marlin/src/HAL/shared/servo.h b/Marlin/src/HAL/shared/servo.h
index b582221b8..f9c478411 100644
--- a/Marlin/src/HAL/shared/servo.h
+++ b/Marlin/src/HAL/shared/servo.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/HAL/shared/servo_private.h b/Marlin/src/HAL/shared/servo_private.h
index 58e455b12..d85d8da8b 100644
--- a/Marlin/src/HAL/shared/servo_private.h
+++ b/Marlin/src/HAL/shared/servo_private.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp
index 8130affe3..00ea51b05 100644
--- a/Marlin/src/MarlinCore.cpp
+++ b/Marlin/src/MarlinCore.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -30,6 +30,14 @@
#include "MarlinCore.h"
+#include "HAL/shared/Delay.h"
+#include "HAL/shared/esp_wifi.h"
+
+#ifdef ARDUINO
+ #include
+#endif
+#include
+
#include "core/utility.h"
#include "lcd/ultralcd.h"
#include "module/motion.h"
@@ -43,20 +51,35 @@
#include "module/printcounter.h" // PrintCounter or Stopwatch
#include "feature/closedloop.h"
-#include "HAL/shared/Delay.h"
-
#include "module/stepper/indirection.h"
-#ifdef ARDUINO
- #include
-#endif
-#include
#include "libs/nozzle.h"
#include "gcode/gcode.h"
#include "gcode/parser.h"
#include "gcode/queue.h"
+#if HAS_TFT_LVGL_UI
+ #include "lcd/extui/lib/mks_ui/tft_lvgl_configuration.h"
+ #include "lcd/extui/lib/mks_ui/draw_ui.h"
+ #include "lcd/extui/lib/mks_ui/mks_hardware_test.h"
+ #include
+#endif
+
+#if ENABLED(DWIN_CREALITY_LCD)
+ #include "lcd/dwin/dwin.h"
+ #include "lcd/dwin/dwin_lcd.h"
+ #include "lcd/dwin/rotary_encoder.h"
+#endif
+
+#if ENABLED(IIC_BL24CXX_EEPROM)
+ #include "libs/BL24CXX.h"
+#endif
+
+#if ENABLED(DIRECT_STEPPING)
+ #include "feature/direct_stepping.h"
+#endif
+
#if ENABLED(TOUCH_BUTTONS)
#include "feature/touch/xpt2046.h"
#endif
@@ -69,7 +92,7 @@
#include "libs/buzzer.h"
#endif
-#if ENABLED(DIGIPOT_I2C)
+#if HAS_I2C_DIGIPOT
#include "feature/digipot/digipot.h"
#endif
@@ -153,6 +176,10 @@
#include "feature/runout.h"
#endif
+#if ENABLED(HOTEND_IDLE_TIMEOUT)
+ #include "feature/hotend_idle.h"
+#endif
+
#if ENABLED(TEMP_STAT_LEDS)
#include "feature/leds/tempstat.h"
#endif
@@ -181,26 +208,18 @@
#include "libs/L64XX/L64XX_Marlin.h"
#endif
-const char NUL_STR[] PROGMEM = "",
- M112_KILL_STR[] PROGMEM = "M112 Shutdown",
- G28_STR[] PROGMEM = "G28",
- M21_STR[] PROGMEM = "M21",
- M23_STR[] PROGMEM = "M23 %s",
- M24_STR[] PROGMEM = "M24",
- SP_P_STR[] PROGMEM = " P",
- SP_T_STR[] PROGMEM = " T",
- SP_X_STR[] PROGMEM = " X",
- SP_Y_STR[] PROGMEM = " Y",
- SP_Z_STR[] PROGMEM = " Z",
- SP_E_STR[] PROGMEM = " E",
- X_LBL[] PROGMEM = "X:",
- Y_LBL[] PROGMEM = "Y:",
- Z_LBL[] PROGMEM = "Z:",
- E_LBL[] PROGMEM = "E:",
- SP_X_LBL[] PROGMEM = " X:",
- SP_Y_LBL[] PROGMEM = " Y:",
- SP_Z_LBL[] PROGMEM = " Z:",
- SP_E_LBL[] PROGMEM = " E:";
+PGMSTR(NUL_STR, "");
+PGMSTR(M112_KILL_STR, "M112 Shutdown");
+PGMSTR(G28_STR, "G28");
+PGMSTR(M21_STR, "M21");
+PGMSTR(M23_STR, "M23 %s");
+PGMSTR(M24_STR, "M24");
+PGMSTR(SP_P_STR, " P"); PGMSTR(SP_T_STR, " T");
+PGMSTR(X_STR, "X"); PGMSTR(Y_STR, "Y"); PGMSTR(Z_STR, "Z"); PGMSTR(E_STR, "E");
+PGMSTR(X_LBL, "X:"); PGMSTR(Y_LBL, "Y:"); PGMSTR(Z_LBL, "Z:"); PGMSTR(E_LBL, "E:");
+PGMSTR(SP_A_STR, " A"); PGMSTR(SP_B_STR, " B"); PGMSTR(SP_C_STR, " C");
+PGMSTR(SP_X_STR, " X"); PGMSTR(SP_Y_STR, " Y"); PGMSTR(SP_Z_STR, " Z"); PGMSTR(SP_E_STR, " E");
+PGMSTR(SP_X_LBL, " X:"); PGMSTR(SP_Y_LBL, " Y:"); PGMSTR(SP_Z_LBL, " Z:"); PGMSTR(SP_E_LBL, " E:");
MarlinState marlin_state = MF_INITIALIZING;
@@ -212,28 +231,17 @@ bool wait_for_heatup = true;
bool wait_for_user; // = false;
void wait_for_user_response(millis_t ms/*=0*/, const bool no_sleep/*=false*/) {
- #if DISABLED(ADVANCED_PAUSE_FEATURE)
- UNUSED(no_sleep);
- #endif
+ TERN(ADVANCED_PAUSE_FEATURE,,UNUSED(no_sleep));
KEEPALIVE_STATE(PAUSED_FOR_USER);
wait_for_user = true;
if (ms) ms += millis(); // expire time
- while (wait_for_user && !(ms && ELAPSED(millis(), ms))) {
- idle(
- #if ENABLED(ADVANCED_PAUSE_FEATURE)
- no_sleep
- #endif
- );
- }
+ while (wait_for_user && !(ms && ELAPSED(millis(), ms)))
+ idle(TERN_(ADVANCED_PAUSE_FEATURE, no_sleep));
wait_for_user = false;
}
#endif
-// Inactivity shutdown
-millis_t max_inactive_time, // = 0
- stepper_inactive_time = (DEFAULT_STEPPER_DEACTIVE_TIME) * 1000UL;
-
#if PIN_EXISTS(CHDK)
extern millis_t chdk_timeout;
#endif
@@ -250,7 +258,11 @@ millis_t max_inactive_time, // = 0
void setup_killpin() {
#if HAS_KILL
- SET_INPUT_PULLUP(KILL_PIN);
+ #if KILL_PIN_STATE
+ SET_INPUT_PULLDOWN(KILL_PIN);
+ #else
+ SET_INPUT_PULLUP(KILL_PIN);
+ #endif
#endif
}
@@ -290,6 +302,9 @@ void setup_powerhold() {
#include "pins/sensitive_pins.h"
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wnarrowing"
+
bool pin_is_protected(const pin_t pin) {
static const pin_t sensitive_pins[] PROGMEM = SENSITIVE_PINS;
LOOP_L_N(i, COUNT(sensitive_pins)) {
@@ -300,6 +315,8 @@ bool pin_is_protected(const pin_t pin) {
return false;
}
+#pragma GCC diagnostic pop
+
void protected_pin_err() {
SERIAL_ERROR_MSG(STR_ERR_PROTECTED_PIN);
}
@@ -317,9 +334,7 @@ void enable_e_steppers() {
}
void enable_all_steppers() {
- #if ENABLED(AUTO_POWER_CONTROL)
- powerManager.power_on();
- #endif
+ TERN_(AUTO_POWER_CONTROL, powerManager.power_on());
ENABLE_AXIS_X();
ENABLE_AXIS_Y();
ENABLE_AXIS_Z();
@@ -363,9 +378,7 @@ void disable_all_steppers() {
}
void event_probe_recover() {
- #if ENABLED(HOST_PROMPT_SUPPORT)
- host_prompt_do(PROMPT_INFO, PSTR("G29 Retrying"), DISMISS_STR);
- #endif
+ TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_INFO, PSTR("G29 Retrying"), DISMISS_STR));
#ifdef ACTION_ON_G29_RECOVER
host_action(PSTR(ACTION_ON_G29_RECOVER));
#endif
@@ -382,6 +395,13 @@ void disable_all_steppers() {
constexpr bool did_pause_print = false;
#endif
+/**
+ * A Print Job exists when the timer is running or SD printing
+ */
+bool printJobOngoing() {
+ return print_job_timer.isRunning() || IS_SD_PRINTING();
+}
+
/**
* Printing is active when the print job timer is running
*/
@@ -398,12 +418,8 @@ bool printingIsPaused() {
void startOrResumeJob() {
if (!printingIsPaused()) {
- #if ENABLED(CANCEL_OBJECTS)
- cancelable.reset();
- #endif
- #if ENABLED(LCD_SHOW_E_TOTAL)
- e_move_accumulator = 0;
- #endif
+ TERN_(CANCEL_OBJECTS, cancelable.reset());
+ TERN_(LCD_SHOW_E_TOTAL, e_move_accumulator = 0);
#if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME)
ui.reset_remaining_time();
#endif
@@ -414,22 +430,20 @@ void startOrResumeJob() {
#if ENABLED(SDSUPPORT)
inline void abortSDPrinting() {
- card.endFilePrint(
- #if SD_RESORT
- true
- #endif
- );
+ card.endFilePrint(TERN_(SD_RESORT, true));
queue.clear();
quickstop_stepper();
print_job_timer.stop();
#if DISABLED(SD_ABORT_NO_COOLDOWN)
thermalManager.disable_all_heaters();
#endif
- thermalManager.zero_fan_speeds();
- wait_for_heatup = false;
- #if ENABLED(POWER_LOSS_RECOVERY)
- recovery.purge();
+ #if !HAS_CUTTER
+ thermalManager.zero_fan_speeds();
+ #else
+ cutter.kill(); // Full cutter shutdown including ISR control
#endif
+ wait_for_heatup = false;
+ TERN_(POWER_LOSS_RECOVERY, recovery.purge());
#ifdef EVENT_GCODE_SD_STOP
queue.inject_P(PSTR(EVENT_GCODE_SD_STOP));
#endif
@@ -444,7 +458,6 @@ void startOrResumeJob() {
/**
* Minimal management of Marlin's core activities:
- * - Check for Filament Runout
* - Keep the command buffer full
* - Check for maximum inactive time between commands
* - Check for maximum inactive time between stepper commands
@@ -455,43 +468,46 @@ void startOrResumeJob() {
* - Check if an idle but hot extruder needs filament extruded (EXTRUDER_RUNOUT_PREVENT)
* - Pulse FET_SAFETY_PIN if it exists
*/
-
inline void manage_inactivity(const bool ignore_stepper_queue=false) {
- #if HAS_FILAMENT_SENSOR
- runout.run();
- #endif
-
if (queue.length < BUFSIZE) queue.get_available_commands();
const millis_t ms = millis();
- if (max_inactive_time && ELAPSED(ms, gcode.previous_move_ms + max_inactive_time)) {
+ // Prevent steppers timing-out in the middle of M600
+ // unless PAUSE_PARK_NO_STEPPER_TIMEOUT is disabled
+ const bool parked_or_ignoring = ignore_stepper_queue ||
+ (BOTH(ADVANCED_PAUSE_FEATURE, PAUSE_PARK_NO_STEPPER_TIMEOUT) && did_pause_print);
+
+ // Reset both the M18/M84 activity timeout and the M85 max 'kill' timeout
+ if (parked_or_ignoring) gcode.reset_stepper_timeout(ms);
+
+ if (gcode.stepper_max_timed_out(ms)) {
SERIAL_ERROR_START();
SERIAL_ECHOLNPAIR(STR_KILL_INACTIVE_TIME, parser.command_ptr);
kill();
}
- // Prevent steppers timing-out in the middle of M600
- #define STAY_TEST (BOTH(ADVANCED_PAUSE_FEATURE, PAUSE_PARK_NO_STEPPER_TIMEOUT) && did_pause_print)
+ // M18 / M94 : Handle steppers inactive time timeout
+ if (gcode.stepper_inactive_time) {
- if (stepper_inactive_time) {
static bool already_shutdown_steppers; // = false
+
+ // Any moves in the planner? Resets both the M18/M84
+ // activity timeout and the M85 max 'kill' timeout
if (planner.has_blocks_queued())
- gcode.reset_stepper_timeout();
- else if (!STAY_TEST && !ignore_stepper_queue && ELAPSED(ms, gcode.previous_move_ms + stepper_inactive_time)) {
+ gcode.reset_stepper_timeout(ms);
+ else if (!parked_or_ignoring && gcode.stepper_inactive_timeout()) {
if (!already_shutdown_steppers) {
already_shutdown_steppers = true; // L6470 SPI will consume 99% of free time without this
+
+ // Individual axes will be disabled if configured
if (ENABLED(DISABLE_INACTIVE_X)) DISABLE_AXIS_X();
if (ENABLED(DISABLE_INACTIVE_Y)) DISABLE_AXIS_Y();
if (ENABLED(DISABLE_INACTIVE_Z)) DISABLE_AXIS_Z();
if (ENABLED(DISABLE_INACTIVE_E)) disable_e_steppers();
- #if HAS_LCD_MENU && ENABLED(AUTO_BED_LEVELING_UBL)
- if (ubl.lcd_map_control) {
- ubl.lcd_map_control = false;
- ui.defer_status_screen(false);
- }
- #endif
+
+ TERN_(AUTO_BED_LEVELING_UBL, ubl.steppers_were_disabled());
}
}
else
@@ -512,7 +528,7 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) {
// -------------------------------------------------------------------------------
static int killCount = 0; // make the inactivity button a bit less responsive
const int KILL_DELAY = 750;
- if (!READ(KILL_PIN))
+ if (kill_state())
killCount++;
else if (killCount > 0)
killCount--;
@@ -540,17 +556,15 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) {
}
#endif
- #if ENABLED(USE_CONTROLLER_FAN)
- controllerFan.update(); // Check if fan should be turned on to cool stepper drivers down
- #endif
+ TERN_(USE_CONTROLLER_FAN, controllerFan.update()); // Check if fan should be turned on to cool stepper drivers down
- #if ENABLED(AUTO_POWER_CONTROL)
- powerManager.check();
- #endif
+ TERN_(AUTO_POWER_CONTROL, powerManager.check());
+
+ TERN_(HOTEND_IDLE_TIMEOUT, hotend_idle.check());
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
if (thermalManager.degHotend(active_extruder) > EXTRUDER_RUNOUT_MINTEMP
- && ELAPSED(ms, gcode.previous_move_ms + (EXTRUDER_RUNOUT_SECONDS) * 1000UL)
+ && ELAPSED(ms, gcode.previous_move_ms + SEC_TO_MS(EXTRUDER_RUNOUT_SECONDS))
&& !planner.has_blocks_queued()
) {
#if ENABLED(SWITCHING_EXTRUDER)
@@ -600,7 +614,7 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) {
}
#endif // !SWITCHING_EXTRUDER
- gcode.reset_stepper_timeout();
+ gcode.reset_stepper_timeout(ms);
}
#endif // EXTRUDER_RUNOUT_PREVENT
@@ -614,17 +628,11 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) {
}
#endif
- #if ENABLED(TEMP_STAT_LEDS)
- handle_status_leds();
- #endif
+ TERN_(TEMP_STAT_LEDS, handle_status_leds());
- #if ENABLED(MONITOR_DRIVER_STATUS)
- monitor_tmc_drivers();
- #endif
+ TERN_(MONITOR_DRIVER_STATUS, monitor_tmc_drivers());
- #if ENABLED(MONITOR_L6470_DRIVER_STATUS)
- L64xxManager.monitor_driver();
- #endif
+ TERN_(MONITOR_L6470_DRIVER_STATUS, L64xxManager.monitor_driver());
// Limit check_axes_activity frequency to 10Hz
static millis_t next_check_axes_ms = 0;
@@ -645,54 +653,81 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) {
}
/**
- * Standard idle routine keeps the machine alive
+ * Standard idle routine keeps the machine alive:
+ * - Core Marlin activities
+ * - Manage heaters (and Watchdog)
+ * - Max7219 heartbeat, animation, etc.
+ *
+ * Only after setup() is complete:
+ * - Handle filament runout sensors
+ * - Run HAL idle tasks
+ * - Handle Power-Loss Recovery
+ * - Run StallGuard endstop checks
+ * - Handle SD Card insert / remove
+ * - Handle USB Flash Drive insert / remove
+ * - Announce Host Keepalive state (if any)
+ * - Update the Print Job Timer state
+ * - Update the Beeper queue
+ * - Read Buttons and Update the LCD
+ * - Run i2c Position Encoders
+ * - Auto-report Temperatures / SD Status
+ * - Update the Prusa MMU2
+ * - Handle Joystick jogging
*/
-void idle(
- #if ENABLED(ADVANCED_PAUSE_FEATURE)
- bool no_stepper_sleep/*=false*/
- #endif
-) {
- #if ENABLED(POWER_LOSS_RECOVERY) && PIN_EXISTS(POWER_LOSS)
- recovery.outage();
- #endif
+void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) {
- #if ENABLED(SPI_ENDSTOPS)
- if (endstops.tmc_spi_homing.any
- #if ENABLED(IMPROVE_HOMING_RELIABILITY)
- && ELAPSED(millis(), sg_guard_period)
- #endif
- ) {
- for (uint8_t i = 4; i--;) // Read SGT 4 times per idle loop
- if (endstops.tmc_spi_homing_check()) break;
- }
- #endif
-
- #if ENABLED(MAX7219_DEBUG)
- max7219.idle_tasks();
- #endif
-
- ui.update();
-
- #if ENABLED(HOST_KEEPALIVE_FEATURE)
- gcode.host_keepalive();
- #endif
-
- manage_inactivity(
- #if ENABLED(ADVANCED_PAUSE_FEATURE)
- no_stepper_sleep
- #endif
- );
+ // Core Marlin activities
+ manage_inactivity(TERN_(ADVANCED_PAUSE_FEATURE, no_stepper_sleep));
+ // Manage Heaters (and Watchdog)
thermalManager.manage_heater();
- #if ENABLED(PRINTCOUNTER)
- print_job_timer.tick();
+ // Max7219 heartbeat, animation, etc
+ TERN_(MAX7219_DEBUG, max7219.idle_tasks());
+
+ // Return if setup() isn't completed
+ if (marlin_state == MF_INITIALIZING) return;
+
+ // Handle filament runout sensors
+ TERN_(HAS_FILAMENT_SENSOR, runout.run());
+
+ // Run HAL idle tasks
+ #ifdef HAL_IDLETASK
+ HAL_idletask();
#endif
- #if USE_BEEPER
- buzzer.tick();
+ // Handle Power-Loss Recovery
+ #if ENABLED(POWER_LOSS_RECOVERY) && PIN_EXISTS(POWER_LOSS)
+ if (printJobOngoing()) recovery.outage();
#endif
+ // Run StallGuard endstop checks
+ #if ENABLED(SPI_ENDSTOPS)
+ if (endstops.tmc_spi_homing.any
+ && TERN1(IMPROVE_HOMING_RELIABILITY, ELAPSED(millis(), sg_guard_period))
+ ) LOOP_L_N(i, 4) // Read SGT 4 times per idle loop
+ if (endstops.tmc_spi_homing_check()) break;
+ #endif
+
+ // Handle SD Card insert / remove
+ TERN_(SDSUPPORT, card.manage_media());
+
+ // Handle USB Flash Drive insert / remove
+ TERN_(USB_FLASH_DRIVE_SUPPORT, Sd2Card::idle());
+
+ // Announce Host Keepalive state (if any)
+ TERN_(HOST_KEEPALIVE_FEATURE, gcode.host_keepalive());
+
+ // Update the Print Job Timer state
+ TERN_(PRINTCOUNTER, print_job_timer.tick());
+
+ // Update the Beeper queue
+ TERN_(USE_BEEPER, buzzer.tick());
+
+ // Handle UI input / draw events
+ TERN(DWIN_CREALITY_LCD, DWIN_Update(), ui.update());
+
+ // Run i2c Position Encoders
#if ENABLED(I2C_POSITION_ENCODERS)
static millis_t i2cpem_next_update_ms;
if (planner.has_blocks_queued()) {
@@ -704,31 +739,25 @@ void idle(
}
#endif
- #ifdef HAL_IDLETASK
- HAL_idletask();
- #endif
-
+ // Auto-report Temperatures / SD Status
#if HAS_AUTO_REPORTING
if (!gcode.autoreport_paused) {
- #if ENABLED(AUTO_REPORT_TEMPERATURES)
- thermalManager.auto_report_temperatures();
- #endif
- #if ENABLED(AUTO_REPORT_SD_STATUS)
- card.auto_report_sd_status();
- #endif
+ TERN_(AUTO_REPORT_TEMPERATURES, thermalManager.auto_report_temperatures());
+ TERN_(AUTO_REPORT_SD_STATUS, card.auto_report_sd_status());
}
#endif
- #if ENABLED(USB_FLASH_DRIVE_SUPPORT)
- Sd2Card::idle();
- #endif
+ // Update the Prusa MMU2
+ TERN_(PRUSA_MMU2, mmu2.mmu_loop());
- #if ENABLED(PRUSA_MMU2)
- mmu2.mmu_loop();
- #endif
+ // Handle Joystick jogging
+ TERN_(POLL_JOG, joystick.inject_jog_moves());
- #if ENABLED(POLL_JOG)
- joystick.inject_jog_moves();
+ // Direct Stepping
+ TERN_(DIRECT_STEPPING, page_manager.write_responses());
+
+ #if HAS_TFT_LVGL_UI
+ LV_TASK_HANDLER();
#endif
}
@@ -739,6 +768,8 @@ void idle(
void kill(PGM_P const lcd_error/*=nullptr*/, PGM_P const lcd_component/*=nullptr*/, const bool steppers_off/*=false*/) {
thermalManager.disable_all_heaters();
+ TERN_(HAS_CUTTER, cutter.kill()); // Full cutter shutdown including ISR control
+
SERIAL_ERROR_MSG(STR_ERR_KILLED);
#if HAS_DISPLAY
@@ -768,33 +799,31 @@ void minkill(const bool steppers_off/*=false*/) {
// Reiterate heaters off
thermalManager.disable_all_heaters();
+ TERN_(HAS_CUTTER, cutter.kill()); // Reiterate cutter shutdown
+
// Power off all steppers (for M112) or just the E steppers
steppers_off ? disable_all_steppers() : disable_e_steppers();
- #if ENABLED(PSU_CONTROL)
- PSU_OFF();
- #endif
+ TERN_(PSU_CONTROL, PSU_OFF());
- #if HAS_SUICIDE
- suicide();
- #endif
+ TERN_(HAS_SUICIDE, suicide());
#if HAS_KILL
// Wait for kill to be released
- while (!READ(KILL_PIN)) watchdog_refresh();
+ while (kill_state()) watchdog_refresh();
// Wait for kill to be pressed
- while (READ(KILL_PIN)) watchdog_refresh();
+ while (!kill_state()) watchdog_refresh();
- void (*resetFunc)() = 0; // Declare resetFunc() at address 0
+ void (*resetFunc)() = 0; // Declare resetFunc() at address 0
resetFunc(); // Jump to address 0
- #else // !HAS_KILL
+ #else
- for (;;) watchdog_refresh(); // Wait for reset
+ for (;;) watchdog_refresh(); // Wait for reset
- #endif // !HAS_KILL
+ #endif
}
/**
@@ -838,86 +867,93 @@ void stop() {
*/
void setup() {
- HAL_init();
-
- #if HAS_L64XX
- L64xxManager.init(); // Set up SPI, init drivers
+ #if ENABLED(MARLIN_DEV_MODE)
+ auto log_current_ms = [&](PGM_P const msg) {
+ SERIAL_ECHO_START();
+ SERIAL_CHAR('['); SERIAL_ECHO(millis()); SERIAL_ECHOPGM("] ");
+ serialprintPGM(msg);
+ SERIAL_EOL();
+ };
+ #define SETUP_LOG(M) log_current_ms(PSTR(M))
+ #else
+ #define SETUP_LOG(...) NOOP
#endif
+ #define SETUP_RUN(C) do{ SETUP_LOG(STRINGIFY(C)); C; }while(0)
- #if ENABLED(SMART_EFFECTOR) && PIN_EXISTS(SMART_EFFECTOR_MOD)
- OUT_WRITE(SMART_EFFECTOR_MOD_PIN, LOW); // Put Smart Effector into NORMAL mode
- #endif
-
- #if ENABLED(DISABLE_DEBUG)
+ #if EITHER(DISABLE_DEBUG, DISABLE_JTAG)
// Disable any hardware debug to free up pins for IO
- #ifdef JTAGSWD_DISABLE
+ #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE)
JTAGSWD_DISABLE();
#elif defined(JTAG_DISABLE)
JTAG_DISABLE();
#else
- #error "DISABLE_DEBUG is not supported for the selected MCU/Board"
+ #error "DISABLE_(DEBUG|JTAG) is not supported for the selected MCU/Board."
#endif
- #elif ENABLED(DISABLE_JTAG)
- // Disable JTAG to free up pins for IO
- #ifdef JTAG_DISABLE
- JTAG_DISABLE();
- #else
- #error "DISABLE_JTAG is not supported for the selected MCU/Board"
- #endif
- #endif
-
- #if HAS_FILAMENT_SENSOR
- runout.setup();
- #endif
-
- #if ENABLED(POWER_LOSS_RECOVERY)
- recovery.setup();
- #endif
-
- setup_killpin();
-
- #if HAS_TMC220x
- tmc_serial_begin();
- #endif
-
- setup_powerhold();
-
- #if HAS_STEPPER_RESET
- disableStepperDrivers();
#endif
#if NUM_SERIAL > 0
MYSERIAL0.begin(BAUDRATE);
uint32_t serial_connect_timeout = millis() + 1000UL;
while (!MYSERIAL0 && PENDING(millis(), serial_connect_timeout)) { /*nada*/ }
- #if NUM_SERIAL > 1
+ #if HAS_MULTI_SERIAL
MYSERIAL1.begin(BAUDRATE);
serial_connect_timeout = millis() + 1000UL;
while (!MYSERIAL1 && PENDING(millis(), serial_connect_timeout)) { /*nada*/ }
#endif
+ SERIAL_ECHO_MSG("start");
#endif
- SERIAL_ECHOLNPGM("start");
- SERIAL_ECHO_START();
+ SETUP_RUN(HAL_init());
+
+ #if HAS_L64XX
+ SETUP_RUN(L64xxManager.init()); // Set up SPI, init drivers
+ #endif
+
+ #if ENABLED(SMART_EFFECTOR) && PIN_EXISTS(SMART_EFFECTOR_MOD)
+ OUT_WRITE(SMART_EFFECTOR_MOD_PIN, LOW); // Put Smart Effector into NORMAL mode
+ #endif
+
+ #if HAS_FILAMENT_SENSOR
+ SETUP_RUN(runout.setup());
+ #endif
+
+ #if ENABLED(POWER_LOSS_RECOVERY)
+ SETUP_RUN(recovery.setup());
+ #endif
+
+ SETUP_RUN(setup_killpin());
+
+ #if HAS_TMC220x
+ SETUP_RUN(tmc_serial_begin());
+ #endif
+
+ SETUP_RUN(setup_powerhold());
+
+ #if HAS_STEPPER_RESET
+ SETUP_RUN(disableStepperDrivers());
+ #endif
#if HAS_TMC_SPI
#if DISABLED(TMC_USE_SW_SPI)
- SPI.begin();
+ SETUP_RUN(SPI.begin());
#endif
- tmc_init_cs_pins();
+ SETUP_RUN(tmc_init_cs_pins());
#endif
#ifdef BOARD_INIT
+ SETUP_LOG("BOARD_INIT");
BOARD_INIT();
#endif
+ SETUP_RUN(esp_wifi_init());
+
// Check startup - does nothing if bootloader sets MCUSR to 0
- byte mcu = HAL_get_reset_source();
- if (mcu & 1) SERIAL_ECHOLNPGM(STR_POWERUP);
- if (mcu & 2) SERIAL_ECHOLNPGM(STR_EXTERNAL_RESET);
- if (mcu & 4) SERIAL_ECHOLNPGM(STR_BROWNOUT_RESET);
- if (mcu & 8) SERIAL_ECHOLNPGM(STR_WATCHDOG_RESET);
- if (mcu & 32) SERIAL_ECHOLNPGM(STR_SOFTWARE_RESET);
+ const byte mcu = HAL_get_reset_source();
+ if (mcu & RST_POWER_ON) SERIAL_ECHOLNPGM(STR_POWERUP);
+ if (mcu & RST_EXTERNAL) SERIAL_ECHOLNPGM(STR_EXTERNAL_RESET);
+ if (mcu & RST_BROWN_OUT) SERIAL_ECHOLNPGM(STR_BROWNOUT_RESET);
+ if (mcu & RST_WATCHDOG) SERIAL_ECHOLNPGM(STR_WATCHDOG_RESET);
+ if (mcu & RST_SOFTWARE) SERIAL_ECHOLNPGM(STR_SOFTWARE_RESET);
HAL_clear_reset_source();
serialprintPGM(GET_TEXT(MSG_MARLIN));
@@ -937,22 +973,6 @@ void setup() {
SERIAL_ECHO_START();
SERIAL_ECHOLNPAIR(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, (int)sizeof(block_t) * (BLOCK_BUFFER_SIZE));
- // UI must be initialized before EEPROM
- // (because EEPROM code calls the UI).
-
- #if ENABLED(MARLIN_DEV_MODE)
- auto log_current_ms = [&](PGM_P const msg) {
- SERIAL_ECHO_START();
- SERIAL_CHAR('['); SERIAL_ECHO(millis()); SERIAL_ECHO("] ");
- serialprintPGM(msg);
- SERIAL_EOL();
- };
- #define SETUP_LOG(M) log_current_ms(PSTR(M))
- #else
- #define SETUP_LOG(...) NOOP
- #endif
- #define SETUP_RUN(C) do{ SETUP_LOG(STRINGIFY(C)); C; }while(0)
-
// Set up LEDs early
#if HAS_COLOR_LEDS
SETUP_RUN(leds.setup());
@@ -962,31 +982,35 @@ void setup() {
SETUP_RUN(controllerFan.setup());
#endif
- SETUP_RUN(ui.init());
- SETUP_RUN(ui.reset_status()); // Load welcome message early. (Retained if no errors exist.)
+ // UI must be initialized before EEPROM
+ // (because EEPROM code calls the UI).
- #if HAS_SPI_LCD && ENABLED(SHOW_BOOTSCREEN)
- SETUP_RUN(ui.show_bootscreen());
+ #if ENABLED(DWIN_CREALITY_LCD)
+ delay(800); // Required delay (since boot?)
+ SERIAL_ECHOPGM("\nDWIN handshake ");
+ if (DWIN_Handshake()) SERIAL_ECHOLNPGM("ok."); else SERIAL_ECHOLNPGM("error.");
+ DWIN_Frame_SetDir(1); // Orientation 90°
+ DWIN_UpdateLCD(); // Show bootscreen (first image)
+ #else
+ SETUP_RUN(ui.init());
+ #if HAS_SPI_LCD && ENABLED(SHOW_BOOTSCREEN)
+ SETUP_RUN(ui.show_bootscreen());
+ #endif
+ SETUP_RUN(ui.reset_status()); // Load welcome message early. (Retained if no errors exist.)
#endif
- #if ENABLED(SDSUPPORT) && defined(SDCARD_CONNECTION) && !SD_CONNECTION_IS(LCD)
- SETUP_RUN(card.mount()); // Mount onboard / custom SD card before settings.first_load
+ #if BOTH(SDSUPPORT, SDCARD_EEPROM_EMULATION)
+ SETUP_RUN(card.mount()); // Mount media with settings before first_load
#endif
SETUP_RUN(settings.first_load()); // Load data from EEPROM if available (or use defaults)
// This also updates variables in the planner, elsewhere
- #if HAS_SERVICE_INTERVALS
- SETUP_RUN(ui.reset_status(true)); // Show service messages or keep current status
- #endif
-
#if ENABLED(TOUCH_BUTTONS)
SETUP_RUN(touch.init());
#endif
- #if HAS_M206_COMMAND
- current_position += home_offset; // Init current position based on home_offset
- #endif
+ TERN_(HAS_M206_COMMAND, current_position += home_offset); // Init current position based on home_offset
sync_plan_position(); // Vital to init stepper/planner equivalent for current_position
@@ -1029,7 +1053,7 @@ void setup() {
SETUP_RUN(enableStepperDrivers());
#endif
- #if ENABLED(DIGIPOT_I2C)
+ #if HAS_I2C_DIGIPOT
SETUP_RUN(digipot_i2c_init());
#endif
@@ -1113,23 +1137,19 @@ void setup() {
#endif
#if ENABLED(SWITCHING_TOOLHEAD)
- swt_init();
+ SETUP_RUN(swt_init());
#endif
#if ENABLED(ELECTROMAGNETIC_SWITCHING_TOOLHEAD)
SETUP_RUN(est_init());
#endif
- #if ENABLED(POWER_LOSS_RECOVERY)
- SETUP_RUN(recovery.check());
- #endif
-
#if ENABLED(USE_WATCHDOG)
SETUP_RUN(watchdog_init()); // Reinit watchdog after HAL_get_reset_source call
#endif
#if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER)
- SETUP_RUN(init_closedloop());
+ SETUP_RUN(closedloop.init());
#endif
#ifdef STARTUP_COMMANDS
@@ -1137,10 +1157,6 @@ void setup() {
queue.inject_P(PSTR(STARTUP_COMMANDS));
#endif
- #if ENABLED(INIT_SDCARD_ON_BOOT) && !HAS_SPI_LCD
- SETUP_RUN(card.beginautostart());
- #endif
-
#if ENABLED(HOST_PROMPT_SUPPORT)
SETUP_RUN(host_action_prompt_end());
#endif
@@ -1153,10 +1169,35 @@ void setup() {
SETUP_RUN(mmu2.init());
#endif
+ #if ENABLED(IIC_BL24CXX_EEPROM)
+ BL24CXX::init();
+ const uint8_t err = BL24CXX::check();
+ SERIAL_ECHO_TERNARY(err, "BL24CXX Check ", "failed", "succeeded", "!\n");
+ #endif
+
+ #if ENABLED(DWIN_CREALITY_LCD)
+ Encoder_Configuration();
+ HMI_Init();
+ HMI_StartFrame(true);
+ #endif
+
+ #if HAS_SERVICE_INTERVALS && DISABLED(DWIN_CREALITY_LCD)
+ ui.reset_status(true); // Show service messages or keep current status
+ #endif
+
#if ENABLED(MAX7219_DEBUG)
SETUP_RUN(max7219.init());
#endif
+ #if ENABLED(DIRECT_STEPPING)
+ SETUP_RUN(page_manager.init());
+ #endif
+
+ #if HAS_TFT_LVGL_UI
+ if (!card.isMounted()) SETUP_RUN(card.mount()); // Mount SD to load graphics and fonts
+ SETUP_RUN(tft_lvgl_init());
+ #endif
+
marlin_state = MF_RUNNING;
SETUP_LOG("setup() completed.");
@@ -1189,5 +1230,7 @@ void loop() {
endstops.event_handler();
+ TERN_(HAS_TFT_LVGL_UI, printer_state_polling());
+
} while (ENABLED(__AVR__)); // Loop forever on slower (AVR) boards
}
diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h
index e6678c5b1..81041c8ee 100644
--- a/Marlin/src/MarlinCore.h
+++ b/Marlin/src/MarlinCore.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -31,26 +31,11 @@
#include
#include
-#if HAS_L64XX
- #include "libs/L64XX/L64XX_Marlin.h"
- extern uint8_t axis_known_position;
-#endif
-
void stop();
-void idle(
- #if ENABLED(ADVANCED_PAUSE_FEATURE)
- bool no_stepper_sleep=false // Pass true to keep steppers from timing out
- #endif
-);
-
-inline void idle_no_sleep() {
- idle(
- #if ENABLED(ADVANCED_PAUSE_FEATURE)
- true
- #endif
- );
-}
+// Pass true to keep steppers from timing out
+void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep=false));
+inline void idle_no_sleep() { idle(TERN_(ADVANCED_PAUSE_FEATURE, true)); }
#if ENABLED(EXPERIMENTAL_I2CBUS)
#include "feature/twibus.h"
@@ -102,13 +87,6 @@ extern bool wait_for_heatup;
void wait_for_user_response(millis_t ms=0, const bool no_sleep=false);
#endif
-// Inactivity shutdown timer
-extern millis_t max_inactive_time, stepper_inactive_time;
-
-#if ENABLED(USE_CONTROLLER_FAN)
- extern uint8_t controllerfan_speed;
-#endif
-
#if ENABLED(PSU_CONTROL)
extern bool powersupply_on;
#define PSU_PIN_ON() do{ OUT_WRITE(PS_ON_PIN, PSU_ACTIVE_HIGH); powersupply_on = true; }while(0)
@@ -129,12 +107,19 @@ void protected_pin_err();
inline void suicide() { OUT_WRITE(SUICIDE_PIN, SUICIDE_PIN_INVERTING); }
#endif
+#if HAS_KILL
+ #ifndef KILL_PIN_STATE
+ #define KILL_PIN_STATE LOW
+ #endif
+ inline bool kill_state() { return READ(KILL_PIN) == KILL_PIN_STATE; }
+#endif
+
#if ENABLED(G29_RETRY_AND_RECOVER)
void event_probe_recover();
void event_probe_failure();
#endif
extern const char NUL_STR[], M112_KILL_STR[], G28_STR[], M21_STR[], M23_STR[], M24_STR[],
+ SP_A_STR[], SP_B_STR[], SP_C_STR[],
SP_P_STR[], SP_T_STR[], SP_X_STR[], SP_Y_STR[], SP_Z_STR[], SP_E_STR[],
X_LBL[], Y_LBL[], Z_LBL[], E_LBL[], SP_X_LBL[], SP_Y_LBL[], SP_Z_LBL[], SP_E_LBL[];
-
diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h
index 30c2d3eb8..6e57a4374 100644
--- a/Marlin/src/core/boards.h
+++ b/Marlin/src/core/boards.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -56,54 +56,57 @@
#define BOARD_3DRAG 1100 // 3Drag Controller
#define BOARD_K8200 1101 // Velleman K8200 Controller (derived from 3Drag Controller)
#define BOARD_K8400 1102 // Velleman K8400 Controller (derived from 3Drag Controller)
-#define BOARD_BAM_DICE 1103 // 2PrintBeta BAM&DICE with STK drivers
-#define BOARD_BAM_DICE_DUE 1104 // 2PrintBeta BAM&DICE Due with STK drivers
-#define BOARD_MKS_BASE 1105 // MKS BASE v1.0
-#define BOARD_MKS_BASE_14 1106 // MKS BASE v1.4 with Allegro A4982 stepper drivers
-#define BOARD_MKS_BASE_15 1107 // MKS BASE v1.5 with Allegro A4982 stepper drivers
-#define BOARD_MKS_BASE_16 1108 // MKS BASE v1.6 with Allegro A4982 stepper drivers
-#define BOARD_MKS_BASE_HEROIC 1109 // MKS BASE 1.0 with Heroic HR4982 stepper drivers
-#define BOARD_MKS_GEN_13 1110 // MKS GEN v1.3 or 1.4
-#define BOARD_MKS_GEN_L 1111 // MKS GEN L
-#define BOARD_KFB_2 1112 // BigTreeTech or BIQU KFB2.0
-#define BOARD_ZRIB_V20 1113 // zrib V2.0 control board (Chinese knock off RAMPS replica)
-#define BOARD_FELIX2 1114 // Felix 2.0+ Electronics Board (RAMPS like)
-#define BOARD_RIGIDBOARD 1115 // Invent-A-Part RigidBoard
-#define BOARD_RIGIDBOARD_V2 1116 // Invent-A-Part RigidBoard V2
-#define BOARD_SAINSMART_2IN1 1117 // Sainsmart 2-in-1 board
-#define BOARD_ULTIMAKER 1118 // Ultimaker
-#define BOARD_ULTIMAKER_OLD 1119 // Ultimaker (Older electronics. Pre 1.5.4. This is rare)
-#define BOARD_AZTEEG_X3 1120 // Azteeg X3
-#define BOARD_AZTEEG_X3_PRO 1121 // Azteeg X3 Pro
-#define BOARD_ULTIMAIN_2 1122 // Ultimainboard 2.x (Uses TEMP_SENSOR 20)
-#define BOARD_RUMBA 1123 // Rumba
-#define BOARD_RUMBA_RAISE3D 1124 // Raise3D N series Rumba derivative
-#define BOARD_RL200 1125 // Rapide Lite 200 (v1, low-cost RUMBA clone with drv)
-#define BOARD_FORMBOT_TREX2PLUS 1126 // Formbot T-Rex 2 Plus
-#define BOARD_FORMBOT_TREX3 1127 // Formbot T-Rex 3
-#define BOARD_FORMBOT_RAPTOR 1128 // Formbot Raptor
-#define BOARD_FORMBOT_RAPTOR2 1129 // Formbot Raptor 2
-#define BOARD_BQ_ZUM_MEGA_3D 1130 // bq ZUM Mega 3D
-#define BOARD_MAKEBOARD_MINI 1131 // MakeBoard Mini v2.1.2 is a control board sold by MicroMake
-#define BOARD_TRIGORILLA_13 1132 // TriGorilla Anycubic version 1.3-based on RAMPS EFB
-#define BOARD_TRIGORILLA_14 1133 // ... Ver 1.4
-#define BOARD_TRIGORILLA_14_11 1134 // ... Rev 1.1 (new servo pin order)
-#define BOARD_RAMPS_ENDER_4 1135 // Creality: Ender-4, CR-8
-#define BOARD_RAMPS_CREALITY 1136 // Creality: CR10S, CR20, CR-X
-#define BOARD_RAMPS_DAGOMA 1137 // Dagoma F5
-#define BOARD_FYSETC_F6_13 1138 // FYSETC F6 1.3
-#define BOARD_FYSETC_F6_14 1139 // FYSETC F6 1.4
-#define BOARD_DUPLICATOR_I3_PLUS 1140 // Wanhao Duplicator i3 Plus
-#define BOARD_VORON 1141 // VORON Design
-#define BOARD_TRONXY_V3_1_0 1142 // Tronxy TRONXY-V3-1.0
-#define BOARD_Z_BOLT_X_SERIES 1143 // Z-Bolt X Series
-#define BOARD_TT_OSCAR 1144 // TT OSCAR
-#define BOARD_OVERLORD 1145 // Overlord/Overlord Pro
-#define BOARD_HJC2560C_REV1 1146 // ADIMLab Gantry v1
-#define BOARD_HJC2560C_REV2 1147 // ADIMLab Gantry v2
-#define BOARD_TANGO 1148 // BIQU Tango V1
-#define BOARD_MKS_GEN_L_V2 1149 // MKS GEN L V2
-#define BOARD_COPYMASTER_3D 1150 // Copymaster 3D
+#define BOARD_K8600 1103 // Velleman K8600 Controller (Vertex Nano)
+#define BOARD_BAM_DICE 1104 // 2PrintBeta BAM&DICE with STK drivers
+#define BOARD_BAM_DICE_DUE 1105 // 2PrintBeta BAM&DICE Due with STK drivers
+#define BOARD_MKS_BASE 1106 // MKS BASE v1.0
+#define BOARD_MKS_BASE_14 1107 // MKS BASE v1.4 with Allegro A4982 stepper drivers
+#define BOARD_MKS_BASE_15 1108 // MKS BASE v1.5 with Allegro A4982 stepper drivers
+#define BOARD_MKS_BASE_16 1109 // MKS BASE v1.6 with Allegro A4982 stepper drivers
+#define BOARD_MKS_BASE_HEROIC 1110 // MKS BASE 1.0 with Heroic HR4982 stepper drivers
+#define BOARD_MKS_GEN_13 1111 // MKS GEN v1.3 or 1.4
+#define BOARD_MKS_GEN_L 1112 // MKS GEN L
+#define BOARD_KFB_2 1113 // BigTreeTech or BIQU KFB2.0
+#define BOARD_ZRIB_V20 1114 // zrib V2.0 control board (Chinese knock off RAMPS replica)
+#define BOARD_FELIX2 1115 // Felix 2.0+ Electronics Board (RAMPS like)
+#define BOARD_RIGIDBOARD 1116 // Invent-A-Part RigidBoard
+#define BOARD_RIGIDBOARD_V2 1117 // Invent-A-Part RigidBoard V2
+#define BOARD_SAINSMART_2IN1 1118 // Sainsmart 2-in-1 board
+#define BOARD_ULTIMAKER 1119 // Ultimaker
+#define BOARD_ULTIMAKER_OLD 1120 // Ultimaker (Older electronics. Pre 1.5.4. This is rare)
+#define BOARD_AZTEEG_X3 1121 // Azteeg X3
+#define BOARD_AZTEEG_X3_PRO 1122 // Azteeg X3 Pro
+#define BOARD_ULTIMAIN_2 1123 // Ultimainboard 2.x (Uses TEMP_SENSOR 20)
+#define BOARD_RUMBA 1124 // Rumba
+#define BOARD_RUMBA_RAISE3D 1125 // Raise3D N series Rumba derivative
+#define BOARD_RL200 1126 // Rapide Lite 200 (v1, low-cost RUMBA clone with drv)
+#define BOARD_FORMBOT_TREX2PLUS 1127 // Formbot T-Rex 2 Plus
+#define BOARD_FORMBOT_TREX3 1128 // Formbot T-Rex 3
+#define BOARD_FORMBOT_RAPTOR 1129 // Formbot Raptor
+#define BOARD_FORMBOT_RAPTOR2 1130 // Formbot Raptor 2
+#define BOARD_BQ_ZUM_MEGA_3D 1131 // bq ZUM Mega 3D
+#define BOARD_MAKEBOARD_MINI 1132 // MakeBoard Mini v2.1.2 is a control board sold by MicroMake
+#define BOARD_TRIGORILLA_13 1133 // TriGorilla Anycubic version 1.3-based on RAMPS EFB
+#define BOARD_TRIGORILLA_14 1134 // ... Ver 1.4
+#define BOARD_TRIGORILLA_14_11 1135 // ... Rev 1.1 (new servo pin order)
+#define BOARD_RAMPS_ENDER_4 1136 // Creality: Ender-4, CR-8
+#define BOARD_RAMPS_CREALITY 1137 // Creality: CR10S, CR20, CR-X
+#define BOARD_RAMPS_DAGOMA 1138 // Dagoma F5
+#define BOARD_FYSETC_F6_13 1139 // FYSETC F6 1.3
+#define BOARD_FYSETC_F6_14 1140 // FYSETC F6 1.4
+#define BOARD_DUPLICATOR_I3_PLUS 1141 // Wanhao Duplicator i3 Plus
+#define BOARD_VORON 1142 // VORON Design
+#define BOARD_TRONXY_V3_1_0 1143 // Tronxy TRONXY-V3-1.0
+#define BOARD_Z_BOLT_X_SERIES 1144 // Z-Bolt X Series
+#define BOARD_TT_OSCAR 1145 // TT OSCAR
+#define BOARD_OVERLORD 1146 // Overlord/Overlord Pro
+#define BOARD_HJC2560C_REV1 1147 // ADIMLab Gantry v1
+#define BOARD_HJC2560C_REV2 1148 // ADIMLab Gantry v2
+#define BOARD_TANGO 1149 // BIQU Tango V1
+#define BOARD_MKS_GEN_L_V2 1150 // MKS GEN L V2
+#define BOARD_COPYMASTER_3D 1151 // Copymaster 3D
+#define BOARD_ORTUR_4 1152 // Ortur 4
+#define BOARD_TENLOG_D3_HERO 1153 // Tenlog D3 Hero IDEX printer
//
// RAMBo and derivatives
@@ -160,13 +163,14 @@
#define BOARD_SANGUINOLOLU_11 1500 // Sanguinololu < 1.2
#define BOARD_SANGUINOLOLU_12 1501 // Sanguinololu 1.2 and above
#define BOARD_MELZI 1502 // Melzi
-#define BOARD_MELZI_MAKR3D 1503 // Melzi with ATmega1284 (MaKr3d version)
-#define BOARD_MELZI_CREALITY 1504 // Melzi Creality3D board (for CR-10 etc)
-#define BOARD_MELZI_MALYAN 1505 // Melzi Malyan M150 board
-#define BOARD_MELZI_TRONXY 1506 // Tronxy X5S
-#define BOARD_STB_11 1507 // STB V1.1
-#define BOARD_AZTEEG_X1 1508 // Azteeg X1
-#define BOARD_ANET_10 1509 // Anet 1.0 (Melzi clone)
+#define BOARD_MELZI_V2 1503 // Melzi V2
+#define BOARD_MELZI_MAKR3D 1504 // Melzi with ATmega1284 (MaKr3d version)
+#define BOARD_MELZI_CREALITY 1505 // Melzi Creality3D board (for CR-10 etc)
+#define BOARD_MELZI_MALYAN 1506 // Melzi Malyan M150 board
+#define BOARD_MELZI_TRONXY 1507 // Tronxy X5S
+#define BOARD_STB_11 1508 // STB V1.1
+#define BOARD_AZTEEG_X1 1509 // Azteeg X1
+#define BOARD_ANET_10 1510 // Anet 1.0 (Melzi clone)
//
// Other ATmega644P, ATmega644, ATmega1284P
@@ -276,28 +280,39 @@
#define BOARD_STM32F103RE 4000 // STM32F103RE Libmaple-based STM32F1 controller
#define BOARD_MALYAN_M200 4001 // STM32C8T6 Libmaple-based STM32F1 controller
-#define BOARD_STM3R_MINI 4002 // STM32F103RE Libmaple-based STM32F1 controller
-#define BOARD_GTM32_PRO_VB 4003 // STM32F103VET6 controller
-#define BOARD_MORPHEUS 4004 // STM32F103C8 / STM32F103CB Libmaple-based STM32F1 controller
-#define BOARD_CHITU3D 4005 // Chitu3D (STM32F103RET6)
-#define BOARD_MKS_ROBIN 4006 // MKS Robin (STM32F103ZET6)
-#define BOARD_MKS_ROBIN_MINI 4007 // MKS Robin Mini (STM32F103VET6)
-#define BOARD_MKS_ROBIN_NANO 4008 // MKS Robin Nano (STM32F103VET6)
-#define BOARD_MKS_ROBIN_LITE 4009 // MKS Robin Lite/Lite2 (STM32F103RCT6)
-#define BOARD_MKS_ROBIN_LITE3 4010 // MKS Robin Lite3 (STM32F103RCT6)
-#define BOARD_MKS_ROBIN_PRO 4011 // MKS Robin Pro (STM32F103ZET6)
-#define BOARD_BTT_SKR_MINI_V1_1 4012 // BigTreeTech SKR Mini v1.1 (STM32F103RC)
-#define BOARD_BTT_SKR_MINI_E3_V1_0 4013 // BigTreeTech SKR Mini E3 (STM32F103RC)
-#define BOARD_BTT_SKR_MINI_E3_V1_2 4014 // BigTreeTech SKR Mini E3 V1.2 (STM32F103RC)
-#define BOARD_BTT_SKR_E3_DIP 4015 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE)
-#define BOARD_JGAURORA_A5S_A1 4016 // JGAurora A5S A1 (STM32F103ZET6)
-#define BOARD_FYSETC_AIO_II 4017 // FYSETC AIO_II
-#define BOARD_FYSETC_CHEETAH 4018 // FYSETC Cheetah
-#define BOARD_FYSETC_CHEETAH_V12 4019 // FYSETC Cheetah V1.2
-#define BOARD_LONGER3D_LK 4020 // Alfawise U20/U20+/U30 (Longer3D LK1/2) / STM32F103VET6
-#define BOARD_GTM32_MINI 4021 // STM32F103VET6 controller
-#define BOARD_GTM32_MINI_A30 4022 // STM32F103VET6 controller
-#define BOARD_GTM32_REV_B 4023 // STM32F103VET6 controller
+#define BOARD_MALYAN_M200_V2 4002 // STM32F070RB Libmaple-based STM32F0 controller
+#define BOARD_STM3R_MINI 4003 // STM32F103RE Libmaple-based STM32F1 controller
+#define BOARD_GTM32_PRO_VB 4004 // STM32F103VET6 controller
+#define BOARD_MORPHEUS 4005 // STM32F103C8 / STM32F103CB Libmaple-based STM32F1 controller
+#define BOARD_CHITU3D 4006 // Chitu3D (STM32F103RET6)
+#define BOARD_MKS_ROBIN 4007 // MKS Robin (STM32F103ZET6)
+#define BOARD_MKS_ROBIN_MINI 4008 // MKS Robin Mini (STM32F103VET6)
+#define BOARD_MKS_ROBIN_NANO 4009 // MKS Robin Nano (STM32F103VET6)
+#define BOARD_MKS_ROBIN_NANO_V2 4010 // MKS Robin Nano V2 (STM32F103VET6)
+#define BOARD_MKS_ROBIN_LITE 4011 // MKS Robin Lite/Lite2 (STM32F103RCT6)
+#define BOARD_MKS_ROBIN_LITE3 4012 // MKS Robin Lite3 (STM32F103RCT6)
+#define BOARD_MKS_ROBIN_PRO 4013 // MKS Robin Pro (STM32F103ZET6)
+#define BOARD_BTT_SKR_MINI_V1_1 4014 // BigTreeTech SKR Mini v1.1 (STM32F103RC)
+#define BOARD_BTT_SKR_MINI_E3_V1_0 4015 // BigTreeTech SKR Mini E3 (STM32F103RC)
+#define BOARD_BTT_SKR_MINI_E3_V1_2 4016 // BigTreeTech SKR Mini E3 V1.2 (STM32F103RC)
+#define BOARD_BTT_SKR_MINI_E3_V2_0 4017 // BigTreeTech SKR Mini E3 V2.0 (STM32F103RC)
+#define BOARD_BTT_SKR_E3_DIP 4018 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE)
+#define BOARD_JGAURORA_A5S_A1 4019 // JGAurora A5S A1 (STM32F103ZET6)
+#define BOARD_FYSETC_AIO_II 4020 // FYSETC AIO_II
+#define BOARD_FYSETC_CHEETAH 4021 // FYSETC Cheetah
+#define BOARD_FYSETC_CHEETAH_V12 4022 // FYSETC Cheetah V1.2
+#define BOARD_LONGER3D_LK 4023 // Alfawise U20/U20+/U30 (Longer3D LK1/2) / STM32F103VET6
+#define BOARD_GTM32_MINI 4024 // STM32F103VET6 controller
+#define BOARD_GTM32_MINI_A30 4025 // STM32F103VET6 controller
+#define BOARD_GTM32_REV_B 4026 // STM32F103VET6 controller
+#define BOARD_MKS_ROBIN_E3D 4027 // MKS Robin E3D (STM32F103RCT6)
+#define BOARD_MKS_ROBIN_E3 4028 // MKS Robin E3 (STM32F103RCT6)
+#define BOARD_MALYAN_M300 4029 // STM32F070-based delta
+#define BOARD_CCROBOT_MEEB_3DP 4030 // ccrobot-online.com MEEB_3DP (STM32F103RC)
+#define BOARD_CHITU3D_V5 4031 // Chitu3D TronXY X5SA V5 Board
+#define BOARD_CHITU3D_V6 4032 // Chitu3D TronXY X5SA V5 Board
+#define BOARD_CREALITY_V4 4033 // Creality v4.x (STM32F103RE)
+#define BOARD_TRIGORILLA_PRO 4034 // Trigorilla Pro (STM32F103ZET6)
//
// ARM Cortex-M4F
@@ -313,20 +328,23 @@
#define BOARD_BEAST 4200 // STM32F4xxVxT6 Libmaple-based STM32F4 controller
#define BOARD_GENERIC_STM32F4 4201 // STM32 STM32GENERIC-based STM32F4 controller
#define BOARD_ARMED 4202 // Arm'ed STM32F4-based controller
-#define BOARD_RUMBA32_AUS3D 4203 // RUMBA32 STM32F446VET6 based controller from Aus3D
-#define BOARD_RUMBA32_MKS 4204 // RUMBA32 STM32F446VET6 based controller from Makerbase
-#define BOARD_BLACK_STM32F407VE 4205 // BLACK_STM32F407VE
-#define BOARD_BLACK_STM32F407ZE 4206 // BLACK_STM32F407ZE
-#define BOARD_STEVAL_3DP001V1 4207 // STEVAL-3DP001V1 3D PRINTER BOARD
-#define BOARD_BTT_SKR_PRO_V1_1 4208 // BigTreeTech SKR Pro v1.1 (STM32F407ZG)
-#define BOARD_BTT_BTT002_V1_0 4209 // BigTreeTech BTT002 v1.0 (STM32F407VE)
-#define BOARD_BTT_GTR_V1_0 4210 // BigTreeTech GTR v1.0 (STM32F407IGT)
-#define BOARD_LERDGE_K 4211 // Lerdge K (STM32F407ZG)
-#define BOARD_LERDGE_X 4212 // Lerdge X (STM32F407VE)
-#define BOARD_VAKE403D 4213 // VAkE 403D (STM32F446VET6)
-#define BOARD_FYSETC_S6 4214 // FYSETC S6 board
-#define BOARD_FLYF407ZG 4215 // FLYF407ZG board (STM32F407ZG)
-#define BOARD_MKS_ROBIN2 4216 // MKS_ROBIN2 (STM32F407ZE)
+#define BOARD_RUMBA32_V1_0 4203 // RUMBA32 STM32F446VET6 based controller from Aus3D
+#define BOARD_RUMBA32_V1_1 4204 // RUMBA32 STM32F446VET6 based controller from Aus3D
+#define BOARD_RUMBA32_MKS 4205 // RUMBA32 STM32F446VET6 based controller from Makerbase
+#define BOARD_BLACK_STM32F407VE 4206 // BLACK_STM32F407VE
+#define BOARD_BLACK_STM32F407ZE 4207 // BLACK_STM32F407ZE
+#define BOARD_STEVAL_3DP001V1 4208 // STEVAL-3DP001V1 3D PRINTER BOARD
+#define BOARD_BTT_SKR_PRO_V1_1 4209 // BigTreeTech SKR Pro v1.1 (STM32F407ZG)
+#define BOARD_BTT_SKR_PRO_V1_2 4210 // BigTreeTech SKR Pro v1.2 (STM32F407ZG)
+#define BOARD_BTT_BTT002_V1_0 4211 // BigTreeTech BTT002 v1.0 (STM32F407VG)
+#define BOARD_BTT_GTR_V1_0 4212 // BigTreeTech GTR v1.0 (STM32F407IGT)
+#define BOARD_LERDGE_K 4213 // Lerdge K (STM32F407ZG)
+#define BOARD_LERDGE_S 4214 // Lerdge S (STM32F407VE)
+#define BOARD_LERDGE_X 4215 // Lerdge X (STM32F407VE)
+#define BOARD_VAKE403D 4216 // VAkE 403D (STM32F446VET6)
+#define BOARD_FYSETC_S6 4217 // FYSETC S6 board
+#define BOARD_FLYF407ZG 4218 // FLYF407ZG board (STM32F407ZG)
+#define BOARD_MKS_ROBIN2 4219 // MKS_ROBIN2 (STM32F407ZE)
//
// ARM Cortex M7
@@ -357,4 +375,4 @@
#define _MB_1(B) (defined(BOARD_##B) && MOTHERBOARD==BOARD_##B)
#define MB(V...) DO(MB,||,V)
-#define IS_MELZI MB(MELZI, MELZI_CREALITY, MELZI_MAKR3D, MELZI_MALYAN, MELZI_TRONXY)
+#define IS_MELZI MB(MELZI, MELZI_CREALITY, MELZI_MAKR3D, MELZI_MALYAN, MELZI_TRONXY, MELZI_V2)
diff --git a/Marlin/src/core/debug_out.h b/Marlin/src/core/debug_out.h
index 4b2cdf9f7..6ae1b9d8b 100644
--- a/Marlin/src/core/debug_out.h
+++ b/Marlin/src/core/debug_out.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -26,11 +26,13 @@
// (or not) in a given .cpp file
//
+#undef DEBUG_SECTION
#undef DEBUG_PRINT_P
#undef DEBUG_ECHO_START
#undef DEBUG_ERROR_START
#undef DEBUG_CHAR
#undef DEBUG_ECHO
+#undef DEBUG_DECIMAL
#undef DEBUG_ECHO_F
#undef DEBUG_ECHOLN
#undef DEBUG_ECHOPGM
@@ -46,16 +48,23 @@
#undef DEBUG_ECHO_MSG
#undef DEBUG_ERROR_MSG
#undef DEBUG_EOL
+#undef DEBUG_FLUSH
#undef DEBUG_POS
#undef DEBUG_XYZ
#undef DEBUG_DELAY
+#undef DEBUG_SYNCHRONIZE
#if DEBUG_OUT
+
+ #include "debug_section.h"
+ #define DEBUG_SECTION(N,S,D) SectionLog N(PSTR(S),D)
+
#define DEBUG_PRINT_P(P) serialprintPGM(P)
#define DEBUG_ECHO_START SERIAL_ECHO_START
#define DEBUG_ERROR_START SERIAL_ERROR_START
#define DEBUG_CHAR SERIAL_CHAR
#define DEBUG_ECHO SERIAL_ECHO
+ #define DEBUG_DECIMAL SERIAL_DECIMAL
#define DEBUG_ECHO_F SERIAL_ECHO_F
#define DEBUG_ECHOLN SERIAL_ECHOLN
#define DEBUG_ECHOPGM SERIAL_ECHOPGM
@@ -71,15 +80,21 @@
#define DEBUG_ECHO_MSG SERIAL_ECHO_MSG
#define DEBUG_ERROR_MSG SERIAL_ERROR_MSG
#define DEBUG_EOL SERIAL_EOL
+ #define DEBUG_FLUSH SERIAL_FLUSH
#define DEBUG_POS SERIAL_POS
#define DEBUG_XYZ SERIAL_XYZ
#define DEBUG_DELAY(ms) serial_delay(ms)
+ #define DEBUG_SYNCHRONIZE() planner.synchronize()
+
#else
+
+ #define DEBUG_SECTION(...) NOOP
#define DEBUG_PRINT_P(P) NOOP
#define DEBUG_ECHO_START() NOOP
#define DEBUG_ERROR_START() NOOP
#define DEBUG_CHAR(...) NOOP
#define DEBUG_ECHO(...) NOOP
+ #define DEBUG_DECIMAL(...) NOOP
#define DEBUG_ECHO_F(...) NOOP
#define DEBUG_ECHOLN(...) NOOP
#define DEBUG_ECHOPGM(...) NOOP
@@ -95,9 +110,12 @@
#define DEBUG_ECHO_MSG(...) NOOP
#define DEBUG_ERROR_MSG(...) NOOP
#define DEBUG_EOL() NOOP
+ #define DEBUG_FLUSH() NOOP
#define DEBUG_POS(...) NOOP
#define DEBUG_XYZ(...) NOOP
#define DEBUG_DELAY(...) NOOP
+ #define DEBUG_SYNCHRONIZE() NOOP
+
#endif
#undef DEBUG_OUT
diff --git a/Marlin/src/core/debug_section.h b/Marlin/src/core/debug_section.h
new file mode 100644
index 000000000..7f39bc742
--- /dev/null
+++ b/Marlin/src/core/debug_section.h
@@ -0,0 +1,49 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#pragma once
+
+#include "serial.h"
+#include "../module/motion.h"
+
+class SectionLog {
+public:
+ SectionLog(PGM_P const msg=nullptr, bool inbug=true) {
+ the_msg = msg;
+ if ((debug = inbug)) echo_msg(PSTR(">>>"));
+ }
+
+ ~SectionLog() { if (debug) echo_msg(PSTR("<<<")); }
+
+private:
+ PGM_P the_msg;
+ bool debug;
+
+ void echo_msg(PGM_P const pre) {
+ serialprintPGM(pre);
+ if (the_msg) {
+ SERIAL_CHAR(' ');
+ serialprintPGM(the_msg);
+ }
+ SERIAL_CHAR(' ');
+ print_xyz(current_position);
+ }
+};
diff --git a/Marlin/src/core/drivers.h b/Marlin/src/core/drivers.h
index 833899bdc..3a0e62092 100644
--- a/Marlin/src/core/drivers.h
+++ b/Marlin/src/core/drivers.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -86,6 +86,10 @@
|| AXIS_DRIVER_TYPE_X2(T) || AXIS_DRIVER_TYPE_Y2(T) || AXIS_DRIVER_TYPE_Z2(T) \
|| AXIS_DRIVER_TYPE_Z3(T) || AXIS_DRIVER_TYPE_Z4(T) || HAS_E_DRIVER(T) )
+//
+// Trinamic Stepper Drivers
+//
+
// Test for supported TMC drivers that require advanced configuration
// Does not match standalone configurations
#if ( HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC2160) \
@@ -127,6 +131,7 @@
#define AXIS_HAS_RXTX AXIS_HAS_UART
+#define AXIS_HAS_HW_SERIAL(A) ( AXIS_HAS_UART(A) && defined(A##_HARDWARE_SERIAL) )
#define AXIS_HAS_SW_SERIAL(A) ( AXIS_HAS_UART(A) && !defined(A##_HARDWARE_SERIAL) )
#define AXIS_HAS_STALLGUARD(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \
@@ -171,17 +176,16 @@
#define HAS_TMC_SPI 1
#endif
-// Defines that can't be evaluated now
-#define HAS_TMC_SW_SERIAL ANY_AXIS_HAS(SW_SERIAL)
+//
+// TMC26XX Stepper Drivers
+//
+#if HAS_DRIVER(TMC26X)
+ #define HAS_TMC26X 1
+#endif
//
-// Stretching 'drivers.h' to include LPC/SAMD51 SD options
+// L64XX Stepper Drivers
//
-#define _SDCARD_LCD 1
-#define _SDCARD_ONBOARD 2
-#define _SDCARD_CUSTOM_CABLE 3
-#define _SDCARD_ID(V) _CAT(_SDCARD_, V)
-#define SD_CONNECTION_IS(V) (_SDCARD_ID(SDCARD_CONNECTION) == _SDCARD_ID(V))
#if HAS_DRIVER(L6470) || HAS_DRIVER(L6474) || HAS_DRIVER(L6480) || HAS_DRIVER(POWERSTEP01)
#define HAS_L64XX 1
diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h
index f58ace770..5208b3e1b 100644
--- a/Marlin/src/core/language.h
+++ b/Marlin/src/core/language.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -39,7 +39,7 @@
//
// ==> ALWAYS TRY TO COMPILE MARLIN WITH/WITHOUT "ULTIPANEL" / "ULTRA_LCD" / "SDSUPPORT" #define IN "Configuration.h"
// ==> ALSO TRY ALL AVAILABLE LANGUAGE OPTIONS
-// See also http://marlinfw.org/docs/development/lcd_language.html
+// See also https://marlinfw.org/docs/development/lcd_language.html
// Languages
// an Aragonese
@@ -57,6 +57,7 @@
// fr French
// gl Galician
// hr Croatian
+// hu Hungarian
// it Italian
// jp_kana Japanese
// ko_KR Korean (South Korea)
@@ -64,6 +65,7 @@
// pl Polish
// pt Portuguese
// pt_br Portuguese (Brazilian)
+// ro Romanian
// ru Russian
// sk Slovak
// tr Turkish
@@ -80,18 +82,16 @@
#ifdef CUSTOM_MACHINE_NAME
#undef MACHINE_NAME
#define MACHINE_NAME CUSTOM_MACHINE_NAME
-#else
- #ifdef DEFAULT_MACHINE_NAME
- #undef MACHINE_NAME
- #define MACHINE_NAME DEFAULT_MACHINE_NAME
- #endif
+#elif defined(DEFAULT_MACHINE_NAME)
+ #undef MACHINE_NAME
+ #define MACHINE_NAME DEFAULT_MACHINE_NAME
#endif
#ifndef MACHINE_UUID
#define MACHINE_UUID DEFAULT_MACHINE_UUID
#endif
-#define MARLIN_WEBSITE_URL "http://marlinfw.org"
+#define MARLIN_WEBSITE_URL "https://marlinfw.org"
//#if !defined(STRING_SPLASH_LINE3) && defined(WEBSITE_URL)
// #define STRING_SPLASH_LINE3 WEBSITE_URL
@@ -126,7 +126,7 @@
#define STR_INVALID_E_STEPPER "Invalid E stepper"
#define STR_E_STEPPER_NOT_SPECIFIED "E stepper not specified"
#define STR_INVALID_SOLENOID "Invalid solenoid"
-#define STR_M115_REPORT "FIRMWARE_NAME:Marlin " DETAILED_BUILD_VERSION " SOURCE_CODE_URL:" SOURCE_CODE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID
+#define STR_M115_REPORT "FIRMWARE_NAME:Marlin " DETAILED_BUILD_VERSION " (" __DATE__ " " __TIME__ ") SOURCE_CODE_URL:" SOURCE_CODE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID
#define STR_COUNT_X " Count X:"
#define STR_COUNT_A " Count A:"
#define STR_WATCHDOG_FIRED "Watchdog timeout. Reset required."
@@ -163,7 +163,7 @@
#define STR_ERR_MATERIAL_INDEX "M145 S out of range (0-1)"
#define STR_ERR_M421_PARAMETERS "M421 incorrect parameter usage"
#define STR_ERR_BAD_PLANE_MODE "G5 requires XY plane mode"
-#define STR_ERR_MESH_XY "Mesh point cannot be resolved"
+#define STR_ERR_MESH_XY "Mesh point out of range"
#define STR_ERR_ARC_ARGS "G2/G3 bad parameters"
#define STR_ERR_PROTECTED_PIN "Protected Pin"
#define STR_ERR_M420_FAILED "Failed to enable Bed Leveling"
@@ -185,7 +185,7 @@
#define STR_INVALID_POS_SLOT "Invalid slot. Total: "
#define STR_SD_CANT_OPEN_SUBDIR "Cannot open subdir "
-#define STR_SD_INIT_FAIL "SD init fail"
+#define STR_SD_INIT_FAIL "No SD card"
#define STR_SD_VOL_INIT_FAIL "volume.init failed"
#define STR_SD_OPENROOT_FAIL "openRoot failed"
#define STR_SD_CARD_OK "SD card ok"
@@ -205,7 +205,6 @@
#define STR_ERR_COLD_EXTRUDE_STOP " cold extrusion prevented"
#define STR_ERR_LONG_EXTRUDE_STOP " too long extrusion prevented"
#define STR_ERR_HOTEND_TOO_COLD "Hotend too cold"
-#define STR_ERR_Z_HOMING_SER "Home XY first"
#define STR_ERR_EEPROM_WRITE "Error writing to EEPROM!"
#define STR_FILAMENT_CHANGE_HEAT_LCD "Press button to heat nozzle"
@@ -221,12 +220,10 @@
#define STR_KILL_BUTTON "!! KILL caused by KILL button/pin"
// temperature.cpp strings
-#define STR_PID_AUTOTUNE_PREFIX "PID Autotune"
-#define STR_PID_AUTOTUNE_START STR_PID_AUTOTUNE_PREFIX " start"
-#define STR_PID_AUTOTUNE_FAILED STR_PID_AUTOTUNE_PREFIX " failed!"
-#define STR_PID_BAD_EXTRUDER_NUM STR_PID_AUTOTUNE_FAILED " Bad extruder number"
-#define STR_PID_TEMP_TOO_HIGH STR_PID_AUTOTUNE_FAILED " Temperature too high"
-#define STR_PID_TIMEOUT STR_PID_AUTOTUNE_FAILED " timeout"
+#define STR_PID_AUTOTUNE_START "PID Autotune start"
+#define STR_PID_BAD_EXTRUDER_NUM "PID Autotune failed! Bad extruder number"
+#define STR_PID_TEMP_TOO_HIGH "PID Autotune failed! Temperature too high"
+#define STR_PID_TIMEOUT "PID Autotune failed! timeout"
#define STR_BIAS " bias: "
#define STR_D_COLON " d: "
#define STR_T_MIN " min: "
@@ -237,7 +234,7 @@
#define STR_KP " Kp: "
#define STR_KI " Ki: "
#define STR_KD " Kd: "
-#define STR_PID_AUTOTUNE_FINISHED STR_PID_AUTOTUNE_PREFIX " finished! Put the last Kp, Ki and Kd constants from below into Configuration.h"
+#define STR_PID_AUTOTUNE_FINISHED "PID Autotune finished! Put the last Kp, Ki and Kd constants from below into Configuration.h"
#define STR_PID_DEBUG " PID_DEBUG "
#define STR_PID_DEBUG_INPUT ": Input "
#define STR_PID_DEBUG_OUTPUT " Output "
diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h
index 899baf735..3bd273872 100644
--- a/Marlin/src/core/macros.h
+++ b/Marlin/src/core/macros.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -76,13 +76,6 @@
// Nanoseconds per cycle
#define NANOSECONDS_PER_CYCLE (1000000000.0 / F_CPU)
-// Macros to make sprintf_P read from PROGMEM (AVR extension)
-#ifdef __AVR__
- #define S_FMT "%S"
-#else
- #define S_FMT "%s"
-#endif
-
// Macros to make a string from a macro
#define STRINGIFY_(M) #M
#define STRINGIFY(M) STRINGIFY_(M)
@@ -104,12 +97,15 @@
#define CBI(A,B) (A &= ~(1 << (B)))
#endif
+#define TBI(N,B) (N ^= _BV(B))
+
#define _BV32(b) (1UL << (b))
#define TEST32(n,b) !!((n)&_BV32(b))
#define SBI32(n,b) (n |= _BV32(b))
#define CBI32(n,b) (n &= ~_BV32(b))
+#define TBI32(N,B) (N ^= _BV32(B))
-#define cu(x) ((x)*(x)*(x))
+#define cu(x) ({__typeof__(x) _x = (x); (_x)*(_x)*(_x);})
#define RADIANS(d) ((d)*float(M_PI)/180.0f)
#define DEGREES(r) ((r)*180.0f/float(M_PI))
#define HYPOT2(x,y) (sq(x)+sq(y))
@@ -117,7 +113,7 @@
#define CIRCLE_AREA(R) (float(M_PI) * sq(float(R)))
#define CIRCLE_CIRC(R) (2 * float(M_PI) * float(R))
-#define SIGN(a) ((a>0)-(a<0))
+#define SIGN(a) ({__typeof__(a) _a = (a); (_a>0)-(_a<0);})
#define IS_POWER_OF_2(x) ((x) && !((x) & ((x) - 1)))
// Macros to constrain values
@@ -137,8 +133,6 @@
#else
- // Using GCC extensions, but Travis GCC version does not like it and gives
- // "error: statement-expressions are not allowed outside functions nor in template-argument lists"
#define NOLESS(v, n) \
do{ \
__typeof__(n) _n = (n); \
@@ -276,7 +270,7 @@
#define NEAR(x,y) NEAR_ZERO((x)-(y))
#define RECIPROCAL(x) (NEAR_ZERO(x) ? 0 : (1 / float(x)))
-#define FIXFLOAT(f) (f + (f < 0 ? -0.00005f : 0.00005f))
+#define FIXFLOAT(f) ({__typeof__(f) _f = (f); _f + (_f < 0 ? -0.0000005f : 0.0000005f);})
//
// Maths macros that can be overridden by HAL
@@ -292,12 +286,6 @@
#define FMOD(x, y) fmodf(x, y)
#define HYPOT(x,y) SQRT(HYPOT2(x,y))
-#ifdef TARGET_LPC1768
- #define I2C_ADDRESS(A) ((A) << 1)
-#else
- #define I2C_ADDRESS(A) A
-#endif
-
// Use NUM_ARGS(__VA_ARGS__) to get the number of variadic arguments
#define _NUM_ARGS(_,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT
#define NUM_ARGS(V...) _NUM_ARGS(0,V,26,25,24,23,22,21,20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0)
@@ -495,3 +483,14 @@
#define RREPEAT(N,OP) RREPEAT_S(0,N,OP)
#define RREPEAT2_S(S,N,OP,V...) EVAL1024(_RREPEAT2(S,SUB##S(N),OP,V))
#define RREPEAT2(N,OP,V...) RREPEAT2_S(0,N,OP,V)
+
+// See https://github.com/swansontec/map-macro
+#define MAP_OUT
+#define MAP_END(...)
+#define MAP_GET_END() 0, MAP_END
+#define MAP_NEXT0(test, next, ...) next MAP_OUT
+#define MAP_NEXT1(test, next) MAP_NEXT0 (test, next, 0)
+#define MAP_NEXT(test, next) MAP_NEXT1 (MAP_GET_END test, next)
+#define MAP0(f, x, peek, ...) f(x) MAP_NEXT (peek, MAP1) (f, peek, __VA_ARGS__)
+#define MAP1(f, x, peek, ...) f(x) MAP_NEXT (peek, MAP0) (f, peek, __VA_ARGS__)
+#define MAP(f, ...) EVAL512 (MAP1 (f, __VA_ARGS__, (), 0))
diff --git a/Marlin/src/core/millis_t.h b/Marlin/src/core/millis_t.h
index 39ea17b9f..95bc40e1e 100644
--- a/Marlin/src/core/millis_t.h
+++ b/Marlin/src/core/millis_t.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -25,5 +25,9 @@
typedef uint32_t millis_t;
+#define SEC_TO_MS(N) millis_t((N)*1000UL)
+#define MIN_TO_MS(N) SEC_TO_MS((N)*60UL)
+#define MS_TO_SEC(N) millis_t((N)/1000UL)
+
#define PENDING(NOW,SOON) ((int32_t)(NOW-(SOON))<0)
#define ELAPSED(NOW,SOON) (!PENDING(NOW,SOON))
diff --git a/Marlin/src/core/multi_language.h b/Marlin/src/core/multi_language.h
index 98020b1e8..5852c439a 100644
--- a/Marlin/src/core/multi_language.h
+++ b/Marlin/src/core/multi_language.h
@@ -16,13 +16,13 @@
* GNU General Public License for more details. *
* *
* To view a copy of the GNU General Public License, go to the following *
- * location: . *
+ * location: . *
****************************************************************************/
#pragma once
typedef const char Language_Str[];
-#if defined(LCD_LANGUAGE_5)
+#ifdef LCD_LANGUAGE_5
#define NUM_LANGUAGES 5
#elif defined(LCD_LANGUAGE_4)
#define NUM_LANGUAGES 4
@@ -76,4 +76,8 @@ typedef const char Language_Str[];
#endif
#define GET_TEXT_F(MSG) (const __FlashStringHelper*)GET_TEXT(MSG)
-#define MSG_CONCAT(A,B) pgm_p_pair_t(GET_TEXT(A),GET_TEXT(B))
+#define GET_LANGUAGE_NAME(INDEX) GET_LANG(LCD_LANGUAGE_##INDEX)::LANGUAGE
+
+#define MSG_1_LINE(A) A "\0" "\0"
+#define MSG_2_LINE(A,B) A "\0" B "\0"
+#define MSG_3_LINE(A,B,C) A "\0" B "\0" C
diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp
index 304aa09a8..77854d0f8 100644
--- a/Marlin/src/core/serial.cpp
+++ b/Marlin/src/core/serial.cpp
@@ -16,19 +16,19 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#include "serial.h"
-#include "language.h"
+#include "../inc/MarlinConfig.h"
uint8_t marlin_debug_flags = MARLIN_DEBUG_NONE;
-static const char errormagic[] PROGMEM = "Error:";
-static const char echomagic[] PROGMEM = "echo:";
+static PGMSTR(errormagic, "Error:");
+static PGMSTR(echomagic, "echo:");
-#if NUM_SERIAL > 1
+#if HAS_MULTI_SERIAL
int8_t serial_port_index = 0;
#endif
@@ -42,8 +42,8 @@ void serial_echopair_PGM(PGM_P const s_P, const char *v) { serialprintPGM(s_P)
void serial_echopair_PGM(PGM_P const s_P, char v) { serialprintPGM(s_P); SERIAL_CHAR(v); }
void serial_echopair_PGM(PGM_P const s_P, int v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
void serial_echopair_PGM(PGM_P const s_P, long v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
-void serial_echopair_PGM(PGM_P const s_P, float v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
-void serial_echopair_PGM(PGM_P const s_P, double v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
+void serial_echopair_PGM(PGM_P const s_P, float v) { serialprintPGM(s_P); SERIAL_DECIMAL(v); }
+void serial_echopair_PGM(PGM_P const s_P, double v) { serialprintPGM(s_P); SERIAL_DECIMAL(v); }
void serial_echopair_PGM(PGM_P const s_P, unsigned int v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
void serial_echopair_PGM(PGM_P const s_P, unsigned long v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h
index 812ff5471..fc830736a 100644
--- a/Marlin/src/core/serial.h
+++ b/Marlin/src/core/serial.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -47,14 +47,20 @@ extern uint8_t marlin_debug_flags;
#define DEBUGGING(F) (marlin_debug_flags & (MARLIN_DEBUG_## F))
#define SERIAL_BOTH 0x7F
-#if NUM_SERIAL > 1
+#if HAS_MULTI_SERIAL
extern int8_t serial_port_index;
#define _PORT_REDIRECT(n,p) REMEMBER(n,serial_port_index,p)
#define _PORT_RESTORE(n) RESTORE(n)
- #define SERIAL_OUT(WHAT, V...) do{ \
- if (!serial_port_index || serial_port_index == SERIAL_BOTH) (void)MYSERIAL0.WHAT(V); \
- if ( serial_port_index) (void)MYSERIAL1.WHAT(V); \
- }while(0)
+
+ #ifdef SERIAL_CATCHALL
+ #define SERIAL_OUT(WHAT, V...) (void)CAT(MYSERIAL,SERIAL_CATCHALL).WHAT(V)
+ #else
+ #define SERIAL_OUT(WHAT, V...) do{ \
+ if (!serial_port_index || serial_port_index == SERIAL_BOTH) (void)MYSERIAL0.WHAT(V); \
+ if ( serial_port_index) (void)MYSERIAL1.WHAT(V); \
+ }while(0)
+ #endif
+
#define SERIAL_ASSERT(P) if(serial_port_index!=(P)){ debugger(); }
#else
#define _PORT_REDIRECT(n,p) NOOP
@@ -184,7 +190,13 @@ extern uint8_t marlin_debug_flags;
#define _SELP_21(a,b,V...) do{ _SEP_2(a,b); _SELP_19(V); }while(0)
#define _SELP_22(a,b,V...) do{ _SEP_2(a,b); _SELP_20(V); }while(0)
#define _SELP_23(a,b,V...) do{ _SEP_2(a,b); _SELP_21(V); }while(0)
-#define _SELP_24(a,b,V...) do{ _SEP_2(a,b); _SELP_22(V); }while(0) // Eat two args, pass the rest up
+#define _SELP_24(a,b,V...) do{ _SEP_2(a,b); _SELP_22(V); }while(0)
+#define _SELP_25(a,b,V...) do{ _SEP_2(a,b); _SELP_23(V); }while(0)
+#define _SELP_26(a,b,V...) do{ _SEP_2(a,b); _SELP_24(V); }while(0)
+#define _SELP_27(a,b,V...) do{ _SEP_2(a,b); _SELP_25(V); }while(0)
+#define _SELP_28(a,b,V...) do{ _SEP_2(a,b); _SELP_26(V); }while(0)
+#define _SELP_29(a,b,V...) do{ _SEP_2(a,b); _SELP_27(V); }while(0)
+#define _SELP_30(a,b,V...) do{ _SEP_2(a,b); _SELP_28(V); }while(0) // Eat two args, pass the rest up
#define SERIAL_ECHOLNPAIR(V...) _SELP_N(NUM_ARGS(V),V)
@@ -214,7 +226,13 @@ extern uint8_t marlin_debug_flags;
#define _SELP_21_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_19_P(V); }while(0)
#define _SELP_22_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_20_P(V); }while(0)
#define _SELP_23_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_21_P(V); }while(0)
-#define _SELP_24_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_22_P(V); }while(0) // Eat two args, pass the rest up
+#define _SELP_24_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_22_P(V); }while(0)
+#define _SELP_25_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_23_P(V); }while(0)
+#define _SELP_26_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_24_P(V); }while(0)
+#define _SELP_27_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_25_P(V); }while(0)
+#define _SELP_28_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_26_P(V); }while(0)
+#define _SELP_29_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_27_P(V); }while(0)
+#define _SELP_30_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_28_P(V); }while(0) // Eat two args, pass the rest up
#define SERIAL_ECHOLNPAIR_P(V...) _SELP_N_P(NUM_ARGS(V),V)
@@ -245,10 +263,11 @@ extern uint8_t marlin_debug_flags;
#define SERIAL_ECHOLIST(pre,V...) do{ SERIAL_ECHOPGM(pre); _SLST_N(NUM_ARGS(V),V); }while(0)
#define SERIAL_ECHOLIST_N(N,V...) _SLST_N(N,LIST_N(N,V))
-#define SERIAL_ECHO_P(P) (serialprintPGM(P))
+#define SERIAL_ECHOPGM_P(P) (serialprintPGM(P))
+#define SERIAL_ECHOLNPGM_P(P) (serialprintPGM(P "\n"))
-#define SERIAL_ECHOPGM(S) (SERIAL_ECHO_P(PSTR(S)))
-#define SERIAL_ECHOLNPGM(S) (SERIAL_ECHO_P(PSTR(S "\n")))
+#define SERIAL_ECHOPGM(S) (serialprintPGM(PSTR(S)))
+#define SERIAL_ECHOLNPGM(S) (serialprintPGM(PSTR(S "\n")))
#define SERIAL_ECHOPAIR_F_P(P,V...) do{ serialprintPGM(P); SERIAL_ECHO_F(V); }while(0)
#define SERIAL_ECHOLNPAIR_F_P(V...) do{ SERIAL_ECHOPAIR_F_P(V); SERIAL_EOL(); }while(0)
@@ -267,6 +286,12 @@ extern uint8_t marlin_debug_flags;
#define SERIAL_ECHO_TERNARY(TF, PRE, ON, OFF, POST) serial_ternary(TF, PSTR(PRE), PSTR(ON), PSTR(OFF), PSTR(POST))
+#if SERIAL_FLOAT_PRECISION
+ #define SERIAL_DECIMAL(V) SERIAL_PRINT(V, SERIAL_FLOAT_PRECISION)
+#else
+ #define SERIAL_DECIMAL(V) SERIAL_ECHO(V)
+#endif
+
//
// Functions for serial printing from PROGMEM. (Saves loads of SRAM.)
//
diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h
index 6bcd4bd48..a5b78caab 100644
--- a/Marlin/src/core/types.h
+++ b/Marlin/src/core/types.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -501,4 +501,4 @@ struct XYZEval {
#undef FI
const xyze_char_t axis_codes { 'X', 'Y', 'Z', 'E' };
-#define XYZ_CHAR(A) ('X' + char(A))
+#define XYZ_CHAR(A) ((char)('X' + A))
diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp
index 5e159af58..295657fa6 100644
--- a/Marlin/src/core/utility.cpp
+++ b/Marlin/src/core/utility.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -57,21 +57,21 @@ void safe_delay(millis_t ms) {
void log_machine_info() {
SERIAL_ECHOLNPGM("Machine Type: "
- TERN(DELTA, "Delta", "")
- TERN(IS_SCARA, "SCARA", "")
- TERN(IS_CORE, "Core", "")
- TERN(IS_CARTESIAN, "Cartesian", "")
+ TERN_(DELTA, "Delta")
+ TERN_(IS_SCARA, "SCARA")
+ TERN_(IS_CORE, "Core")
+ TERN_(IS_CARTESIAN, "Cartesian")
);
SERIAL_ECHOLNPGM("Probe: "
- TERN(PROBE_MANUALLY, "PROBE_MANUALLY", "")
- TERN(NOZZLE_AS_PROBE, "NOZZLE_AS_PROBE", "")
- TERN(FIX_MOUNTED_PROBE, "FIX_MOUNTED_PROBE", "")
- TERN(HAS_Z_SERVO_PROBE, TERN(BLTOUCH, "BLTOUCH", "SERVO PROBE"), "")
- TERN(TOUCH_MI_PROBE, "TOUCH_MI_PROBE", "")
- TERN(Z_PROBE_SLED, "Z_PROBE_SLED", "")
- TERN(Z_PROBE_ALLEN_KEY, "Z_PROBE_ALLEN_KEY", "")
- TERN(SOLENOID_PROBE, "SOLENOID_PROBE", "")
+ TERN_(PROBE_MANUALLY, "PROBE_MANUALLY")
+ TERN_(NOZZLE_AS_PROBE, "NOZZLE_AS_PROBE")
+ TERN_(FIX_MOUNTED_PROBE, "FIX_MOUNTED_PROBE")
+ TERN_(HAS_Z_SERVO_PROBE, TERN(BLTOUCH, "BLTOUCH", "SERVO PROBE"))
+ TERN_(TOUCH_MI_PROBE, "TOUCH_MI_PROBE")
+ TERN_(Z_PROBE_SLED, "Z_PROBE_SLED")
+ TERN_(Z_PROBE_ALLEN_KEY, "Z_PROBE_ALLEN_KEY")
+ TERN_(SOLENOID_PROBE, "SOLENOID_PROBE")
TERN(PROBE_SELECTED, "", "NONE")
);
@@ -108,10 +108,10 @@ void safe_delay(millis_t ms) {
#if HAS_ABL_OR_UBL
SERIAL_ECHOPGM("Auto Bed Leveling: "
- TERN(AUTO_BED_LEVELING_LINEAR, "LINEAR", "")
- TERN(AUTO_BED_LEVELING_BILINEAR, "BILINEAR", "")
- TERN(AUTO_BED_LEVELING_3POINT, "3POINT", "")
- TERN(AUTO_BED_LEVELING_UBL, "UBL", "")
+ TERN_(AUTO_BED_LEVELING_LINEAR, "LINEAR")
+ TERN_(AUTO_BED_LEVELING_BILINEAR, "BILINEAR")
+ TERN_(AUTO_BED_LEVELING_3POINT, "3POINT")
+ TERN_(AUTO_BED_LEVELING_UBL, "UBL")
);
if (planner.leveling_active) {
@@ -123,10 +123,10 @@ void safe_delay(millis_t ms) {
#if ABL_PLANAR
SERIAL_ECHOPGM("ABL Adjustment X");
LOOP_XYZ(a) {
- float v = planner.get_axis_position_mm(AxisEnum(a)) - current_position[a];
+ const float v = planner.get_axis_position_mm(AxisEnum(a)) - current_position[a];
SERIAL_CHAR(' ', XYZ_CHAR(a));
if (v > 0) SERIAL_CHAR('+');
- SERIAL_ECHO(v);
+ SERIAL_DECIMAL(v);
}
#else
#if ENABLED(AUTO_BED_LEVELING_UBL)
diff --git a/Marlin/src/core/utility.h b/Marlin/src/core/utility.h
index 0c2e91d31..0481ffc02 100644
--- a/Marlin/src/core/utility.h
+++ b/Marlin/src/core/utility.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/babystep.cpp b/Marlin/src/feature/babystep.cpp
index 5d2dc47be..41d0a9cb1 100644
--- a/Marlin/src/feature/babystep.cpp
+++ b/Marlin/src/feature/babystep.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -54,66 +54,13 @@ void Babystep::add_mm(const AxisEnum axis, const float &mm) {
}
void Babystep::add_steps(const AxisEnum axis, const int16_t distance) {
-
if (DISABLED(BABYSTEP_WITHOUT_HOMING) && !TEST(axis_known_position, axis)) return;
accum += distance; // Count up babysteps for the UI
- #if ENABLED(BABYSTEP_DISPLAY_TOTAL)
- axis_total[BS_TOTAL_IND(axis)] += distance;
- #endif
-
- #if ENABLED(BABYSTEP_ALWAYS_AVAILABLE)
- #define BSA_ENABLE(AXIS) do{ switch (AXIS) { case X_AXIS: ENABLE_AXIS_X(); break; case Y_AXIS: ENABLE_AXIS_Y(); break; case Z_AXIS: ENABLE_AXIS_Z(); break; default: break; } }while(0)
- #else
- #define BSA_ENABLE(AXIS) NOOP
- #endif
-
- #if IS_CORE
- #if ENABLED(BABYSTEP_XY)
- switch (axis) {
- case CORE_AXIS_1: // X on CoreXY and CoreXZ, Y on CoreYZ
- BSA_ENABLE(CORE_AXIS_1);
- BSA_ENABLE(CORE_AXIS_2);
- steps[CORE_AXIS_1] += distance * 2;
- steps[CORE_AXIS_2] += distance * 2;
- break;
- case CORE_AXIS_2: // Y on CoreXY, Z on CoreXZ and CoreYZ
- BSA_ENABLE(CORE_AXIS_1);
- BSA_ENABLE(CORE_AXIS_2);
- steps[CORE_AXIS_1] += CORESIGN(distance * 2);
- steps[CORE_AXIS_2] -= CORESIGN(distance * 2);
- break;
- case NORMAL_AXIS: // Z on CoreXY, Y on CoreXZ, X on CoreYZ
- default:
- BSA_ENABLE(NORMAL_AXIS);
- steps[NORMAL_AXIS] += distance;
- break;
- }
- #elif CORE_IS_XZ || CORE_IS_YZ
- // Only Z stepping needs to be handled here
- BSA_ENABLE(CORE_AXIS_1);
- BSA_ENABLE(CORE_AXIS_2);
- steps[CORE_AXIS_1] += CORESIGN(distance * 2);
- steps[CORE_AXIS_2] -= CORESIGN(distance * 2);
- #else
- BSA_ENABLE(Z_AXIS);
- steps[Z_AXIS] += distance;
- #endif
- #else
- #if ENABLED(BABYSTEP_XY)
- BSA_ENABLE(axis);
- #else
- BSA_ENABLE(Z_AXIS);
- #endif
- steps[BS_AXIS_IND(axis)] += distance;
- #endif
- #if ENABLED(BABYSTEP_ALWAYS_AVAILABLE)
- gcode.reset_stepper_timeout();
- #endif
-
- #if ENABLED(INTEGRATED_BABYSTEPPING)
- if (has_steps()) stepper.initiateBabystepping();
- #endif
+ steps[BS_AXIS_IND(axis)] += distance;
+ TERN_(BABYSTEP_DISPLAY_TOTAL, axis_total[BS_TOTAL_IND(axis)] += distance);
+ TERN_(BABYSTEP_ALWAYS_AVAILABLE, gcode.reset_stepper_timeout());
+ TERN_(INTEGRATED_BABYSTEPPING, if (has_steps()) stepper.initiateBabystepping());
}
#endif // BABYSTEPPING
diff --git a/Marlin/src/feature/babystep.h b/Marlin/src/feature/babystep.h
index 287664502..f85e5909c 100644
--- a/Marlin/src/feature/babystep.h
+++ b/Marlin/src/feature/babystep.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -55,11 +55,8 @@ public:
#if ENABLED(BABYSTEP_DISPLAY_TOTAL)
static int16_t axis_total[BS_TOTAL_IND(Z_AXIS) + 1]; // Total babysteps since G28
static inline void reset_total(const AxisEnum axis) {
- if (true
- #if ENABLED(BABYSTEP_XY)
- && axis == Z_AXIS
- #endif
- ) axis_total[BS_TOTAL_IND(axis)] = 0;
+ if (TERN1(BABYSTEP_XY, axis == Z_AXIS))
+ axis_total[BS_TOTAL_IND(axis)] = 0;
}
#endif
diff --git a/Marlin/src/feature/backlash.cpp b/Marlin/src/feature/backlash.cpp
index bc33ae318..867e9cdd2 100644
--- a/Marlin/src/feature/backlash.cpp
+++ b/Marlin/src/feature/backlash.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/feature/backlash.h b/Marlin/src/feature/backlash.h
index 20666c540..8d00570f9 100644
--- a/Marlin/src/feature/backlash.h
+++ b/Marlin/src/feature/backlash.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -55,26 +55,16 @@ public:
static inline float get_measurement(const AxisEnum a) {
// Return the measurement averaged over all readings
- return (
- #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING)
- measured_count[a] > 0 ? measured_mm[a] / measured_count[a] :
- #endif
- 0
+ return TERN(MEASURE_BACKLASH_WHEN_PROBING
+ , measured_count[a] > 0 ? measured_mm[a] / measured_count[a] : 0
+ , 0
);
- #if DISABLED(MEASURE_BACKLASH_WHEN_PROBING)
- UNUSED(a);
- #endif
+ TERN(MEASURE_BACKLASH_WHEN_PROBING,,UNUSED(a));
}
static inline bool has_measurement(const AxisEnum a) {
- return (false
- #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING)
- || (measured_count[a] > 0)
- #endif
- );
- #if DISABLED(MEASURE_BACKLASH_WHEN_PROBING)
- UNUSED(a);
- #endif
+ return TERN0(MEASURE_BACKLASH_WHEN_PROBING, measured_count[a] > 0);
+ TERN(MEASURE_BACKLASH_WHEN_PROBING,,UNUSED(a));
}
static inline bool has_any_measurement() {
diff --git a/Marlin/src/feature/baricuda.cpp b/Marlin/src/feature/baricuda.cpp
index 389934854..596891707 100644
--- a/Marlin/src/feature/baricuda.cpp
+++ b/Marlin/src/feature/baricuda.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/feature/baricuda.h b/Marlin/src/feature/baricuda.h
index 567d2253e..f28d07d64 100644
--- a/Marlin/src/feature/baricuda.h
+++ b/Marlin/src/feature/baricuda.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/bedlevel/abl/abl.cpp b/Marlin/src/feature/bedlevel/abl/abl.cpp
index 33c9cbdfd..a585c1e15 100644
--- a/Marlin/src/feature/bedlevel/abl/abl.cpp
+++ b/Marlin/src/feature/bedlevel/abl/abl.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -74,9 +74,7 @@ static void extrapolate_one_point(const uint8_t x, const uint8_t y, const int8_t
// Take the average instead of the median
z_values[x][y] = (a + b + c) / 3.0;
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(x, y, z_values[x][y]);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y]));
// Median is robust (ignores outliers).
// z_values[x][y] = (a < b) ? ((b < c) ? b : (c < a) ? a : c)
@@ -241,9 +239,7 @@ void print_bilinear_leveling_grid() {
// Refresh after other values have been updated
void refresh_bed_level() {
bilinear_grid_factor = bilinear_grid_spacing.reciprocal();
- #if ENABLED(ABL_BILINEAR_SUBDIVISION)
- bed_level_virt_interpolate();
- #endif
+ TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate());
}
#if ENABLED(ABL_BILINEAR_SUBDIVISION)
diff --git a/Marlin/src/feature/bedlevel/abl/abl.h b/Marlin/src/feature/bedlevel/abl/abl.h
index 312dc0db8..bbe2411dc 100644
--- a/Marlin/src/feature/bedlevel/abl/abl.h
+++ b/Marlin/src/feature/bedlevel/abl/abl.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/bedlevel/bedlevel.cpp b/Marlin/src/feature/bedlevel/bedlevel.cpp
index 63493712a..3e9225b7f 100644
--- a/Marlin/src/feature/bedlevel/bedlevel.cpp
+++ b/Marlin/src/feature/bedlevel/bedlevel.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -47,17 +47,9 @@
#endif
bool leveling_is_valid() {
- return
- #if ENABLED(MESH_BED_LEVELING)
- mbl.has_mesh()
- #elif ENABLED(AUTO_BED_LEVELING_BILINEAR)
- !!bilinear_grid_spacing.x
- #elif ENABLED(AUTO_BED_LEVELING_UBL)
- ubl.mesh_is_valid()
- #else // 3POINT, LINEAR
- true
- #endif
- ;
+ return TERN1(MESH_BED_LEVELING, mbl.has_mesh())
+ && TERN1(AUTO_BED_LEVELING_BILINEAR, !!bilinear_grid_spacing.x)
+ && TERN1(AUTO_BED_LEVELING_UBL, ubl.mesh_is_valid());
}
/**
@@ -69,11 +61,7 @@ bool leveling_is_valid() {
*/
void set_bed_leveling_enabled(const bool enable/*=true*/) {
- #if ENABLED(AUTO_BED_LEVELING_BILINEAR)
- const bool can_change = (!enable || leveling_is_valid());
- #else
- constexpr bool can_change = true;
- #endif
+ const bool can_change = TERN1(AUTO_BED_LEVELING_BILINEAR, !enable || leveling_is_valid());
if (can_change && enable != planner.leveling_active) {
@@ -145,9 +133,7 @@ void reset_bed_level() {
bilinear_grid_spacing.reset();
GRID_LOOP(x, y) {
z_values[x][y] = NAN;
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(x, y, 0);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, 0));
}
#elif ABL_PLANAR
planner.bed_level_matrix.set_to_identity();
@@ -245,9 +231,7 @@ void reset_bed_level() {
current_position = pos;
- #if ENABLED(LCD_BED_LEVELING)
- ui.wait_for_move = false;
- #endif
+ TERN_(LCD_BED_LEVELING, ui.wait_for_move = false);
}
#endif
diff --git a/Marlin/src/feature/bedlevel/bedlevel.h b/Marlin/src/feature/bedlevel/bedlevel.h
index fd3ed82e5..995e9d0db 100644
--- a/Marlin/src/feature/bedlevel/bedlevel.h
+++ b/Marlin/src/feature/bedlevel/bedlevel.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp
index 7439c3fcd..1200c2a1b 100644
--- a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp
+++ b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h
index 3a1cbaccb..ade7a9314 100644
--- a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h
+++ b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp
index 8ef2ad564..63b448234 100644
--- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp
+++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -49,14 +49,13 @@
void unified_bed_leveling::report_current_mesh() {
if (!leveling_is_valid()) return;
SERIAL_ECHO_MSG(" G29 I99");
- LOOP_L_N(x, GRID_MAX_POINTS_X)
- for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++)
- if (!isnan(z_values[x][y])) {
- SERIAL_ECHO_START();
- SERIAL_ECHOPAIR(" M421 I", int(x), " J", int(y));
- SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, z_values[x][y], 4);
- serial_delay(75); // Prevent Printrun from exploding
- }
+ GRID_LOOP(x, y)
+ if (!isnan(z_values[x][y])) {
+ SERIAL_ECHO_START();
+ SERIAL_ECHOPAIR(" M421 I", int(x), " J", int(y));
+ SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, z_values[x][y], 4);
+ serial_delay(75); // Prevent Printrun from exploding
+ }
}
void unified_bed_leveling::report_state() {
@@ -85,11 +84,7 @@
_GRIDPOS(Y, 12), _GRIDPOS(Y, 13), _GRIDPOS(Y, 14), _GRIDPOS(Y, 15)
);
- #if HAS_LCD_MENU
- bool unified_bed_leveling::lcd_map_control = false;
- #endif
-
- volatile int unified_bed_leveling::encoder_diff;
+ volatile int16_t unified_bed_leveling::encoder_diff;
unified_bed_leveling::unified_bed_leveling() {
reset();
@@ -114,9 +109,7 @@
void unified_bed_leveling::set_all_mesh_points_to_value(const float value) {
GRID_LOOP(x, y) {
z_values[x][y] = value;
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(x, y, value);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, value));
}
}
@@ -209,7 +202,7 @@
if (human) SERIAL_CHAR(is_current ? ']' : ' ');
SERIAL_FLUSHTX();
- idle();
+ idle_no_sleep();
}
if (!lcd) SERIAL_EOL();
diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.h b/Marlin/src/feature/bedlevel/ubl/ubl.h
index 9e227f02d..9ac9de180 100644
--- a/Marlin/src/feature/bedlevel/ubl/ubl.h
+++ b/Marlin/src/feature/bedlevel/ubl/ubl.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -111,9 +111,12 @@ class unified_bed_leveling {
#if HAS_LCD_MENU
static bool lcd_map_control;
+ static void steppers_were_disabled();
+ #else
+ static inline void steppers_were_disabled() {}
#endif
- static volatile int encoder_diff; // Volatile because it's changed at interrupt time.
+ static volatile int16_t encoder_diff; // Volatile because buttons may changed it at interrupt time
unified_bed_leveling();
diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp
index 217d89454..f8219ac7e 100644
--- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp
+++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -38,7 +38,7 @@
#include "../../../gcode/gcode.h"
#include "../../../libs/least_squares_fit.h"
- #if HOTENDS > 1
+ #if HAS_MULTI_HOTEND
#include "../../../module/tool_change.h"
#endif
@@ -54,7 +54,18 @@
#define UBL_G29_P31
#if HAS_LCD_MENU
- void _lcd_ubl_output_map_lcd();
+
+ bool unified_bed_leveling::lcd_map_control = false;
+
+ void unified_bed_leveling::steppers_were_disabled() {
+ if (lcd_map_control) {
+ lcd_map_control = false;
+ ui.defer_status_screen(false);
+ }
+ }
+
+ void ubl_map_screen();
+
#endif
#define SIZE_OF_LITTLE_RAISE 1
@@ -305,17 +316,13 @@
const int8_t p_val = parser.intval('P', -1);
const bool may_move = p_val == 1 || p_val == 2 || p_val == 4 || parser.seen('J');
- #if HOTENDS > 1
- const uint8_t old_tool_index = active_extruder;
- #endif
+ TERN_(HAS_MULTI_HOTEND, const uint8_t old_tool_index = active_extruder);
// Check for commands that require the printer to be homed
if (may_move) {
planner.synchronize();
if (axes_need_homing()) gcode.home_all_axes();
- #if HOTENDS > 1
- if (active_extruder != 0) tool_change(0);
- #endif
+ TERN_(HAS_MULTI_HOTEND, if (active_extruder) tool_change(0));
}
// Invalidate Mesh Points. This command is a little bit asymmetrical because
@@ -340,9 +347,7 @@
break; // No more invalid Mesh Points to populate
}
z_values[cpos.x][cpos.y] = NAN;
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(cpos, 0.0f);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(cpos, 0.0f));
cnt++;
}
}
@@ -369,9 +374,7 @@
const float p1 = 0.5f * (GRID_MAX_POINTS_X) - x,
p2 = 0.5f * (GRID_MAX_POINTS_Y) - y;
z_values[x][y] += 2.0f * HYPOT(p1, p2);
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(x, y, z_values[x][y]);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y]));
}
break;
@@ -392,9 +395,7 @@
for (uint8_t x = (GRID_MAX_POINTS_X) / 3; x < 2 * (GRID_MAX_POINTS_X) / 3; x++) // Create a rectangular raised area in
for (uint8_t y = (GRID_MAX_POINTS_Y) / 3; y < 2 * (GRID_MAX_POINTS_Y) / 3; y++) { // the center of the bed
z_values[x][y] += parser.seen('C') ? g29_constant : 9.99f;
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(x, y, z_values[x][y]);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y]));
}
break;
}
@@ -403,17 +404,12 @@
#if HAS_BED_PROBE
if (parser.seen('J')) {
- if (g29_grid_size) { // if not 0 it is a normal n x n grid being probed
- save_ubl_active_state_and_disable();
- tilt_mesh_based_on_probed_grid(false /* false says to do normal grid probing */ );
- restore_ubl_active_state_and_leave();
- }
- else { // grid_size == 0 : A 3-Point leveling has been requested
- save_ubl_active_state_and_disable();
- tilt_mesh_based_on_probed_grid(true /* true says to do 3-Point leveling */ );
- restore_ubl_active_state_and_leave();
- }
- do_blocking_move_to_xy(0.5f * (MESH_MAX_X - (MESH_MIN_X)), 0.5f * (MESH_MAX_Y - (MESH_MIN_Y)));
+ save_ubl_active_state_and_disable();
+ tilt_mesh_based_on_probed_grid(g29_grid_size == 0); // Zero size does 3-Point
+ restore_ubl_active_state_and_leave();
+ #if ENABLED(UBL_G29_J_RECENTER)
+ do_blocking_move_to_xy(0.5f * ((MESH_MIN_X) + (MESH_MAX_X)), 0.5f * ((MESH_MIN_Y) + (MESH_MAX_Y)));
+ #endif
report_current_position();
probe_deployed = true;
}
@@ -448,11 +444,11 @@
if (g29_verbose_level > 1) {
SERIAL_ECHOPAIR("Probing around (", g29_pos.x);
SERIAL_CHAR(',');
- SERIAL_ECHO(g29_pos.y);
+ SERIAL_DECIMAL(g29_pos.y);
SERIAL_ECHOLNPGM(").\n");
}
- const xy_pos_t near = g29_pos + probe.offset_xy;
- probe_entire_mesh(near, parser.seen('T'), parser.seen('E'), parser.seen('U'));
+ const xy_pos_t near_probe_xy = g29_pos + probe.offset_xy;
+ probe_entire_mesh(near_probe_xy, parser.seen('T'), parser.seen('E'), parser.seen('U'));
report_current_position();
probe_deployed = true;
@@ -466,7 +462,7 @@
// Manually Probe Mesh in areas that can't be reached by the probe
//
SERIAL_ECHOLNPGM("Manually probing unreachable points.");
- do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES);
+ do_z_clearance(Z_CLEARANCE_BETWEEN_PROBES);
if (parser.seen('C') && !xy_seen) {
@@ -488,7 +484,7 @@
}
if (parser.seen('B')) {
- g29_card_thickness = parser.has_value() ? parser.value_float() : measure_business_card_thickness((float) Z_CLEARANCE_BETWEEN_PROBES);
+ g29_card_thickness = parser.has_value() ? parser.value_float() : measure_business_card_thickness(float(Z_CLEARANCE_BETWEEN_PROBES));
if (ABS(g29_card_thickness) > 1.5f) {
SERIAL_ECHOLNPGM("?Error in Business Card measurement.");
return;
@@ -540,9 +536,7 @@
}
else {
z_values[cpos.x][cpos.y] = g29_constant;
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(cpos, g29_constant);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(cpos, g29_constant));
}
}
}
@@ -683,9 +677,7 @@
UNUSED(probe_deployed);
#endif
- #if HOTENDS > 1
- tool_change(old_tool_index);
- #endif
+ TERN_(HAS_MULTI_HOTEND, tool_change(old_tool_index));
return;
}
@@ -718,9 +710,7 @@
GRID_LOOP(x, y)
if (!isnan(z_values[x][y])) {
z_values[x][y] -= mean + value;
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(x, y, z_values[x][y]);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y]));
}
}
@@ -728,9 +718,7 @@
GRID_LOOP(x, y)
if (!isnan(z_values[x][y])) {
z_values[x][y] += g29_constant;
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(x, y, z_values[x][y]);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y]));
}
}
@@ -742,9 +730,7 @@
void unified_bed_leveling::probe_entire_mesh(const xy_pos_t &near, const bool do_ubl_mesh_map, const bool stow_probe, const bool do_furthest) {
probe.deploy(); // Deploy before ui.capture() to allow for PAUSE_BEFORE_DEPLOY_STOW
- #if HAS_LCD_MENU
- ui.capture();
- #endif
+ TERN_(HAS_LCD_MENU, ui.capture());
save_ubl_active_state_and_disable(); // No bed level correction so only raw data is obtained
uint8_t count = GRID_MAX_POINTS;
@@ -755,9 +741,7 @@
const int point_num = (GRID_MAX_POINTS) - count + 1;
SERIAL_ECHOLNPAIR("\nProbing mesh point ", point_num, "/", int(GRID_MAX_POINTS), ".\n");
- #if HAS_DISPLAY
- ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), point_num, int(GRID_MAX_POINTS));
- #endif
+ TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), point_num, int(GRID_MAX_POINTS)));
#if HAS_LCD_MENU
if (ui.button_pressed()) {
@@ -776,12 +760,14 @@
: find_closest_mesh_point_of_type(INVALID, near, true);
if (best.pos.x >= 0) { // mesh point found and is reachable by probe
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(best.pos, ExtUI::PROBE_START));
const float measured_z = probe.probe_at_point(
best.meshpos(),
stow_probe ? PROBE_PT_STOW : PROBE_PT_RAISE, g29_verbose_level
);
z_values[best.pos.x][best.pos.y] = measured_z;
#if ENABLED(EXTENSIBLE_UI)
+ ExtUI::onMeshUpdate(best.pos, ExtUI::PROBE_FINISH);
ExtUI::onMeshUpdate(best.pos, measured_z);
#endif
}
@@ -789,17 +775,12 @@
} while (best.pos.x >= 0 && --count);
- #if HAS_LCD_MENU
- ui.release();
- #endif
- probe.stow(); // Release UI during stow to allow for PAUSE_BEFORE_DEPLOY_STOW
- #if HAS_LCD_MENU
- ui.capture();
- #endif
+ // Release UI during stow to allow for PAUSE_BEFORE_DEPLOY_STOW
+ TERN_(HAS_LCD_MENU, ui.release());
+ probe.stow();
+ TERN_(HAS_LCD_MENU, ui.capture());
- #ifdef Z_AFTER_PROBING
- probe.move_z_after_probing();
- #endif
+ probe.move_z_after_probing();
restore_ubl_active_state_and_leave();
@@ -817,11 +798,11 @@
bool click_and_hold(const clickFunc_t func=nullptr) {
if (ui.button_pressed()) {
- ui.quick_feedback(false); // Preserve button state for click-and-hold
+ ui.quick_feedback(false); // Preserve button state for click-and-hold
const millis_t nxt = millis() + 1500UL;
- while (ui.button_pressed()) { // Loop while the encoder is pressed. Uses hardware flag!
- idle(); // idle, of course
- if (ELAPSED(millis(), nxt)) { // After 1.5 seconds
+ while (ui.button_pressed()) { // Loop while the encoder is pressed. Uses hardware flag!
+ idle(); // idle, of course
+ if (ELAPSED(millis(), nxt)) { // After 1.5 seconds
ui.quick_feedback();
if (func) (*func)();
ui.wait_for_release();
@@ -854,9 +835,7 @@
static void echo_and_take_a_measurement() { SERIAL_ECHOLNPGM(" and take a measurement."); }
float unified_bed_leveling::measure_business_card_thickness(float in_height) {
- #if HAS_LCD_MENU
- ui.capture();
- #endif
+ ui.capture();
save_ubl_active_state_and_disable(); // Disable bed level correction for probing
do_blocking_move_to(0.5f * (MESH_MAX_X - (MESH_MIN_X)), 0.5f * (MESH_MAX_Y - (MESH_MIN_Y)), in_height);
@@ -877,7 +856,6 @@
echo_and_take_a_measurement();
const float z2 = measure_point_with_encoder();
-
do_blocking_move_to_z(current_position.z + Z_CLEARANCE_BETWEEN_PROBES);
const float thickness = ABS(z1 - z2);
@@ -887,17 +865,13 @@
SERIAL_ECHOLNPGM("mm thick.");
}
- ui.release();
-
restore_ubl_active_state_and_leave();
return thickness;
}
void unified_bed_leveling::manually_probe_remaining_mesh(const xy_pos_t &pos, const float &z_clearance, const float &thick, const bool do_ubl_mesh_map) {
- #if HAS_LCD_MENU
- ui.capture();
- #endif
+ ui.capture();
save_ubl_active_state_and_disable(); // No bed level correction so only raw data is obtained
do_blocking_move_to_xy_z(current_position, z_clearance);
@@ -922,12 +896,10 @@
LCD_MESSAGEPGM(MSG_UBL_MOVING_TO_NEXT);
do_blocking_move_to(ppos);
- do_blocking_move_to_z(z_clearance);
+ do_z_clearance(z_clearance);
KEEPALIVE_STATE(PAUSED_FOR_USER);
- #if HAS_LCD_MENU
- ui.capture();
- #endif
+ ui.capture();
if (do_ubl_mesh_map) display_map(g29_map_type); // show user where we're probing
@@ -940,15 +912,12 @@
if (click_and_hold()) {
SERIAL_ECHOLNPGM("\nMesh only partially populated.");
- do_blocking_move_to_z(Z_CLEARANCE_DEPLOY_PROBE);
- ui.release();
+ do_z_clearance(Z_CLEARANCE_DEPLOY_PROBE);
return restore_ubl_active_state_and_leave();
}
z_values[lpos.x][lpos.y] = current_position.z - thick;
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(location, z_values[lpos.x][lpos.y]);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location, z_values[lpos.x][lpos.y]));
if (g29_verbose_level > 2)
SERIAL_ECHOLNPAIR_F("Mesh Point Measured at: ", z_values[lpos.x][lpos.y], 6);
@@ -968,7 +937,7 @@
void abort_fine_tune() {
ui.return_to_status();
- do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES);
+ do_z_clearance(Z_CLEARANCE_BETWEEN_PROBES);
set_message_with_feedback(GET_TEXT(MSG_EDITING_STOPPED));
}
@@ -994,14 +963,11 @@
save_ubl_active_state_and_disable();
LCD_MESSAGEPGM(MSG_UBL_FINE_TUNE_MESH);
- #if HAS_LCD_MENU
- ui.capture(); // Take over control of the LCD encoder
- #endif
- do_blocking_move_to_xy_z(pos, Z_CLEARANCE_BETWEEN_PROBES); // Move to the given XY with probe clearance
+ ui.capture(); // Take over control of the LCD encoder
- #if ENABLED(UBL_MESH_EDIT_MOVES_Z)
- do_blocking_move_to_z(h_offset); // Move Z to the given 'H' offset
- #endif
+ do_blocking_move_to_xy_z(pos, Z_CLEARANCE_BETWEEN_PROBES); // Move to the given XY with probe clearance
+
+ TERN_(UBL_MESH_EDIT_MOVES_Z, do_blocking_move_to_z(h_offset)); // Move Z to the given 'H' offset
MeshFlags done_flags{0};
const xy_int8_t &lpos = location.pos;
@@ -1022,9 +988,7 @@
do_blocking_move_to(raw); // Move the nozzle to the edit point with probe clearance
- #if ENABLED(UBL_MESH_EDIT_MOVES_Z)
- do_blocking_move_to_z(h_offset); // Move Z to the given 'H' offset before editing
- #endif
+ TERN_(UBL_MESH_EDIT_MOVES_Z, do_blocking_move_to_z(h_offset)); // Move Z to the given 'H' offset before editing
KEEPALIVE_STATE(PAUSED_FOR_USER);
@@ -1039,11 +1003,9 @@
lcd_mesh_edit_setup(new_z);
do {
- new_z = lcd_mesh_edit();
- #if ENABLED(UBL_MESH_EDIT_MOVES_Z)
- do_blocking_move_to_z(h_offset + new_z); // Move the nozzle as the point is edited
- #endif
idle();
+ new_z = lcd_mesh_edit();
+ TERN_(UBL_MESH_EDIT_MOVES_Z, do_blocking_move_to_z(h_offset + new_z)); // Move the nozzle as the point is edited
SERIAL_FLUSH(); // Prevent host M105 buffer overrun.
} while (!ui.button_pressed());
@@ -1052,17 +1014,13 @@
if (click_and_hold(abort_fine_tune)) break; // Button held down? Abort editing
z_values[lpos.x][lpos.y] = new_z; // Save the updated Z value
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(location, new_z);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location, new_z));
serial_delay(20); // No switch noise
ui.refresh();
} while (lpos.x >= 0 && --g29_repetition_cnt > 0);
- ui.release();
-
if (do_ubl_mesh_map) display_map(g29_map_type);
restore_ubl_active_state_and_leave();
@@ -1072,7 +1030,7 @@
SERIAL_ECHOLNPGM("Done Editing Mesh");
if (lcd_map_control)
- ui.goto_screen(_lcd_ubl_output_map_lcd);
+ ui.goto_screen(ubl_map_screen);
else
ui.return_to_status();
}
@@ -1082,9 +1040,7 @@
bool unified_bed_leveling::g29_parameter_parsing() {
bool err_flag = false;
- #if HAS_LCD_MENU
- set_message_with_feedback(GET_TEXT(MSG_UBL_DOING_G29));
- #endif
+ TERN_(HAS_LCD_MENU, set_message_with_feedback(GET_TEXT(MSG_UBL_DOING_G29)));
g29_constant = 0;
g29_repetition_cnt = 0;
@@ -1206,9 +1162,7 @@
ubl_state_recursion_chk++;
if (ubl_state_recursion_chk != 1) {
SERIAL_ECHOLNPGM("save_ubl_active_state_and_disabled() called multiple times in a row.");
- #if HAS_LCD_MENU
- set_message_with_feedback(GET_TEXT(MSG_UBL_SAVE_ERROR));
- #endif
+ TERN_(HAS_LCD_MENU, set_message_with_feedback(GET_TEXT(MSG_UBL_SAVE_ERROR)));
return;
}
#endif
@@ -1217,12 +1171,11 @@
}
void unified_bed_leveling::restore_ubl_active_state_and_leave() {
+ TERN_(HAS_LCD_MENU, ui.release());
#if ENABLED(UBL_DEVEL_DEBUGGING)
if (--ubl_state_recursion_chk) {
SERIAL_ECHOLNPGM("restore_ubl_active_state_and_leave() called too many times.");
- #if HAS_LCD_MENU
- set_message_with_feedback(GET_TEXT(MSG_UBL_RESTORE_ERROR));
- #endif
+ TERN_(HAS_LCD_MENU, set_message_with_feedback(GET_TEXT(MSG_UBL_RESTORE_ERROR)));
return;
}
#endif
@@ -1337,9 +1290,7 @@
const float v2 = z_values[dx + xdir][dy + ydir];
if (!isnan(v2)) {
z_values[x][y] = v1 < v2 ? v1 : v1 + v1 - v2;
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(x, y, z_values[x][y]);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y]));
return true;
}
}
@@ -1403,9 +1354,7 @@
if (do_3_pt_leveling) {
SERIAL_ECHOLNPGM("Tilting mesh (1/3)");
- #if HAS_DISPLAY
- ui.status_printf_P(0, PSTR(S_FMT " 1/3"), GET_TEXT(MSG_LCD_TILTING_MESH));
- #endif
+ TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " 1/3"), GET_TEXT(MSG_LCD_TILTING_MESH)));
measured_z = probe.probe_at_point(points[0], PROBE_PT_RAISE, g29_verbose_level);
if (isnan(measured_z))
@@ -1424,9 +1373,7 @@
if (!abort_flag) {
SERIAL_ECHOLNPGM("Tilting mesh (2/3)");
- #if HAS_DISPLAY
- ui.status_printf_P(0, PSTR(S_FMT " 2/3"), GET_TEXT(MSG_LCD_TILTING_MESH));
- #endif
+ TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " 2/3"), GET_TEXT(MSG_LCD_TILTING_MESH)));
measured_z = probe.probe_at_point(points[1], PROBE_PT_RAISE, g29_verbose_level);
#ifdef VALIDATE_MESH_TILT
@@ -1446,9 +1393,7 @@
if (!abort_flag) {
SERIAL_ECHOLNPGM("Tilting mesh (3/3)");
- #if HAS_DISPLAY
- ui.status_printf_P(0, PSTR(S_FMT " 3/3"), GET_TEXT(MSG_LCD_TILTING_MESH));
- #endif
+ TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " 3/3"), GET_TEXT(MSG_LCD_TILTING_MESH)));
measured_z = probe.probe_at_point(points[2], PROBE_PT_STOW, g29_verbose_level);
#ifdef VALIDATE_MESH_TILT
@@ -1467,9 +1412,7 @@
}
probe.stow();
- #ifdef Z_AFTER_PROBING
- probe.move_z_after_probing();
- #endif
+ probe.move_z_after_probing();
if (abort_flag) {
SERIAL_ECHOLNPGM("?Error probing point. Aborting operation.");
@@ -1491,9 +1434,7 @@
if (!abort_flag) {
SERIAL_ECHOLNPAIR("Tilting mesh point ", point_num, "/", total_points, "\n");
- #if HAS_DISPLAY
- ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_LCD_TILTING_MESH), point_num, total_points);
- #endif
+ TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_LCD_TILTING_MESH), point_num, total_points));
measured_z = probe.probe_at_point(rpos, parser.seen('E') ? PROBE_PT_STOW : PROBE_PT_RAISE, g29_verbose_level); // TODO: Needs error handling
@@ -1532,9 +1473,7 @@
}
}
probe.stow();
- #ifdef Z_AFTER_PROBING
- probe.move_z_after_probing();
- #endif
+ probe.move_z_after_probing();
if (abort_flag || finish_incremental_LSF(&lsf_results)) {
SERIAL_ECHOPGM("Could not complete LSF!");
@@ -1582,9 +1521,7 @@
}
z_values[i][j] = mz - lsf_results.D;
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(i, j, z_values[i][j]);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(i, j, z_values[i][j]));
}
if (DEBUGGING(LEVELING)) {
@@ -1680,9 +1617,7 @@
}
const float ez = -lsf_results.D - lsf_results.A * ppos.x - lsf_results.B * ppos.y;
z_values[ix][iy] = ez;
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(ix, iy, z_values[ix][iy]);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, z_values[ix][iy]));
idle(); // housekeeping
}
}
@@ -1743,8 +1678,9 @@
SERIAL_EOL();
#if HAS_KILL
- SERIAL_ECHOLNPAIR("Kill pin on :", int(KILL_PIN), " state:", READ(KILL_PIN));
+ SERIAL_ECHOLNPAIR("Kill pin on :", int(KILL_PIN), " state:", int(kill_state()));
#endif
+
SERIAL_EOL();
serial_delay(50);
@@ -1822,9 +1758,7 @@
GRID_LOOP(x, y) {
z_values[x][y] -= tmp_z_values[x][y];
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(x, y, z_values[x][y]);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y]));
}
}
diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp
index 536410824..63559e0bb 100644
--- a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp
+++ b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#include "../../../inc/MarlinConfig.h"
diff --git a/Marlin/src/feature/binary_protocol.cpp b/Marlin/src/feature/binary_protocol.cpp
index e555c0c46..5884a05f4 100644
--- a/Marlin/src/feature/binary_protocol.cpp
+++ b/Marlin/src/feature/binary_protocol.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/feature/binary_protocol.h b/Marlin/src/feature/binary_protocol.h
index 978d6a2c0..10dea10d4 100644
--- a/Marlin/src/feature/binary_protocol.h
+++ b/Marlin/src/feature/binary_protocol.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -32,7 +32,7 @@
inline bool bs_serial_data_available(const uint8_t index) {
switch (index) {
case 0: return MYSERIAL0.available();
- #if NUM_SERIAL > 1
+ #if HAS_MULTI_SERIAL
case 1: return MYSERIAL1.available();
#endif
}
@@ -42,7 +42,7 @@ inline bool bs_serial_data_available(const uint8_t index) {
inline int bs_read_serial(const uint8_t index) {
switch (index) {
case 0: return MYSERIAL0.read();
- #if NUM_SERIAL > 1
+ #if HAS_MULTI_SERIAL
case 1: return MYSERIAL1.read();
#endif
}
@@ -82,9 +82,7 @@ private:
}
transfer_active = true;
data_waiting = 0;
- #if ENABLED(BINARY_STREAM_COMPRESSION)
- heatshrink_decoder_reset(&hsd);
- #endif
+ TERN_(BINARY_STREAM_COMPRESSION, heatshrink_decoder_reset(&hsd));
return true;
}
@@ -127,9 +125,7 @@ private:
card.closefile();
card.release();
}
- #if ENABLED(BINARY_STREAM_COMPRESSION)
- heatshrink_decoder_finish(&hsd);
- #endif
+ TERN_(BINARY_STREAM_COMPRESSION, heatshrink_decoder_finish(&hsd));
transfer_active = false;
return true;
}
@@ -139,9 +135,7 @@ private:
card.closefile();
card.removeFile(card.filename);
card.release();
- #if ENABLED(BINARY_STREAM_COMPRESSION)
- heatshrink_decoder_finish(&hsd);
- #endif
+ TERN_(BINARY_STREAM_COMPRESSION, heatshrink_decoder_finish(&hsd));
}
transfer_active = false;
return;
diff --git a/Marlin/src/feature/bltouch.cpp b/Marlin/src/feature/bltouch.cpp
index efe575ec6..d6b1f99c1 100644
--- a/Marlin/src/feature/bltouch.cpp
+++ b/Marlin/src/feature/bltouch.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -124,9 +124,7 @@ bool BLTouch::deploy_proc() {
}
// One of the recommended ANTClabs ways to probe, using SW MODE
- #if ENABLED(BLTOUCH_FORCE_SW_MODE)
- _set_SW_mode();
- #endif
+ TERN_(BLTOUCH_FORCE_SW_MODE, _set_SW_mode());
// Now the probe is ready to issue a 10ms pulse when the pin goes up.
// The trigger STOW (see motion.cpp for example) will pull up the probes pin as soon as the pulse
diff --git a/Marlin/src/feature/bltouch.h b/Marlin/src/feature/bltouch.h
index af75fb8b2..40685af1b 100644
--- a/Marlin/src/feature/bltouch.h
+++ b/Marlin/src/feature/bltouch.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -26,9 +26,17 @@
// BLTouch commands are sent as servo angles
typedef unsigned char BLTCommand;
-#define BLTOUCH_DEPLOY 10
+#if ENABLED(CREALITY_TOUCH)
+ #define STOW_ALARM false
+ #define BLTOUCH_DEPLOY 170
+ #define BLTOUCH_STOW 20
+#else
+ #define STOW_ALARM true
+ #define BLTOUCH_DEPLOY 10
+ #define BLTOUCH_STOW 90
+#endif
+
#define BLTOUCH_SW_MODE 60
-#define BLTOUCH_STOW 90
#define BLTOUCH_SELFTEST 120
#define BLTOUCH_MODE_STORE 130
#define BLTOUCH_5V_MODE 140
@@ -95,7 +103,7 @@ public:
private:
FORCE_INLINE static bool _deploy_query_alarm() { return command(BLTOUCH_DEPLOY, BLTOUCH_DEPLOY_DELAY); }
- FORCE_INLINE static bool _stow_query_alarm() { return command(BLTOUCH_STOW, BLTOUCH_STOW_DELAY); }
+ FORCE_INLINE static bool _stow_query_alarm() { return command(BLTOUCH_STOW, BLTOUCH_STOW_DELAY) == STOW_ALARM; }
static void clear();
static bool command(const BLTCommand cmd, const millis_t &ms);
diff --git a/Marlin/src/feature/cancel_object.cpp b/Marlin/src/feature/cancel_object.cpp
index e2ee64521..7eb471543 100644
--- a/Marlin/src/feature/cancel_object.cpp
+++ b/Marlin/src/feature/cancel_object.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#include "../inc/MarlinConfig.h"
diff --git a/Marlin/src/feature/cancel_object.h b/Marlin/src/feature/cancel_object.h
index 41bbfb70f..1d2d77f20 100644
--- a/Marlin/src/feature/cancel_object.h
+++ b/Marlin/src/feature/cancel_object.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/caselight.cpp b/Marlin/src/feature/caselight.cpp
index a135cac41..4287a0f26 100644
--- a/Marlin/src/feature/caselight.cpp
+++ b/Marlin/src/feature/caselight.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/feature/caselight.h b/Marlin/src/feature/caselight.h
index de77f0696..ff01b1a67 100644
--- a/Marlin/src/feature/caselight.h
+++ b/Marlin/src/feature/caselight.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/closedloop.cpp b/Marlin/src/feature/closedloop.cpp
index b77724348..8a97f0c0c 100644
--- a/Marlin/src/feature/closedloop.cpp
+++ b/Marlin/src/feature/closedloop.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#include "../inc/MarlinConfig.h"
@@ -29,12 +29,14 @@
#include "closedloop.h"
-void init_closedloop() {
+ClosedLoop closedloop;
+
+void ClosedLoop::init() {
OUT_WRITE(CLOSED_LOOP_ENABLE_PIN, LOW);
SET_INPUT_PULLUP(CLOSED_LOOP_MOVE_COMPLETE_PIN);
}
-void set_closedloop(const byte val) {
+void ClosedLoop::set(const byte val) {
OUT_WRITE(CLOSED_LOOP_ENABLE_PIN, val);
}
diff --git a/Marlin/src/feature/closedloop.h b/Marlin/src/feature/closedloop.h
index 7e5594447..e03400c35 100644
--- a/Marlin/src/feature/closedloop.h
+++ b/Marlin/src/feature/closedloop.h
@@ -16,10 +16,17 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
-void init_closedloop();
-void set_closedloop(const byte val);
+class ClosedLoop {
+public:
+ static void init();
+ static void set(const byte val);
+};
+
+extern ClosedLoop closedloop;
+
+#define CLOSED_LOOP_WAITING() (READ(CLOSED_LOOP_ENABLE_PIN) && !READ(CLOSED_LOOP_MOVE_COMPLETE_PIN))
diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp
index 074670040..fa5a86b01 100644
--- a/Marlin/src/feature/controllerfan.cpp
+++ b/Marlin/src/feature/controllerfan.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -55,43 +55,34 @@ void ControllerFan::update() {
#define MOTOR_IS_ON(A,B) (A##_ENABLE_READ() == bool(B##_ENABLE_ON))
#define _OR_ENABLED_E(N) || MOTOR_IS_ON(E##N,E)
- const bool motor_on = MOTOR_IS_ON(Z,Z)
- #if HAS_Z2_ENABLE
- || MOTOR_IS_ON(Z2,Z)
- #endif
- #if HAS_Z3_ENABLE
- || MOTOR_IS_ON(Z3,Z)
- #endif
- #if HAS_Z4_ENABLE
- || MOTOR_IS_ON(Z4,Z)
- #endif
- || (DISABLED(CONTROLLER_FAN_USE_Z_ONLY) && (
- MOTOR_IS_ON(X,X) || MOTOR_IS_ON(Y,Y)
- #if HAS_X2_ENABLE
- || MOTOR_IS_ON(X2,X)
- #endif
- #if HAS_Y2_ENABLE
- || MOTOR_IS_ON(Y2,Y)
- #endif
+ const bool motor_on = (
+ ( DISABLED(CONTROLLER_FAN_IGNORE_Z) &&
+ ( MOTOR_IS_ON(Z,Z)
+ || TERN0(HAS_Z2_ENABLE, MOTOR_IS_ON(Z2,Z))
+ || TERN0(HAS_Z3_ENABLE, MOTOR_IS_ON(Z3,Z))
+ || TERN0(HAS_Z4_ENABLE, MOTOR_IS_ON(Z4,Z))
+ )
+ ) || (
+ DISABLED(CONTROLLER_FAN_USE_Z_ONLY) &&
+ ( MOTOR_IS_ON(X,X) || MOTOR_IS_ON(Y,Y)
+ || TERN0(HAS_X2_ENABLE, MOTOR_IS_ON(X2,X))
+ || TERN0(HAS_Y2_ENABLE, MOTOR_IS_ON(Y2,Y))
#if E_STEPPERS
REPEAT(E_STEPPERS, _OR_ENABLED_E)
#endif
)
)
- ;
+ );
// If any of the drivers or the heated bed are enabled...
- if (motor_on
- #if HAS_HEATED_BED
- || thermalManager.temp_bed.soft_pwm_amount > 0
- #endif
- ) lastMotorOn = ms; //... set time to NOW so the fan will turn on
+ if (motor_on || TERN0(HAS_HEATED_BED, thermalManager.temp_bed.soft_pwm_amount > 0))
+ lastMotorOn = ms; //... set time to NOW so the fan will turn on
// Fan Settings. Set fan > 0:
// - If AutoMode is on and steppers have been enabled for CONTROLLERFAN_IDLE_TIME seconds.
// - If System is on idle and idle fan speed settings is activated.
set_fan_speed(
- settings.auto_mode && lastMotorOn && PENDING(ms, lastMotorOn + settings.duration * 1000UL)
+ settings.auto_mode && lastMotorOn && PENDING(ms, lastMotorOn + SEC_TO_MS(settings.duration))
? settings.active_speed : settings.idle_speed
);
diff --git a/Marlin/src/feature/controllerfan.h b/Marlin/src/feature/controllerfan.h
index cd56ff8ce..d1d39f21f 100644
--- a/Marlin/src/feature/controllerfan.h
+++ b/Marlin/src/feature/controllerfan.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -62,11 +62,7 @@ class ControllerFan {
#endif
static inline bool state() { return speed > 0; }
static inline void init() { reset(); }
- static inline void reset() {
- #if ENABLED(CONTROLLER_FAN_EDITABLE)
- settings = controllerFan_defaults;
- #endif
- }
+ static inline void reset() { TERN_(CONTROLLER_FAN_EDITABLE, settings = controllerFan_defaults); }
static void setup();
static void update();
};
diff --git a/Marlin/src/feature/dac/dac_dac084s085.h b/Marlin/src/feature/dac/dac_dac084s085.h
index cccc9cbd4..5be0129fc 100644
--- a/Marlin/src/feature/dac/dac_dac084s085.h
+++ b/Marlin/src/feature/dac/dac_dac084s085.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/dac/dac_mcp4728.cpp b/Marlin/src/feature/dac/dac_mcp4728.cpp
index cfb4dc462..4976b3690 100644
--- a/Marlin/src/feature/dac/dac_mcp4728.cpp
+++ b/Marlin/src/feature/dac/dac_mcp4728.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -27,7 +27,7 @@
* https://ww1.microchip.com/downloads/en/DeviceDoc/22187a.pdf
*
* For discussion and feedback, please go to:
- * http://arduino.cc/forum/index.php/topic,51842.0.html
+ * https://arduino.cc/forum/index.php/topic,51842.0.html
*/
#include "../../inc/MarlinConfig.h"
@@ -43,7 +43,7 @@ xyze_uint_t mcp4728_values;
*/
void mcp4728_init() {
Wire.begin();
- Wire.requestFrom(I2C_ADDRESS(DAC_DEV_ADDRESS), 24);
+ Wire.requestFrom(I2C_ADDRESS(DAC_DEV_ADDRESS), uint8_t(24));
while (Wire.available()) {
char deviceID = Wire.read(),
hiByte = Wire.read(),
diff --git a/Marlin/src/feature/dac/dac_mcp4728.h b/Marlin/src/feature/dac/dac_mcp4728.h
index 8e8b25ca6..6cce77856 100644
--- a/Marlin/src/feature/dac/dac_mcp4728.h
+++ b/Marlin/src/feature/dac/dac_mcp4728.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/dac/stepper_dac.cpp b/Marlin/src/feature/dac/stepper_dac.cpp
index c8c1cb249..6b140a002 100644
--- a/Marlin/src/feature/dac/stepper_dac.cpp
+++ b/Marlin/src/feature/dac/stepper_dac.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -29,6 +29,7 @@
#if ENABLED(DAC_STEPPER_CURRENT)
#include "stepper_dac.h"
+#include "../../MarlinCore.h" // for SP_X_LBL...
bool dac_present = false;
constexpr xyze_uint8_t dac_order = DAC_STEPPER_ORDER;
@@ -85,15 +86,12 @@ void dac_current_set_percents(xyze_uint8_t &pct) {
void dac_print_values() {
if (!dac_present) return;
-
SERIAL_ECHO_MSG("Stepper current values in % (Amps):");
SERIAL_ECHO_START();
- SERIAL_ECHOLNPAIR_P(
- SP_X_LBL, dac_perc(X_AXIS), PSTR(" ("), dac_amps(X_AXIS), PSTR(")")
- SP_Y_LBL, dac_perc(Y_AXIS), PSTR(" ("), dac_amps(Y_AXIS), PSTR(")")
- SP_Z_LBL, dac_perc(Z_AXIS), PSTR(" ("), dac_amps(Z_AXIS), PSTR(")")
- SP_E_LBL, dac_perc(E_AXIS), PSTR(" ("), dac_amps(E_AXIS), PSTR(")")
- );
+ SERIAL_ECHOPAIR_P( SP_X_LBL, dac_perc(X_AXIS), PSTR(" ("), dac_amps(X_AXIS), PSTR(")"));
+ SERIAL_ECHOPAIR_P( SP_Y_LBL, dac_perc(Y_AXIS), PSTR(" ("), dac_amps(Y_AXIS), PSTR(")"));
+ SERIAL_ECHOPAIR_P( SP_Z_LBL, dac_perc(Z_AXIS), PSTR(" ("), dac_amps(Z_AXIS), PSTR(")"));
+ SERIAL_ECHOLNPAIR_P(SP_E_LBL, dac_perc(E_AXIS), PSTR(" ("), dac_amps(E_AXIS), PSTR(")"));
}
void dac_commit_eeprom() {
diff --git a/Marlin/src/feature/dac/stepper_dac.h b/Marlin/src/feature/dac/stepper_dac.h
index 3e77d471a..0543b6275 100644
--- a/Marlin/src/feature/dac/stepper_dac.h
+++ b/Marlin/src/feature/dac/stepper_dac.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/digipot/digipot.h b/Marlin/src/feature/digipot/digipot.h
index b7c0b6503..d59f8b930 100644
--- a/Marlin/src/feature/digipot/digipot.h
+++ b/Marlin/src/feature/digipot/digipot.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/digipot/digipot_mcp4018.cpp b/Marlin/src/feature/digipot/digipot_mcp4018.cpp
index e8df4a475..35c513a32 100644
--- a/Marlin/src/feature/digipot/digipot_mcp4018.cpp
+++ b/Marlin/src/feature/digipot/digipot_mcp4018.cpp
@@ -16,60 +16,52 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#include "../../inc/MarlinConfig.h"
-#if BOTH(DIGIPOT_I2C, DIGIPOT_MCP4018)
+#if ENABLED(DIGIPOT_MCP4018)
-#include "Stream.h"
-#include "utility/twi.h"
-#include //https://github.com/stawel/SlowSoftI2CMaster
+#include
+#include // https://github.com/stawel/SlowSoftI2CMaster
// Settings for the I2C based DIGIPOT (MCP4018) based on WT150
#define DIGIPOT_A4988_Rsx 0.250
#define DIGIPOT_A4988_Vrefmax 1.666
-#define DIGIPOT_A4988_MAX_VALUE 127
+#define DIGIPOT_MCP4018_MAX_VALUE 127
-#define DIGIPOT_A4988_Itripmax(Vref) ((Vref)/(8.0*DIGIPOT_A4988_Rsx))
+#define DIGIPOT_A4988_Itripmax(Vref) ((Vref) / (8.0 * DIGIPOT_A4988_Rsx))
-#define DIGIPOT_A4988_FACTOR ((DIGIPOT_A4988_MAX_VALUE)/DIGIPOT_A4988_Itripmax(DIGIPOT_A4988_Vrefmax))
+#define DIGIPOT_A4988_FACTOR ((DIGIPOT_MCP4018_MAX_VALUE) / DIGIPOT_A4988_Itripmax(DIGIPOT_A4988_Vrefmax))
#define DIGIPOT_A4988_MAX_CURRENT 2.0
static byte current_to_wiper(const float current) {
- const int16_t value = ceil(float(DIGIPOT_A4988_FACTOR) * current);
- return byte(constrain(value, 0, DIGIPOT_A4988_MAX_VALUE));
+ const int16_t value = TERN(DIGIPOT_USE_RAW_VALUES, current, CEIL(current * DIGIPOT_A4988_FACTOR));
+ return byte(constrain(value, 0, DIGIPOT_MCP4018_MAX_VALUE));
}
-const uint8_t sda_pins[DIGIPOT_I2C_NUM_CHANNELS] = {
- DIGIPOTS_I2C_SDA_X
- #if DIGIPOT_I2C_NUM_CHANNELS > 1
- , DIGIPOTS_I2C_SDA_Y
- #if DIGIPOT_I2C_NUM_CHANNELS > 2
- , DIGIPOTS_I2C_SDA_Z
- #if DIGIPOT_I2C_NUM_CHANNELS > 3
- , DIGIPOTS_I2C_SDA_E0
- #if DIGIPOT_I2C_NUM_CHANNELS > 4
- , DIGIPOTS_I2C_SDA_E1
- #endif
- #endif
- #endif
- #endif
-};
-
static SlowSoftI2CMaster pots[DIGIPOT_I2C_NUM_CHANNELS] = {
- SlowSoftI2CMaster { sda_pins[X_AXIS], DIGIPOTS_I2C_SCL }
+ SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_X, DIGIPOTS_I2C_SCL)
#if DIGIPOT_I2C_NUM_CHANNELS > 1
- , SlowSoftI2CMaster { sda_pins[Y_AXIS], DIGIPOTS_I2C_SCL }
+ , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_Y, DIGIPOTS_I2C_SCL)
#if DIGIPOT_I2C_NUM_CHANNELS > 2
- , SlowSoftI2CMaster { sda_pins[Z_AXIS], DIGIPOTS_I2C_SCL }
+ , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_Z, DIGIPOTS_I2C_SCL)
#if DIGIPOT_I2C_NUM_CHANNELS > 3
- , SlowSoftI2CMaster { sda_pins[E_AXIS], DIGIPOTS_I2C_SCL }
+ , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E0, DIGIPOTS_I2C_SCL)
#if DIGIPOT_I2C_NUM_CHANNELS > 4
- , SlowSoftI2CMaster { sda_pins[E_AXIS + 1], DIGIPOTS_I2C_SCL }
+ , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E1, DIGIPOTS_I2C_SCL)
+ #if DIGIPOT_I2C_NUM_CHANNELS > 5
+ , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E2, DIGIPOTS_I2C_SCL)
+ #if DIGIPOT_I2C_NUM_CHANNELS > 6
+ , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E3, DIGIPOTS_I2C_SCL)
+ #if DIGIPOT_I2C_NUM_CHANNELS > 7
+ , SlowSoftI2CMaster(DIGIPOTS_I2C_SDA_E4, DIGIPOTS_I2C_SCL)
+ #endif
+ #endif
+ #endif
#endif
#endif
#endif
@@ -86,18 +78,23 @@ static void i2c_send(const uint8_t channel, const byte v) {
// This is for the MCP4018 I2C based digipot
void digipot_i2c_set_current(const uint8_t channel, const float current) {
- i2c_send(channel, current_to_wiper(_MIN(_MAX(current, 0), float(DIGIPOT_A4988_MAX_CURRENT))));
+ const float ival = _MIN(_MAX(current, 0), float(DIGIPOT_MCP4018_MAX_VALUE));
+ i2c_send(channel, current_to_wiper(ival));
}
void digipot_i2c_init() {
- static const float digipot_motor_current[] PROGMEM = DIGIPOT_I2C_MOTOR_CURRENTS;
+ LOOP_L_N(i, DIGIPOT_I2C_NUM_CHANNELS) pots[i].i2c_init();
- LOOP_L_N(i, DIGIPOT_I2C_NUM_CHANNELS)
- pots[i].i2c_init();
-
- // setup initial currents as defined in Configuration_adv.h
+ // Init currents according to Configuration_adv.h
+ static const float digipot_motor_current[] PROGMEM =
+ #if ENABLED(DIGIPOT_USE_RAW_VALUES)
+ DIGIPOT_MOTOR_CURRENT
+ #else
+ DIGIPOT_I2C_MOTOR_CURRENTS
+ #endif
+ ;
LOOP_L_N(i, COUNT(digipot_motor_current))
digipot_i2c_set_current(i, pgm_read_float(&digipot_motor_current[i]));
}
-#endif // DIGIPOT_I2C && DIGIPOT_MCP4018
+#endif // DIGIPOT_MCP4018
diff --git a/Marlin/src/feature/digipot/digipot_mcp4451.cpp b/Marlin/src/feature/digipot/digipot_mcp4451.cpp
index 1183c96aa..0c8ff04a0 100644
--- a/Marlin/src/feature/digipot/digipot_mcp4451.cpp
+++ b/Marlin/src/feature/digipot/digipot_mcp4451.cpp
@@ -16,15 +16,15 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#include "../../inc/MarlinConfig.h"
-#if ENABLED(DIGIPOT_I2C) && DISABLED(DIGIPOT_MCP4018)
+#if ENABLED(DIGIPOT_MCP4451)
-#include "Stream.h"
+#include
#include
#if MB(MKS_SBASE)
@@ -33,18 +33,18 @@
// Settings for the I2C based DIGIPOT (MCP4451) on Azteeg X3 Pro
#if MB(5DPRINT)
- #define DIGIPOT_I2C_FACTOR 117.96
- #define DIGIPOT_I2C_MAX_CURRENT 1.736
+ #define DIGIPOT_I2C_FACTOR 117.96f
+ #define DIGIPOT_I2C_MAX_CURRENT 1.736f
#elif MB(AZTEEG_X5_MINI, AZTEEG_X5_MINI_WIFI)
- #define DIGIPOT_I2C_FACTOR 113.5
- #define DIGIPOT_I2C_MAX_CURRENT 2.0
+ #define DIGIPOT_I2C_FACTOR 113.5f
+ #define DIGIPOT_I2C_MAX_CURRENT 2.0f
#else
- #define DIGIPOT_I2C_FACTOR 106.7
- #define DIGIPOT_I2C_MAX_CURRENT 2.5
+ #define DIGIPOT_I2C_FACTOR 106.7f
+ #define DIGIPOT_I2C_MAX_CURRENT 2.5f
#endif
static byte current_to_wiper(const float current) {
- return byte(CEIL(float((DIGIPOT_I2C_FACTOR * current))));
+ return byte(TERN(DIGIPOT_USE_RAW_VALUES, current, CEIL(DIGIPOT_I2C_FACTOR * current)));
}
static void digipot_i2c_send(const byte addr, const byte a, const byte b) {
@@ -62,8 +62,8 @@ static void digipot_i2c_send(const byte addr, const byte a, const byte b) {
// This is for the MCP4451 I2C based digipot
void digipot_i2c_set_current(const uint8_t channel, const float current) {
- // these addresses are specific to Azteeg X3 Pro, can be set to others,
- // In this case first digipot is at address A0=0, A1= 0, second one is at A0=0, A1= 1
+ // These addresses are specific to Azteeg X3 Pro, can be set to others.
+ // In this case first digipot is at address A0=0, A1=0, second one is at A0=0, A1=1
const byte addr = channel < 4 ? DIGIPOT_I2C_ADDRESS_A : DIGIPOT_I2C_ADDRESS_B; // channel 0-3 vs 4-7
// Initial setup
@@ -77,14 +77,20 @@ void digipot_i2c_set_current(const uint8_t channel, const float current) {
void digipot_i2c_init() {
#if MB(MKS_SBASE)
- configure_i2c(16); // Setting clock_option to 16 ensure the I2C bus is initialized at 400kHz
+ configure_i2c(16); // Set clock_option to 16 ensure I2C is initialized at 400kHz
#else
Wire.begin();
#endif
- // setup initial currents as defined in Configuration_adv.h
- static const float digipot_motor_current[] PROGMEM = DIGIPOT_I2C_MOTOR_CURRENTS;
+ // Set up initial currents as defined in Configuration_adv.h
+ static const float digipot_motor_current[] PROGMEM =
+ #if ENABLED(DIGIPOT_USE_RAW_VALUES)
+ DIGIPOT_MOTOR_CURRENT
+ #else
+ DIGIPOT_I2C_MOTOR_CURRENTS
+ #endif
+ ;
LOOP_L_N(i, COUNT(digipot_motor_current))
digipot_i2c_set_current(i, pgm_read_float(&digipot_motor_current[i]));
}
-#endif // DIGIPOT_I2C
+#endif // DIGIPOT_MCP4451
diff --git a/Marlin/src/feature/direct_stepping.cpp b/Marlin/src/feature/direct_stepping.cpp
new file mode 100644
index 000000000..d3bdb43ab
--- /dev/null
+++ b/Marlin/src/feature/direct_stepping.cpp
@@ -0,0 +1,273 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#include "../inc/MarlinConfigPre.h"
+
+#if ENABLED(DIRECT_STEPPING)
+
+#include "direct_stepping.h"
+
+#include "../MarlinCore.h"
+
+#define CHECK_PAGE(I, R) do{ \
+ if (I >= sizeof(page_states) / sizeof(page_states[0])) { \
+ fatal_error = true; \
+ return R; \
+ } \
+}while(0)
+
+#define CHECK_PAGE_STATE(I, R, S) do { \
+ CHECK_PAGE(I, R); \
+ if (page_states[I] != S) { \
+ fatal_error = true; \
+ return R; \
+ } \
+}while(0)
+
+namespace DirectStepping {
+
+ template
+ State SerialPageManager::state;
+
+ template
+ volatile bool SerialPageManager::fatal_error;
+
+ template
+ volatile PageState SerialPageManager::page_states[Cfg::NUM_PAGES];
+
+ template
+ volatile bool SerialPageManager::page_states_dirty;
+
+ template
+ millis_t SerialPageManager::next_response;
+
+ template
+ uint8_t SerialPageManager::pages[Cfg::NUM_PAGES][Cfg::PAGE_SIZE];
+
+ template
+ uint8_t SerialPageManager::checksum;
+
+ template
+ typename Cfg::write_byte_idx_t SerialPageManager::write_byte_idx;
+
+ template
+ typename Cfg::page_idx_t SerialPageManager::write_page_idx;
+
+ template
+ typename Cfg::write_byte_idx_t SerialPageManager::write_page_size;
+
+ template
+ void SerialPageManager::init() {
+ for (int i = 0 ; i < Cfg::NUM_PAGES ; i++)
+ page_states[i] = PageState::FREE;
+
+ fatal_error = false;
+ next_response = 0;
+ state = State::NEWLINE;
+
+ page_states_dirty = false;
+
+ SERIAL_ECHOLNPGM("pages_ready");
+ }
+
+ template
+ FORCE_INLINE bool SerialPageManager::maybe_store_rxd_char(uint8_t c) {
+ switch (state) {
+ default:
+ case State::MONITOR:
+ switch (c) {
+ case '\n':
+ case '\r':
+ state = State::NEWLINE;
+ default:
+ return false;
+ }
+ case State::NEWLINE:
+ switch (c) {
+ case Cfg::CONTROL_CHAR:
+ state = State::ADDRESS;
+ return true;
+ case '\n':
+ case '\r':
+ state = State::NEWLINE;
+ return false;
+ default:
+ state = State::MONITOR;
+ return false;
+ }
+ case State::ADDRESS:
+ //TODO: 16 bit address, State::ADDRESS2
+ write_page_idx = c;
+ write_byte_idx = 0;
+ checksum = 0;
+
+ CHECK_PAGE(write_page_idx, true);
+
+ if (page_states[write_page_idx] == PageState::FAIL) {
+ // Special case for fail
+ state = State::UNFAIL;
+ return true;
+ }
+
+ set_page_state(write_page_idx, PageState::WRITING);
+
+ state = Cfg::DIRECTIONAL ? State::COLLECT : State::SIZE;
+
+ return true;
+ case State::SIZE:
+ // Zero means full page size
+ write_page_size = c;
+ state = State::COLLECT;
+ return true;
+ case State::COLLECT:
+ pages[write_page_idx][write_byte_idx++] = c;
+ checksum ^= c;
+
+ // check if still collecting
+ if (Cfg::PAGE_SIZE == 256) {
+ // special case for 8-bit, check if rolled back to 0
+ if (Cfg::DIRECTIONAL || !write_page_size) { // full 256 bytes
+ if (write_byte_idx) return true;
+ } else {
+ if (write_byte_idx < write_page_size) return true;
+ }
+ } else if (Cfg::DIRECTIONAL) {
+ if (write_byte_idx != Cfg::PAGE_SIZE) return true;
+ } else {
+ if (write_byte_idx < write_page_size) return true;
+ }
+
+ state = State::CHECKSUM;
+ return true;
+ case State::CHECKSUM: {
+ const PageState page_state = (checksum == c) ? PageState::OK : PageState::FAIL;
+ set_page_state(write_page_idx, page_state);
+ state = State::MONITOR;
+ return true;
+ }
+ case State::UNFAIL:
+ if (c == 0) {
+ set_page_state(write_page_idx, PageState::FREE);
+ } else {
+ fatal_error = true;
+ }
+ state = State::MONITOR;
+ return true;
+ }
+ }
+
+ template
+ void SerialPageManager::write_responses() {
+ if (fatal_error) {
+ kill(GET_TEXT(MSG_BAD_PAGE));
+ return;
+ }
+
+ // Runs on a set interval also, as responses may get lost.
+ if (next_response && next_response < millis()) {
+ page_states_dirty = true;
+ }
+
+ if (!page_states_dirty) return;
+
+ page_states_dirty = false;
+ next_response = millis() + Cfg::RESPONSE_INTERVAL_MS;
+
+ SERIAL_ECHO(Cfg::CONTROL_CHAR);
+ constexpr int state_bits = 2;
+ constexpr int n_bytes = Cfg::NUM_PAGES >> state_bits;
+ volatile uint8_t bits_b[n_bytes] = { 0 };
+
+ for (page_idx_t i = 0 ; i < Cfg::NUM_PAGES ; i++) {
+ bits_b[i >> state_bits] |= page_states[i] << ((i * state_bits) & 0x7);
+ }
+
+ uint8_t crc = 0;
+ for (uint8_t i = 0 ; i < n_bytes ; i++) {
+ crc ^= bits_b[i];
+ SERIAL_ECHO(bits_b[i]);
+ }
+
+ SERIAL_ECHO(crc);
+ SERIAL_EOL();
+ }
+
+ template
+ FORCE_INLINE void SerialPageManager::set_page_state(const page_idx_t page_idx, const PageState page_state) {
+ CHECK_PAGE(page_idx,);
+
+ page_states[page_idx] = page_state;
+ page_states_dirty = true;
+ }
+
+ template <>
+ FORCE_INLINE uint8_t *PageManager::get_page(const page_idx_t page_idx) {
+ CHECK_PAGE(page_idx, nullptr);
+
+ return pages[page_idx];
+ }
+
+ template <>
+ FORCE_INLINE void PageManager::free_page(const page_idx_t page_idx) {
+ set_page_state(page_idx, PageState::FREE);
+ }
+
+};
+
+DirectStepping::PageManager page_manager;
+
+const uint8_t segment_table[DirectStepping::Config::NUM_SEGMENTS][DirectStepping::Config::SEGMENT_STEPS] PROGMEM = {
+
+ #if STEPPER_PAGE_FORMAT == SP_4x4D_128
+
+ { 1, 1, 1, 1, 1, 1, 1, 0 }, // 0 = -7
+ { 1, 1, 1, 0, 1, 1, 1, 0 }, // 1 = -6
+ { 0, 1, 1, 0, 1, 0, 1, 1 }, // 2 = -5
+ { 0, 1, 0, 1, 0, 1, 0, 1 }, // 3 = -4
+ { 0, 1, 0, 0, 1, 0, 0, 1 }, // 4 = -3
+ { 0, 0, 1, 0, 0, 0, 1, 0 }, // 5 = -2
+ { 0, 0, 0, 0, 1, 0, 0, 0 }, // 6 = -1
+ { 0, 0, 0, 0, 0, 0, 0, 0 }, // 7 = 0
+ { 0, 0, 0, 0, 1, 0, 0, 0 }, // 8 = 1
+ { 0, 0, 1, 0, 0, 0, 1, 0 }, // 9 = 2
+ { 0, 1, 0, 0, 1, 0, 0, 1 }, // 10 = 3
+ { 0, 1, 0, 1, 0, 1, 0, 1 }, // 11 = 4
+ { 0, 1, 1, 0, 1, 0, 1, 1 }, // 12 = 5
+ { 1, 1, 1, 0, 1, 1, 1, 0 }, // 13 = 6
+ { 1, 1, 1, 1, 1, 1, 1, 0 }, // 14 = 7
+ { 0 }
+
+ #elif STEPPER_PAGE_FORMAT == SP_4x2_256
+
+ { 0, 0, 0, 0 }, // 0
+ { 0, 1, 0, 0 }, // 1
+ { 1, 0, 1, 0 }, // 2
+ { 1, 1, 1, 0 }, // 3
+
+ #elif STEPPER_PAGE_FORMAT == SP_4x1_512
+
+ {0} // Uncompressed format, table not used
+
+ #endif
+
+};
+
+#endif // DIRECT_STEPPING
diff --git a/Marlin/src/feature/direct_stepping.h b/Marlin/src/feature/direct_stepping.h
new file mode 100644
index 000000000..dea261650
--- /dev/null
+++ b/Marlin/src/feature/direct_stepping.h
@@ -0,0 +1,137 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#pragma once
+
+#include "../inc/MarlinConfig.h"
+
+namespace DirectStepping {
+
+ enum State : char {
+ MONITOR, NEWLINE, ADDRESS, SIZE, COLLECT, CHECKSUM, UNFAIL
+ };
+
+ enum PageState : uint8_t {
+ FREE, WRITING, OK, FAIL
+ };
+
+ // Static state used for stepping through direct stepping pages
+ struct page_step_state_t {
+ // Current page
+ uint8_t *page;
+ // Current segment
+ uint16_t segment_idx;
+ // Current steps within segment
+ uint8_t segment_steps;
+ // Segment delta
+ xyze_uint8_t sd;
+ // Block delta
+ xyze_int_t bd;
+ };
+
+ template
+ class SerialPageManager {
+ public:
+
+ typedef typename Cfg::page_idx_t page_idx_t;
+
+ static bool maybe_store_rxd_char(uint8_t c);
+ static void write_responses();
+
+ // common methods for page managers
+ static void init();
+ static uint8_t *get_page(const page_idx_t page_idx);
+ static void free_page(const page_idx_t page_idx);
+
+ protected:
+
+ typedef typename Cfg::write_byte_idx_t write_byte_idx_t;
+
+ static State state;
+ static volatile bool fatal_error;
+
+ static volatile PageState page_states[Cfg::NUM_PAGES];
+ static volatile bool page_states_dirty;
+ static millis_t next_response;
+
+ static uint8_t pages[Cfg::NUM_PAGES][Cfg::PAGE_SIZE];
+ static uint8_t checksum;
+ static write_byte_idx_t write_byte_idx;
+ static page_idx_t write_page_idx;
+ static write_byte_idx_t write_page_size;
+
+ static void set_page_state(const page_idx_t page_idx, const PageState page_state);
+ };
+
+ template struct TypeSelector { typedef T type;} ;
+ template struct TypeSelector { typedef F type; };
+
+ template
+ struct config_t {
+ static constexpr char CONTROL_CHAR = '!';
+
+ static constexpr int NUM_PAGES = num_pages;
+ static constexpr int NUM_AXES = num_axes;
+ static constexpr int BITS_SEGMENT = bits_segment;
+ static constexpr int DIRECTIONAL = dir ? 1 : 0;
+ static constexpr int SEGMENTS = segments;
+
+ static constexpr int RAW = (BITS_SEGMENT == 1) ? 1 : 0;
+ static constexpr int NUM_SEGMENTS = 1 << BITS_SEGMENT;
+ static constexpr int SEGMENT_STEPS = 1 << (BITS_SEGMENT - DIRECTIONAL - RAW);
+ static constexpr int TOTAL_STEPS = SEGMENT_STEPS * SEGMENTS;
+ static constexpr int PAGE_SIZE = (NUM_AXES * BITS_SEGMENT * SEGMENTS) / 8;
+
+ static constexpr millis_t RESPONSE_INTERVAL_MS = 50;
+
+ typedef typename TypeSelector<(PAGE_SIZE>256), uint16_t, uint8_t>::type write_byte_idx_t;
+ typedef typename TypeSelector<(NUM_PAGES>256), uint16_t, uint8_t>::type page_idx_t;
+ };
+
+ template
+ using SP_4x4D_128 = config_t;
+
+ template
+ using SP_4x2_256 = config_t;
+
+ template
+ using SP_4x1_512 = config_t;
+
+ // configured types
+ typedef STEPPER_PAGE_FORMAT Config;
+
+ template class PAGE_MANAGER;
+ typedef PAGE_MANAGER PageManager;
+};
+
+#define SP_4x4D_128 1
+//#define SP_4x4_128 2
+//#define SP_4x2D_256 3
+#define SP_4x2_256 4
+#define SP_4x1_512 5
+
+typedef typename DirectStepping::Config::page_idx_t page_idx_t;
+
+// TODO: use config
+typedef DirectStepping::page_step_state_t page_step_state_t;
+
+extern const uint8_t segment_table[DirectStepping::Config::NUM_SEGMENTS][DirectStepping::Config::SEGMENT_STEPS];
+extern DirectStepping::PageManager page_manager;
diff --git a/Marlin/src/feature/e_parser.cpp b/Marlin/src/feature/e_parser.cpp
index e7d79bf74..85b1845a6 100644
--- a/Marlin/src/feature/e_parser.cpp
+++ b/Marlin/src/feature/e_parser.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/feature/e_parser.h b/Marlin/src/feature/e_parser.h
index 41261402a..73e459680 100644
--- a/Marlin/src/feature/e_parser.h
+++ b/Marlin/src/feature/e_parser.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp
index a70227a27..f67d50a6e 100644
--- a/Marlin/src/feature/encoder_i2c.cpp
+++ b/Marlin/src/feature/encoder_i2c.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -107,7 +107,7 @@ void I2CPositionEncoder::update() {
SERIAL_ECHOLNPAIR("New zero-offset of ", zeroOffset);
SERIAL_ECHOPAIR("New position reads as ", get_position());
SERIAL_CHAR('(');
- SERIAL_ECHO(mm_from_count(get_position()));
+ SERIAL_DECIMAL(mm_from_count(get_position()));
SERIAL_ECHOLNPGM(")");
#endif
}
@@ -305,7 +305,7 @@ int32_t I2CPositionEncoder::get_raw_count() {
encoderCount.val = 0x00;
- if (Wire.requestFrom((int)i2cAddress, 3) != 3) {
+ if (Wire.requestFrom(I2C_ADDRESS(i2cAddress), uint8_t(3)) != 3) {
//houston, we have a problem...
H = I2CPE_MAG_SIG_NF;
return 0;
@@ -459,9 +459,7 @@ void I2CPositionEncoder::reset() {
Wire.write(I2CPE_RESET_COUNT);
Wire.endTransmission();
- #if ENABLED(I2CPE_ERR_ROLLING_AVERAGE)
- ZERO(err);
- #endif
+ TERN_(I2CPE_ERR_ROLLING_AVERAGE, ZERO(err));
}
@@ -746,7 +744,7 @@ void I2CPositionEncodersMgr::report_module_firmware(const uint8_t address) {
Wire.endTransmission();
// Read value
- if (Wire.requestFrom((int)address, 32)) {
+ if (Wire.requestFrom(I2C_ADDRESS(address), uint8_t(32))) {
char c;
while (Wire.available() > 0 && (c = (char)Wire.read()) > 0)
SERIAL_ECHO(c);
diff --git a/Marlin/src/feature/encoder_i2c.h b/Marlin/src/feature/encoder_i2c.h
index 0665ee809..511e560ba 100644
--- a/Marlin/src/feature/encoder_i2c.h
+++ b/Marlin/src/feature/encoder_i2c.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -280,13 +280,13 @@ class I2CPositionEncodersMgr {
static void set_ec_threshold(const int8_t idx, const float newThreshold, const AxisEnum axis) {
CHECK_IDX();
encoders[idx].set_ec_threshold(newThreshold);
- SERIAL_ECHOLNPAIR("Error correct threshold for ", axis_codes[axis], " axis set to ", FIXFLOAT(newThreshold), "mm.");
+ SERIAL_ECHOLNPAIR("Error correct threshold for ", axis_codes[axis], " axis set to ", newThreshold, "mm.");
}
static void get_ec_threshold(const int8_t idx, const AxisEnum axis) {
CHECK_IDX();
const float threshold = encoders[idx].get_ec_threshold();
- SERIAL_ECHOLNPAIR("Error correct threshold for ", axis_codes[axis], " axis is ", FIXFLOAT(threshold), "mm.");
+ SERIAL_ECHOLNPAIR("Error correct threshold for ", axis_codes[axis], " axis is ", threshold, "mm.");
}
static int8_t idx_from_axis(const AxisEnum axis) {
diff --git a/Marlin/src/feature/fanmux.cpp b/Marlin/src/feature/fanmux.cpp
index b90c72c64..43952ca8e 100644
--- a/Marlin/src/feature/fanmux.cpp
+++ b/Marlin/src/feature/fanmux.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/feature/fanmux.h b/Marlin/src/feature/fanmux.h
index 2e5414447..b1b0c67a5 100644
--- a/Marlin/src/feature/fanmux.h
+++ b/Marlin/src/feature/fanmux.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/filwidth.cpp b/Marlin/src/feature/filwidth.cpp
index 4357d39fe..2bd9c7898 100644
--- a/Marlin/src/feature/filwidth.cpp
+++ b/Marlin/src/feature/filwidth.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/feature/filwidth.h b/Marlin/src/feature/filwidth.h
index 335a49b74..ef3859df7 100644
--- a/Marlin/src/feature/filwidth.h
+++ b/Marlin/src/feature/filwidth.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/fwretract.cpp b/Marlin/src/feature/fwretract.cpp
index 7d756ac6d..c0e4db0a4 100644
--- a/Marlin/src/feature/fwretract.cpp
+++ b/Marlin/src/feature/fwretract.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -60,9 +60,7 @@ float FWRetract::current_retract[EXTRUDERS], // Retract value used by p
FWRetract::current_hop;
void FWRetract::reset() {
- #if ENABLED(FWRETRACT_AUTORETRACT)
- autoretract_enabled = false;
- #endif
+ TERN_(FWRETRACT_AUTORETRACT, autoretract_enabled = false);
settings.retract_length = RETRACT_LENGTH;
settings.retract_feedrate_mm_s = RETRACT_FEEDRATE;
settings.retract_zraise = RETRACT_ZRAISE;
@@ -95,7 +93,7 @@ void FWRetract::reset() {
*/
void FWRetract::retract(const bool retracting
#if EXTRUDERS > 1
- , bool swapping /* =false */
+ , bool swapping/*=false*/
#endif
) {
// Prevent two retracts or recovers in a row
@@ -128,12 +126,8 @@ void FWRetract::retract(const bool retracting
SERIAL_ECHOLNPAIR("current_hop ", current_hop);
//*/
- const float base_retract = (
- (swapping ? settings.swap_retract_length : settings.retract_length)
- #if ENABLED(RETRACT_SYNC_MIXING)
- * (MIXING_STEPPERS)
- #endif
- );
+ const float base_retract = TERN1(RETRACT_SYNC_MIXING, (MIXING_STEPPERS))
+ * (swapping ? settings.swap_retract_length : settings.retract_length);
// The current position will be the destination for E and Z moves
destination = current_position;
@@ -148,10 +142,7 @@ void FWRetract::retract(const bool retracting
// Retract by moving from a faux E position back to the current E position
current_retract[active_extruder] = base_retract;
prepare_internal_move_to_destination( // set current to destination
- settings.retract_feedrate_mm_s
- #if ENABLED(RETRACT_SYNC_MIXING)
- * (MIXING_STEPPERS)
- #endif
+ settings.retract_feedrate_mm_s * TERN1(RETRACT_SYNC_MIXING, (MIXING_STEPPERS))
);
// Is a Z hop set, and has the hop not yet been done?
@@ -177,18 +168,14 @@ void FWRetract::retract(const bool retracting
current_retract[active_extruder] = 0;
- const feedRate_t fr_mm_s = (
+ // Recover E, set_current_to_destination
+ prepare_internal_move_to_destination(
(swapping ? settings.swap_retract_recover_feedrate_mm_s : settings.retract_recover_feedrate_mm_s)
- #if ENABLED(RETRACT_SYNC_MIXING)
- * (MIXING_STEPPERS)
- #endif
+ * TERN1(RETRACT_SYNC_MIXING, (MIXING_STEPPERS))
);
- prepare_internal_move_to_destination(fr_mm_s); // Recover E, set_current_to_destination
}
- #if ENABLED(RETRACT_SYNC_MIXING)
- mixer.T(old_mixing_tool); // Restore original mixing tool
- #endif
+ TERN_(RETRACT_SYNC_MIXING, mixer.T(old_mixing_tool)); // Restore original mixing tool
retracted[active_extruder] = retracting; // Active extruder now retracted / recovered
diff --git a/Marlin/src/feature/fwretract.h b/Marlin/src/feature/fwretract.h
index e08f8f03a..3d6873642 100644
--- a/Marlin/src/feature/fwretract.h
+++ b/Marlin/src/feature/fwretract.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/host_actions.cpp b/Marlin/src/feature/host_actions.cpp
index 2108f4e7f..9539c82b6 100644
--- a/Marlin/src/feature/host_actions.cpp
+++ b/Marlin/src/feature/host_actions.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -37,7 +37,8 @@
#include "runout.h"
#endif
-void host_action(const char * const pstr, const bool eol) {
+void host_action(PGM_P const pstr, const bool eol) {
+ PORT_REDIRECT(SERIAL_BOTH);
SERIAL_ECHOPGM("//action:");
serialprintPGM(pstr);
if (eol) SERIAL_EOL();
@@ -64,8 +65,8 @@ void host_action(const char * const pstr, const bool eol) {
#if ENABLED(HOST_PROMPT_SUPPORT)
- const char CONTINUE_STR[] PROGMEM = "Continue",
- DISMISS_STR[] PROGMEM = "Dismiss";
+ PGMSTR(CONTINUE_STR, "Continue");
+ PGMSTR(DISMISS_STR, "Dismiss");
#if HAS_RESUME_CONTINUE
extern bool wait_for_user;
@@ -74,33 +75,42 @@ void host_action(const char * const pstr, const bool eol) {
PromptReason host_prompt_reason = PROMPT_NOT_DEFINED;
void host_action_notify(const char * const message) {
+ PORT_REDIRECT(SERIAL_BOTH);
+ host_action(PSTR("notification "), false);
+ SERIAL_ECHOLN(message);
+ }
+
+ void host_action_notify_P(PGM_P const message) {
+ PORT_REDIRECT(SERIAL_BOTH);
host_action(PSTR("notification "), false);
serialprintPGM(message);
SERIAL_EOL();
}
- void host_action_prompt(const char * const ptype, const bool eol=true) {
+ void host_action_prompt(PGM_P const ptype, const bool eol=true) {
+ PORT_REDIRECT(SERIAL_BOTH);
host_action(PSTR("prompt_"), false);
serialprintPGM(ptype);
if (eol) SERIAL_EOL();
}
- void host_action_prompt_plus(const char * const ptype, const char * const pstr, const char extra_char='\0') {
+ void host_action_prompt_plus(PGM_P const ptype, PGM_P const pstr, const char extra_char='\0') {
host_action_prompt(ptype, false);
+ PORT_REDIRECT(SERIAL_BOTH);
SERIAL_CHAR(' ');
serialprintPGM(pstr);
if (extra_char != '\0') SERIAL_CHAR(extra_char);
SERIAL_EOL();
}
- void host_action_prompt_begin(const PromptReason reason, const char * const pstr, const char extra_char/*='\0'*/) {
+ void host_action_prompt_begin(const PromptReason reason, PGM_P const pstr, const char extra_char/*='\0'*/) {
host_action_prompt_end();
host_prompt_reason = reason;
host_action_prompt_plus(PSTR("begin"), pstr, extra_char);
}
- void host_action_prompt_button(const char * const pstr) { host_action_prompt_plus(PSTR("button"), pstr); }
+ void host_action_prompt_button(PGM_P const pstr) { host_action_prompt_plus(PSTR("button"), pstr); }
void host_action_prompt_end() { host_action_prompt(PSTR("end")); }
void host_action_prompt_show() { host_action_prompt(PSTR("show")); }
- void host_prompt_do(const PromptReason reason, const char * const pstr, const char * const btn1/*=nullptr*/, const char * const btn2/*=nullptr*/) {
+ void host_prompt_do(const PromptReason reason, PGM_P const pstr, PGM_P const btn1/*=nullptr*/, PGM_P const btn2/*=nullptr*/) {
host_action_prompt_begin(reason, pstr);
if (btn1) host_action_prompt_button(btn1);
if (btn2) host_action_prompt_button(btn2);
@@ -108,11 +118,7 @@ void host_action(const char * const pstr, const bool eol) {
}
void filament_load_host_prompt() {
- const bool disable_to_continue = (false
- #if HAS_FILAMENT_SENSOR
- || runout.filament_ran_out
- #endif
- );
+ const bool disable_to_continue = TERN0(HAS_FILAMENT_SENSOR, runout.filament_ran_out);
host_prompt_do(PROMPT_FILAMENT_RUNOUT, PSTR("Paused"), PSTR("PurgeMore"),
disable_to_continue ? PSTR("DisableRunout") : CONTINUE_STR
);
@@ -127,11 +133,11 @@ void host_action(const char * const pstr, const bool eol) {
//
void host_response_handler(const uint8_t response) {
#ifdef DEBUG_HOST_ACTIONS
- static const char m876_prefix[] PROGMEM = "M876 Handle Re";
+ static PGMSTR(m876_prefix, "M876 Handle Re");
serialprintPGM(m876_prefix); SERIAL_ECHOLNPAIR("ason: ", host_prompt_reason);
serialprintPGM(m876_prefix); SERIAL_ECHOLNPAIR("sponse: ", response);
#endif
- const char *msg = PSTR("UNKNOWN STATE");
+ PGM_P msg = PSTR("UNKNOWN STATE");
const PromptReason hpr = host_prompt_reason;
host_prompt_reason = PROMPT_NOT_DEFINED; // Reset now ahead of logic
switch (hpr) {
@@ -140,14 +146,14 @@ void host_action(const char * const pstr, const bool eol) {
switch (response) {
case 0: // "Purge More" button
- #if HAS_LCD_MENU && ENABLED(ADVANCED_PAUSE_FEATURE)
+ #if BOTH(HAS_LCD_MENU, ADVANCED_PAUSE_FEATURE)
pause_menu_response = PAUSE_RESPONSE_EXTRUDE_MORE; // Simulate menu selection (menu exits, doesn't extrude more)
#endif
filament_load_host_prompt(); // Initiate another host prompt. (NOTE: The loop in load_filament may also do this!)
break;
case 1: // "Continue" / "Disable Runout" button
- #if HAS_LCD_MENU && ENABLED(ADVANCED_PAUSE_FEATURE)
+ #if BOTH(HAS_LCD_MENU, ADVANCED_PAUSE_FEATURE)
pause_menu_response = PAUSE_RESPONSE_RESUME_PRINT; // Simulate menu selection
#endif
#if HAS_FILAMENT_SENSOR
@@ -160,9 +166,7 @@ void host_action(const char * const pstr, const bool eol) {
}
break;
case PROMPT_USER_CONTINUE:
- #if HAS_RESUME_CONTINUE
- wait_for_user = false;
- #endif
+ TERN_(HAS_RESUME_CONTINUE, wait_for_user = false);
msg = PSTR("FILAMENT_RUNOUT_CONTINUE");
break;
case PROMPT_PAUSE_RESUME:
diff --git a/Marlin/src/feature/host_actions.h b/Marlin/src/feature/host_actions.h
index 3667b7f43..a6ad2c048 100644
--- a/Marlin/src/feature/host_actions.h
+++ b/Marlin/src/feature/host_actions.h
@@ -16,14 +16,15 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
#include "../inc/MarlinConfigPre.h"
+#include "../HAL/shared/Marduino.h"
-void host_action(const char * const pstr, const bool eol=true);
+void host_action(PGM_P const pstr, const bool eol=true);
#ifdef ACTION_ON_KILL
void host_action_kill();
@@ -61,12 +62,13 @@ void host_action(const char * const pstr, const bool eol=true);
void host_response_handler(const uint8_t response);
void host_action_notify(const char * const message);
- void host_action_prompt_begin(const PromptReason reason, const char * const pstr, const char extra_char='\0');
- void host_action_prompt_button(const char * const pstr);
+ void host_action_notify_P(PGM_P const message);
+ void host_action_prompt_begin(const PromptReason reason, PGM_P const pstr, const char extra_char='\0');
+ void host_action_prompt_button(PGM_P const pstr);
void host_action_prompt_end();
void host_action_prompt_show();
- void host_prompt_do(const PromptReason reason, const char * const pstr, const char * const btn1=nullptr, const char * const btn2=nullptr);
- inline void host_prompt_open(const PromptReason reason, const char * const pstr, const char * const btn1=nullptr, const char * const btn2=nullptr) {
+ void host_prompt_do(const PromptReason reason, PGM_P const pstr, PGM_P const btn1=nullptr, PGM_P const btn2=nullptr);
+ inline void host_prompt_open(const PromptReason reason, PGM_P const pstr, PGM_P const btn1=nullptr, PGM_P const btn2=nullptr) {
if (host_prompt_reason == PROMPT_NOT_DEFINED) host_prompt_do(reason, pstr, btn1, btn2);
}
diff --git a/Marlin/src/feature/hotend_idle.cpp b/Marlin/src/feature/hotend_idle.cpp
new file mode 100644
index 000000000..9d5594c2f
--- /dev/null
+++ b/Marlin/src/feature/hotend_idle.cpp
@@ -0,0 +1,89 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+
+/**
+ * Hotend Idle Timeout
+ * Prevent filament in the nozzle from charring and causing a critical jam.
+ */
+
+#include "../inc/MarlinConfig.h"
+
+#if ENABLED(HOTEND_IDLE_TIMEOUT)
+
+#include "hotend_idle.h"
+#include "../gcode/gcode.h"
+
+#include "../module/temperature.h"
+#include "../module/motion.h"
+#include "../lcd/ultralcd.h"
+
+extern HotendIdleProtection hotend_idle;
+
+millis_t HotendIdleProtection::next_protect_ms = 0;
+
+void HotendIdleProtection::check_hotends(const millis_t &ms) {
+ bool do_prot = false;
+ HOTEND_LOOP() {
+ if (thermalManager.degHotend(e) >= HOTEND_IDLE_MIN_TRIGGER) {
+ do_prot = true; break;
+ }
+ }
+ if (bool(next_protect_ms) != do_prot)
+ next_protect_ms = do_prot ? ms + hp_interval : 0;
+}
+
+void HotendIdleProtection::check_e_motion(const millis_t &ms) {
+ static float old_e_position = 0;
+ if (old_e_position != current_position.e) {
+ old_e_position = current_position.e; // Track filament motion
+ if (next_protect_ms) // If some heater is on then...
+ next_protect_ms = ms + hp_interval; // ...delay the timeout till later
+ }
+}
+
+void HotendIdleProtection::check() {
+ const millis_t ms = millis(); // Shared millis
+
+ check_hotends(ms); // Any hotends need protection?
+ check_e_motion(ms); // Motion will protect them
+
+ // Hot and not moving for too long...
+ if (next_protect_ms && ELAPSED(ms, next_protect_ms))
+ timed_out();
+}
+
+// Lower (but don't raise) hotend / bed temperatures
+void HotendIdleProtection::timed_out() {
+ next_protect_ms = 0;
+ SERIAL_ECHOLNPGM("Hotend Idle Timeout");
+ LCD_MESSAGEPGM(MSG_HOTEND_IDLE_TIMEOUT);
+ HOTEND_LOOP() {
+ if ((HOTEND_IDLE_NOZZLE_TARGET) < thermalManager.degTargetHotend(e))
+ thermalManager.setTargetHotend(HOTEND_IDLE_NOZZLE_TARGET, e);
+ }
+ #if HAS_HEATED_BED
+ if ((HOTEND_IDLE_BED_TARGET) < thermalManager.degTargetBed())
+ thermalManager.setTargetBed(HOTEND_IDLE_BED_TARGET);
+ #endif
+}
+
+#endif // HOTEND_IDLE_TIMEOUT
diff --git a/Marlin/src/feature/hotend_idle.h b/Marlin/src/feature/hotend_idle.h
new file mode 100644
index 000000000..40f557d5e
--- /dev/null
+++ b/Marlin/src/feature/hotend_idle.h
@@ -0,0 +1,37 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#pragma once
+
+#include "../core/millis_t.h"
+
+class HotendIdleProtection {
+public:
+ static void check();
+private:
+ static constexpr millis_t hp_interval = SEC_TO_MS(HOTEND_IDLE_TIMEOUT_SEC);
+ static millis_t next_protect_ms;
+ static void check_hotends(const millis_t &ms);
+ static void check_e_motion(const millis_t &ms);
+ static void timed_out();
+};
+
+extern HotendIdleProtection hotend_idle;
diff --git a/Marlin/src/feature/joystick.cpp b/Marlin/src/feature/joystick.cpp
index 66afb63b0..d9c5ae7c1 100644
--- a/Marlin/src/feature/joystick.cpp
+++ b/Marlin/src/feature/joystick.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -154,9 +154,7 @@ Joystick joystick;
// Other non-joystick poll-based jogging could be implemented here
// with "jogging" encapsulated as a more general class.
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::_joystick_update(norm_jog);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::_joystick_update(norm_jog));
// norm_jog values of [-1 .. 1] maps linearly to [-feedrate .. feedrate]
xyz_float_t move_dist{0};
diff --git a/Marlin/src/feature/joystick.h b/Marlin/src/feature/joystick.h
index 12f9554a7..ca4683457 100644
--- a/Marlin/src/feature/joystick.h
+++ b/Marlin/src/feature/joystick.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -35,19 +35,11 @@
class Joystick {
friend class Temperature;
private:
- #if HAS_JOY_ADC_X
- static temp_info_t x;
- #endif
- #if HAS_JOY_ADC_Y
- static temp_info_t y;
- #endif
- #if HAS_JOY_ADC_Z
- static temp_info_t z;
- #endif
+ TERN_(HAS_JOY_ADC_X, static temp_info_t x);
+ TERN_(HAS_JOY_ADC_Y, static temp_info_t y);
+ TERN_(HAS_JOY_ADC_Z, static temp_info_t z);
public:
- #if ENABLED(JOYSTICK_DEBUG)
- static void report();
- #endif
+ TERN_(JOYSTICK_DEBUG, static void report());
static void calculate(xyz_float_t &norm_jog);
static void inject_jog_moves();
};
diff --git a/Marlin/src/feature/leds/blinkm.cpp b/Marlin/src/feature/leds/blinkm.cpp
index 1c7ceeb66..868eb4b3d 100644
--- a/Marlin/src/feature/leds/blinkm.cpp
+++ b/Marlin/src/feature/leds/blinkm.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/feature/leds/blinkm.h b/Marlin/src/feature/leds/blinkm.h
index c7c099d3a..29a9e7841 100644
--- a/Marlin/src/feature/leds/blinkm.h
+++ b/Marlin/src/feature/leds/blinkm.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp
index 995693ffc..eec0cde63 100644
--- a/Marlin/src/feature/leds/leds.cpp
+++ b/Marlin/src/feature/leds/leds.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -39,7 +39,7 @@
#endif
#if ENABLED(PCA9533)
- #include
+ #include "pca9533.h"
#endif
#if ENABLED(LED_COLOR_PRESETS)
@@ -68,15 +68,9 @@ void LEDLights::setup() {
if (PWM_PIN(RGB_LED_W_PIN)) SET_PWM(RGB_LED_W_PIN); else SET_OUTPUT(RGB_LED_W_PIN);
#endif
#endif
- #if ENABLED(NEOPIXEL_LED)
- neo.init();
- #endif
- #if ENABLED(PCA9533)
- RGBinit();
- #endif
- #if ENABLED(LED_USER_PRESET_STARTUP)
- set_default();
- #endif
+ TERN_(NEOPIXEL_LED, neo.init());
+ TERN_(PCA9533, PCA9533_init());
+ TERN_(LED_USER_PRESET_STARTUP, set_default());
}
void LEDLights::set_color(const LEDColor &incol
@@ -140,9 +134,7 @@ void LEDLights::set_color(const LEDColor &incol
pca9632_set_led_color(incol);
#endif
- #if ENABLED(PCA9533)
- RGBsetColor(incol.r, incol.g, incol.b, true);
- #endif
+ TERN_(PCA9533, PCA9533_setColor(incol.r, incol.g, incol.b));
#if EITHER(LED_CONTROL_MENU, PRINTER_EVENT_LEDS)
// Don't update the color when OFF
diff --git a/Marlin/src/feature/leds/leds.h b/Marlin/src/feature/leds/leds.h
index 22184381f..577c94752 100644
--- a/Marlin/src/feature/leds/leds.h
+++ b/Marlin/src/feature/leds/leds.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -34,7 +34,9 @@
#endif
// A white component can be passed
-#define HAS_WHITE_LED EITHER(RGBW_LED, NEOPIXEL_LED)
+#if EITHER(RGBW_LED, NEOPIXEL_LED)
+ #define HAS_WHITE_LED 1
+#endif
/**
* LEDcolor type for use with leds.set_color
@@ -85,9 +87,7 @@ typedef struct LEDColor {
LEDColor& operator=(const uint8_t (&rgbw)[4]) {
r = rgbw[0]; g = rgbw[1]; b = rgbw[2];
- #if HAS_WHITE_LED
- w = rgbw[3];
- #endif
+ TERN_(HAS_WHITE_LED, w = rgbw[3]);
return *this;
}
diff --git a/Marlin/src/feature/leds/neopixel.cpp b/Marlin/src/feature/leds/neopixel.cpp
index 892ebe15c..5d80cfe5d 100644
--- a/Marlin/src/feature/leds/neopixel.cpp
+++ b/Marlin/src/feature/leds/neopixel.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -35,6 +35,7 @@
#endif
Marlin_NeoPixel neo;
+int8_t Marlin_NeoPixel::neoindex;
Adafruit_NeoPixel Marlin_NeoPixel::adaneo1(NEOPIXEL_PIXELS, NEOPIXEL_PIN, NEOPIXEL_TYPE + NEO_KHZ800)
#if MULTIPLE_NEOPIXEL_TYPES
@@ -52,14 +53,20 @@ Adafruit_NeoPixel Marlin_NeoPixel::adaneo1(NEOPIXEL_PIXELS, NEOPIXEL_PIN, NEOPIX
#endif
void Marlin_NeoPixel::set_color(const uint32_t color) {
- for (uint16_t i = 0; i < pixels(); ++i) {
- #ifdef NEOPIXEL_BKGD_LED_INDEX
- if (i == NEOPIXEL_BKGD_LED_INDEX && color != 0x000000) {
- set_color_background();
- continue;
- }
- #endif
- set_pixel_color(i, color);
+ if (get_neo_index() >= 0) {
+ set_pixel_color(get_neo_index(), color);
+ set_neo_index(-1);
+ }
+ else {
+ for (uint16_t i = 0; i < pixels(); ++i) {
+ #ifdef NEOPIXEL_BKGD_LED_INDEX
+ if (i == NEOPIXEL_BKGD_LED_INDEX && color != 0x000000) {
+ set_color_background();
+ continue;
+ }
+ #endif
+ set_pixel_color(i, color);
+ }
}
show();
}
@@ -71,13 +78,12 @@ void Marlin_NeoPixel::set_color_startup(const uint32_t color) {
}
void Marlin_NeoPixel::init() {
- SET_OUTPUT(NEOPIXEL_PIN);
- set_brightness(NEOPIXEL_BRIGHTNESS); // 0 - 255 range
+ set_neo_index(-1); // -1 .. NEOPIXEL_PIXELS-1 range
+ set_brightness(NEOPIXEL_BRIGHTNESS); // 0 .. 255 range
begin();
show(); // initialize to all off
#if ENABLED(NEOPIXEL_STARTUP_TEST)
- safe_delay(1000);
set_color_startup(adaneo1.Color(255, 0, 0, 0)); // red
safe_delay(1000);
set_color_startup(adaneo1.Color(0, 255, 0, 0)); // green
diff --git a/Marlin/src/feature/leds/neopixel.h b/Marlin/src/feature/leds/neopixel.h
index 11e435b83..17057498d 100644
--- a/Marlin/src/feature/leds/neopixel.h
+++ b/Marlin/src/feature/leds/neopixel.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -38,10 +38,15 @@
// Defines
// ------------------------
-#define MULTIPLE_NEOPIXEL_TYPES (defined(NEOPIXEL2_TYPE) && (NEOPIXEL2_TYPE != NEOPIXEL_TYPE))
+#if defined(NEOPIXEL2_TYPE) && NEOPIXEL2_TYPE != NEOPIXEL_TYPE
+ #define MULTIPLE_NEOPIXEL_TYPES 1
+#endif
-#define NEOPIXEL_IS_RGB (NEOPIXEL_TYPE == NEO_RGB || NEOPIXEL_TYPE == NEO_RBG || NEOPIXEL_TYPE == NEO_GRB || NEOPIXEL_TYPE == NEO_GBR || NEOPIXEL_TYPE == NEO_BRG || NEOPIXEL_TYPE == NEO_BGR)
-#define NEOPIXEL_IS_RGBW !NEOPIXEL_IS_RGB
+#if NEOPIXEL_TYPE == NEO_RGB || NEOPIXEL_TYPE == NEO_RBG || NEOPIXEL_TYPE == NEO_GRB || NEOPIXEL_TYPE == NEO_GBR || NEOPIXEL_TYPE == NEO_BRG || NEOPIXEL_TYPE == NEO_BGR
+ #define NEOPIXEL_IS_RGB 1
+#else
+ #define NEOPIXEL_IS_RGBW 1
+#endif
#if NEOPIXEL_IS_RGB
#define NEO_WHITE 255, 255, 255, 0
@@ -60,6 +65,7 @@ private:
, adaneo2
#endif
;
+ static int8_t neoindex;
public:
static void init();
@@ -67,29 +73,26 @@ public:
static void set_color(const uint32_t c);
+ FORCE_INLINE static void set_neo_index(const int8_t neoIndex) { neoindex = neoIndex; }
+ FORCE_INLINE static int8_t get_neo_index() { return neoindex; }
+
#ifdef NEOPIXEL_BKGD_LED_INDEX
static void set_color_background();
#endif
static inline void begin() {
adaneo1.begin();
- #if MULTIPLE_NEOPIXEL_TYPES
- adaneo2.begin();
- #endif
+ TERN_(MULTIPLE_NEOPIXEL_TYPES, adaneo2.begin());
}
static inline void set_pixel_color(const uint16_t n, const uint32_t c) {
adaneo1.setPixelColor(n, c);
- #if MULTIPLE_NEOPIXEL_TYPES
- adaneo2.setPixelColor(n, c);
- #endif
+ TERN_(MULTIPLE_NEOPIXEL_TYPES, adaneo2.setPixelColor(n, c));
}
static inline void set_brightness(const uint8_t b) {
adaneo1.setBrightness(b);
- #if MULTIPLE_NEOPIXEL_TYPES
- adaneo2.setBrightness(b);
- #endif
+ TERN_(MULTIPLE_NEOPIXEL_TYPES, adaneo2.setBrightness(b));
}
static inline void show() {
diff --git a/Marlin/src/feature/leds/pca9533.cpp b/Marlin/src/feature/leds/pca9533.cpp
new file mode 100644
index 000000000..bcc4bc50a
--- /dev/null
+++ b/Marlin/src/feature/leds/pca9533.cpp
@@ -0,0 +1,127 @@
+/*
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+
+/**
+ * PCA9533 LED controller driver (MightyBoard, FlashForge Creator Pro, etc.)
+ * by @grauerfuchs - 1 Apr 2020
+ */
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(PCA9533)
+
+#include "pca9533.h"
+#include
+
+void PCA9533_init() {
+ Wire.begin();
+ PCA9533_reset();
+}
+
+static void PCA9533_writeAllRegisters(uint8_t psc0, uint8_t pwm0, uint8_t psc1, uint8_t pwm1, uint8_t ls0){
+ uint8_t data[6] = { PCA9533_REG_PSC0 | PCA9533_REGM_AI, psc0, pwm0, psc1, pwm1, ls0 };
+ Wire.beginTransmission(PCA9533_Addr >> 1);
+ Wire.write(data, 6);
+ Wire.endTransmission();
+ delayMicroseconds(1);
+}
+
+static void PCA9533_writeRegister(uint8_t reg, uint8_t val){
+ uint8_t data[2] = { reg, val };
+ Wire.beginTransmission(PCA9533_Addr >> 1);
+ Wire.write(data, 2);
+ Wire.endTransmission();
+ delayMicroseconds(1);
+}
+
+// Reset (clear) all registers
+void PCA9533_reset() {
+ PCA9533_writeAllRegisters(0, 0, 0, 0, 0);
+}
+
+// Turn all LEDs off
+void PCA9533_setOff() {
+ PCA9533_writeRegister(PCA9533_REG_SEL, 0);
+}
+
+void PCA9533_setColor(uint8_t red, uint8_t green, uint8_t blue) {
+ uint8_t r_pwm0 = 0; // Register data - PWM value
+ uint8_t r_pwm1 = 0; // Register data - PWM value
+
+ uint8_t op_g = 0, op_r = 0, op_b = 0; // Opcodes - Green, Red, Blue
+
+ // Light theory! GREEN takes priority because
+ // it's the most visible to the human eye.
+ if (green == 0) op_g = PCA9533_LED_OP_OFF;
+ else if (green == 255) op_g = PCA9533_LED_OP_ON;
+ else { r_pwm0 = green; op_g = PCA9533_LED_OP_PWM0; }
+
+ // RED
+ if (red == 0) op_r = PCA9533_LED_OP_OFF;
+ else if (red == 255) op_r = PCA9533_LED_OP_ON;
+ else if (r_pwm0 == 0 || r_pwm0 == red) {
+ r_pwm0 = red; op_r = PCA9533_LED_OP_PWM0;
+ }
+ else {
+ r_pwm1 = red; op_r = PCA9533_LED_OP_PWM1;
+ }
+
+ // BLUE
+ if (blue == 0) op_b = PCA9533_LED_OP_OFF;
+ else if (blue == 255) op_b = PCA9533_LED_OP_ON;
+ else if (r_pwm0 == 0 || r_pwm0 == blue) {
+ r_pwm0 = blue; op_b = PCA9533_LED_OP_PWM0;
+ }
+ else if (r_pwm1 == 0 || r_pwm1 == blue) {
+ r_pwm1 = blue; op_b = PCA9533_LED_OP_PWM1;
+ }
+ else {
+ /**
+ * Conflict. 3 values are requested but only 2 channels exist.
+ * G is on channel 0 and R is on channel 1, so work from there.
+ * Find the closest match, average the values, then use the free channel.
+ */
+ uint8_t dgb = ABS(green - blue),
+ dgr = ABS(green - red),
+ dbr = ABS(blue - red);
+ if (dgb < dgr && dgb < dbr) { // Mix with G on channel 0.
+ op_b = PCA9533_LED_OP_PWM0;
+ r_pwm0 = uint8_t(((uint16_t)green + (uint16_t)blue) / 2);
+ }
+ else if (dbr <= dgr && dbr <= dgb) { // Mix with R on channel 1.
+ op_b = PCA9533_LED_OP_PWM1;
+ r_pwm1 = uint8_t(((uint16_t)red + (uint16_t)blue) / 2);
+ }
+ else { // Mix R+G on 0 and put B on 1.
+ op_r = PCA9533_LED_OP_PWM0;
+ r_pwm0 = uint8_t(((uint16_t)green + (uint16_t)red) / 2);
+ op_b = PCA9533_LED_OP_PWM1;
+ r_pwm1 = blue;
+ }
+ }
+
+ // Write the changes to the hardware
+ PCA9533_writeAllRegisters(0, r_pwm0, 0, r_pwm1,
+ (op_g << PCA9533_LED_OFS_GRN) | (op_r << PCA9533_LED_OFS_RED) | (op_b << PCA9533_LED_OFS_BLU)
+ );
+}
+
+#endif // PCA9533
diff --git a/Marlin/src/feature/leds/pca9533.h b/Marlin/src/feature/leds/pca9533.h
new file mode 100644
index 000000000..899418ff2
--- /dev/null
+++ b/Marlin/src/feature/leds/pca9533.h
@@ -0,0 +1,59 @@
+/*
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#pragma once
+
+/*
+ * Driver for the PCA9533 LED controller found on the MightyBoard
+ * used by FlashForge Creator Pro, MakerBot, etc.
+ * Written 2020 APR 01 by grauerfuchs
+ */
+#include
+
+#define ENABLE_I2C_PULLUPS
+
+// Chip address (for Wire)
+#define PCA9533_Addr 0xC4
+
+// Control registers
+#define PCA9533_REG_READ 0x00
+#define PCA9533_REG_PSC0 0x01
+#define PCA9533_REG_PWM0 0x02
+#define PCA9533_REG_PSC1 0x03
+#define PCA9533_REG_PWM1 0x04
+#define PCA9533_REG_SEL 0x05
+#define PCA9533_REGM_AI 0x10
+
+// LED selector operation
+#define PCA9533_LED_OP_OFF 0B00
+#define PCA9533_LED_OP_ON 0B01
+#define PCA9533_LED_OP_PWM0 0B10
+#define PCA9533_LED_OP_PWM1 0B11
+
+// Select register bit offsets for LED colors
+#define PCA9533_LED_OFS_RED 0
+#define PCA9533_LED_OFS_GRN 2
+#define PCA9533_LED_OFS_BLU 4
+
+void PCA9533_init();
+void PCA9533_reset();
+void PCA9533_setColor(uint8_t red, uint8_t green, uint8_t blue);
+void PCA9533_setOff();
diff --git a/Marlin/src/feature/leds/pca9632.cpp b/Marlin/src/feature/leds/pca9632.cpp
index af9e39b86..df991ded3 100644
--- a/Marlin/src/feature/leds/pca9632.cpp
+++ b/Marlin/src/feature/leds/pca9632.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/feature/leds/pca9632.h b/Marlin/src/feature/leds/pca9632.h
index 749230f65..34aceb31d 100644
--- a/Marlin/src/feature/leds/pca9632.h
+++ b/Marlin/src/feature/leds/pca9632.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/leds/printer_event_leds.cpp b/Marlin/src/feature/leds/printer_event_leds.cpp
index 70eee76b3..58084da83 100644
--- a/Marlin/src/feature/leds/printer_event_leds.cpp
+++ b/Marlin/src/feature/leds/printer_event_leds.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -47,10 +47,10 @@ PrinterEventLEDs printerEventLEDs;
inline void pel_set_rgb(const uint8_t r, const uint8_t g, const uint8_t b) {
leds.set_color(
MakeLEDColor(r, g, b, 0, neo.brightness())
- #if ENABLED(NEOPIXEL_IS_SEQUENTIAL)
- , true
- #endif
- );
+ #if ENABLED(NEOPIXEL_IS_SEQUENTIAL)
+ , true
+ #endif
+ );
}
#endif
diff --git a/Marlin/src/feature/leds/printer_event_leds.h b/Marlin/src/feature/leds/printer_event_leds.h
index d2888705e..0295f9f5a 100644
--- a/Marlin/src/feature/leds/printer_event_leds.h
+++ b/Marlin/src/feature/leds/printer_event_leds.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/leds/tempstat.cpp b/Marlin/src/feature/leds/tempstat.cpp
index 2d7afdcf9..880258f85 100644
--- a/Marlin/src/feature/leds/tempstat.cpp
+++ b/Marlin/src/feature/leds/tempstat.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -36,10 +36,7 @@ void handle_status_leds() {
static millis_t next_status_led_update_ms = 0;
if (ELAPSED(millis(), next_status_led_update_ms)) {
next_status_led_update_ms += 500; // Update every 0.5s
- float max_temp = 0.0;
- #if HAS_HEATED_BED
- max_temp = _MAX(thermalManager.degTargetBed(), thermalManager.degBed());
- #endif
+ float max_temp = TERN0(HAS_HEATED_BED, _MAX(thermalManager.degTargetBed(), thermalManager.degBed()));
HOTEND_LOOP()
max_temp = _MAX(max_temp, thermalManager.degHotend(e), thermalManager.degTargetHotend(e));
const int8_t new_red = (max_temp > 55.0) ? HIGH : (max_temp < 54.0 || old_red < 0) ? LOW : old_red;
diff --git a/Marlin/src/feature/leds/tempstat.h b/Marlin/src/feature/leds/tempstat.h
index fefe776cf..a8b919bd8 100644
--- a/Marlin/src/feature/leds/tempstat.h
+++ b/Marlin/src/feature/leds/tempstat.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/max7219.cpp b/Marlin/src/feature/max7219.cpp
index a012aeb5f..ebcb56490 100644
--- a/Marlin/src/feature/max7219.cpp
+++ b/Marlin/src/feature/max7219.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/feature/max7219.h b/Marlin/src/feature/max7219.h
index 19170b2d5..8e98c9456 100644
--- a/Marlin/src/feature/max7219.h
+++ b/Marlin/src/feature/max7219.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/mixing.cpp b/Marlin/src/feature/mixing.cpp
index d6ae2bb62..7de4eb79e 100644
--- a/Marlin/src/feature/mixing.cpp
+++ b/Marlin/src/feature/mixing.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -44,7 +44,7 @@ int_fast8_t Mixer::runner = 0;
mixer_comp_t Mixer::s_color[MIXING_STEPPERS];
mixer_accu_t Mixer::accu[MIXING_STEPPERS] = { 0 };
-#if DUAL_MIXING_EXTRUDER || ENABLED(GRADIENT_MIX)
+#if EITHER(HAS_DUAL_MIXING, GRADIENT_MIX)
mixer_perc_t Mixer::mix[MIXING_STEPPERS];
#endif
@@ -90,15 +90,13 @@ void Mixer::normalize(const uint8_t tool_index) {
SERIAL_ECHOLNPGM("]");
#endif
- #if ENABLED(GRADIENT_MIX)
- refresh_gradient();
- #endif
+ TERN_(GRADIENT_MIX, refresh_gradient());
}
void Mixer::reset_vtools() {
// Virtual Tools 0, 1, 2, 3 = Filament 1, 2, 3, 4, etc.
// Every virtual tool gets a pure filament
- LOOP_L_N(t, MIXING_VIRTUAL_TOOLS && t < MIXING_STEPPERS)
+ LOOP_L_N(t, _MIN(MIXING_VIRTUAL_TOOLS, MIXING_STEPPERS))
MIXER_STEPPER_LOOP(i)
color[t][i] = (t == i) ? COLOR_A_MASK : 0;
@@ -115,7 +113,7 @@ void Mixer::init() {
reset_vtools();
- #if ENABLED(RETRACT_SYNC_MIXING)
+ #if HAS_MIXER_SYNC_CHANNEL
// AUTORETRACT_TOOL gets the same amount of all filaments
MIXER_STEPPER_LOOP(i)
color[MIXER_AUTORETRACT_TOOL][i] = COLOR_A_MASK;
@@ -123,13 +121,11 @@ void Mixer::init() {
ZERO(collector);
- #if DUAL_MIXING_EXTRUDER || ENABLED(GRADIENT_MIX)
+ #if EITHER(HAS_DUAL_MIXING, GRADIENT_MIX)
update_mix_from_vtool();
#endif
- #if ENABLED(GRADIENT_MIX)
- update_gradient_for_planner_z();
- #endif
+ TERN_(GRADIENT_MIX, update_gradient_for_planner_z());
}
void Mixer::refresh_collector(const float proportion/*=1.0*/, const uint8_t t/*=selected_vtool*/, float (&c)[MIXING_STEPPERS]/*=collector*/) {
diff --git a/Marlin/src/feature/mixing.h b/Marlin/src/feature/mixing.h
index da5240995..7fe7062a7 100644
--- a/Marlin/src/feature/mixing.h
+++ b/Marlin/src/feature/mixing.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -25,7 +25,7 @@
//#define MIXER_NORMALIZER_DEBUG
-#ifndef __AVR__ // || DUAL_MIXING_EXTRUDER
+#ifndef __AVR__ // || HAS_DUAL_MIXING
// Use 16-bit (or fastest) data for the integer mix factors
typedef uint_fast16_t mixer_comp_t;
typedef uint_fast16_t mixer_accu_t;
@@ -48,29 +48,23 @@ typedef int8_t mixer_perc_t;
#endif
enum MixTool {
- FIRST_USER_VIRTUAL_TOOL = 0,
- LAST_USER_VIRTUAL_TOOL = MIXING_VIRTUAL_TOOLS - 1,
- NR_USER_VIRTUAL_TOOLS,
- MIXER_DIRECT_SET_TOOL = NR_USER_VIRTUAL_TOOLS,
- #if ENABLED(RETRACT_SYNC_MIXING)
- MIXER_AUTORETRACT_TOOL,
+ FIRST_USER_VIRTUAL_TOOL = 0
+ , LAST_USER_VIRTUAL_TOOL = MIXING_VIRTUAL_TOOLS - 1
+ , NR_USER_VIRTUAL_TOOLS
+ , MIXER_DIRECT_SET_TOOL = NR_USER_VIRTUAL_TOOLS
+ #if HAS_MIXER_SYNC_CHANNEL
+ , MIXER_AUTORETRACT_TOOL
#endif
- NR_MIXING_VIRTUAL_TOOLS
+ , NR_MIXING_VIRTUAL_TOOLS
};
-#if ENABLED(RETRACT_SYNC_MIXING)
- #define MAX_VTOOLS 254
-#else
- #define MAX_VTOOLS 255
-#endif
+#define MAX_VTOOLS TERN(HAS_MIXER_SYNC_CHANNEL, 254, 255)
static_assert(NR_MIXING_VIRTUAL_TOOLS <= MAX_VTOOLS, "MIXING_VIRTUAL_TOOLS must be <= " STRINGIFY(MAX_VTOOLS) "!");
-#define MIXER_STEPPER_LOOP(VAR) \
- for (uint_fast8_t VAR = 0; VAR < MIXING_STEPPERS; VAR++)
-
#define MIXER_BLOCK_FIELD mixer_comp_t b_color[MIXING_STEPPERS]
#define MIXER_POPULATE_BLOCK() mixer.populate_block(block->b_color)
#define MIXER_STEPPER_SETUP() mixer.stepper_setup(current_block->b_color)
+#define MIXER_STEPPER_LOOP(VAR) for (uint_fast8_t VAR = 0; VAR < MIXING_STEPPERS; VAR++)
#if ENABLED(GRADIENT_MIX)
@@ -81,9 +75,7 @@ static_assert(NR_MIXING_VIRTUAL_TOOLS <= MAX_VTOOLS, "MIXING_VIRTUAL_TOOLS must
int8_t start_vtool, end_vtool; // Start and end virtual tools
mixer_perc_t start_mix[MIXING_STEPPERS], // Start and end mixes from those tools
end_mix[MIXING_STEPPERS];
- #if ENABLED(GRADIENT_VTOOL)
- int8_t vtool_index; // Use this virtual tool number as index
- #endif
+ TERN_(GRADIENT_VTOOL, int8_t vtool_index); // Use this virtual tool number as index
} gradient_t;
#endif
@@ -112,12 +104,8 @@ class Mixer {
FORCE_INLINE static void T(const uint_fast8_t c) {
selected_vtool = c;
- #if ENABLED(GRADIENT_VTOOL)
- refresh_gradient();
- #endif
- #if DUAL_MIXING_EXTRUDER
- update_mix_from_vtool();
- #endif
+ TERN_(GRADIENT_VTOOL, refresh_gradient());
+ TERN_(HAS_DUAL_MIXING, update_mix_from_vtool());
}
// Used when dealing with blocks
@@ -135,7 +123,7 @@ class Mixer {
MIXER_STEPPER_LOOP(i) s_color[i] = b_color[i];
}
- #if DUAL_MIXING_EXTRUDER || ENABLED(GRADIENT_MIX)
+ #if EITHER(HAS_DUAL_MIXING, GRADIENT_MIX)
static mixer_perc_t mix[MIXING_STEPPERS]; // Scratch array for the Mix in proportion to 100
@@ -173,21 +161,19 @@ class Mixer {
#endif
}
- #endif // DUAL_MIXING_EXTRUDER || GRADIENT_MIX
+ #endif // HAS_DUAL_MIXING || GRADIENT_MIX
- #if DUAL_MIXING_EXTRUDER
+ #if HAS_DUAL_MIXING
// Update the virtual tool from an edited mix
static inline void update_vtool_from_mix() {
copy_mix_to_color(color[selected_vtool]);
- #if ENABLED(GRADIENT_MIX)
- refresh_gradient();
- #endif
+ TERN_(GRADIENT_MIX, refresh_gradient());
// MIXER_STEPPER_LOOP(i) collector[i] = mix[i];
// normalize();
}
- #endif // DUAL_MIXING_EXTRUDER
+ #endif // HAS_DUAL_MIXING
#if ENABLED(GRADIENT_MIX)
diff --git a/Marlin/src/feature/mmu2/mmu2.cpp b/Marlin/src/feature/mmu2/mmu2.cpp
index 4506883f4..35f2db45a 100644
--- a/Marlin/src/feature/mmu2/mmu2.cpp
+++ b/Marlin/src/feature/mmu2/mmu2.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -51,8 +51,13 @@ MMU2 mmu2;
#define MMU_TODELAY 100
#define MMU_TIMEOUT 10
-#define MMU_CMD_TIMEOUT 60000ul // 5min timeout for mmu commands (except P0)
-#define MMU_P0_TIMEOUT 3000ul // Timeout for P0 command: 3seconds
+#define MMU_CMD_TIMEOUT 45000UL // 45s timeout for mmu commands (except P0)
+#define MMU_P0_TIMEOUT 3000UL // Timeout for P0 command: 3seconds
+
+#if ENABLED(MMU_EXTRUDER_SENSOR)
+ uint8_t mmu_idl_sens = 0;
+ static bool mmu_loading_flag = false;
+#endif
#define MMU_CMD_NONE 0
#define MMU_CMD_T0 0x10
@@ -79,11 +84,7 @@ MMU2 mmu2;
#define MMU_CMD_F3 0x73
#define MMU_CMD_F4 0x74
-#if ENABLED(MMU2_MODE_12V)
- #define MMU_REQUIRED_FW_BUILDNR 132
-#else
- #define MMU_REQUIRED_FW_BUILDNR 126
-#endif
+#define MMU_REQUIRED_FW_BUILDNR TERN(MMU2_MODE_12V, 132, 126)
#define MMU2_NO_TOOL 99
#define MMU_BAUD 115200
@@ -91,23 +92,32 @@ MMU2 mmu2;
#define mmuSerial MMU2_SERIAL
bool MMU2::enabled, MMU2::ready, MMU2::mmu_print_saved;
+#if ENABLED(PRUSA_MMU2_S_MODE)
+ bool MMU2::mmu2s_triggered;
+#endif
uint8_t MMU2::cmd, MMU2::cmd_arg, MMU2::last_cmd, MMU2::extruder;
int8_t MMU2::state = 0;
volatile int8_t MMU2::finda = 1;
volatile bool MMU2::finda_runout_valid;
int16_t MMU2::version = -1, MMU2::buildnr = -1;
-millis_t MMU2::last_request, MMU2::next_P0_request;
+millis_t MMU2::prev_request, MMU2::prev_P0_request;
char MMU2::rx_buffer[MMU_RX_SIZE], MMU2::tx_buffer[MMU_TX_SIZE];
-#if HAS_LCD_MENU && ENABLED(MMU2_MENUS)
+#if BOTH(HAS_LCD_MENU, MMU2_MENUS)
struct E_Step {
float extrude; //!< extrude distance in mm
feedRate_t feedRate; //!< feed rate in mm/s
};
- static constexpr E_Step ramming_sequence[] PROGMEM = { MMU2_RAMMING_SEQUENCE };
- static constexpr E_Step load_to_nozzle_sequence[] PROGMEM = { MMU2_LOAD_TO_NOZZLE_SEQUENCE };
+ static constexpr E_Step
+ ramming_sequence[] PROGMEM = { MMU2_RAMMING_SEQUENCE }
+ , load_to_nozzle_sequence[] PROGMEM = { MMU2_LOAD_TO_NOZZLE_SEQUENCE }
+ #if ENABLED(PRUSA_MMU2_S_MODE)
+ , can_load_sequence[] PROGMEM = { MMU2_CAN_LOAD_SEQUENCE }
+ , can_load_increment_sequence[] PROGMEM = { MMU2_CAN_LOAD_INCREMENT_SEQUENCE }
+ #endif
+ ;
#endif // MMU2_MENUS
@@ -150,6 +160,10 @@ uint8_t MMU2::get_current_tool() {
return extruder == MMU2_NO_TOOL ? -1 : extruder;
}
+#if EITHER(PRUSA_MMU2_S_MODE, MMU_EXTRUDER_SENSOR)
+ #define FILAMENT_PRESENT() (READ(FIL_RUNOUT_PIN) != FIL_RUNOUT_STATE)
+#endif
+
void MMU2::mmu_loop() {
switch (state) {
@@ -228,6 +242,7 @@ void MMU2::mmu_loop() {
enabled = true;
state = 1;
+ TERN_(PRUSA_MMU2_S_MODE, mmu2s_triggered = false);
}
break;
@@ -238,6 +253,7 @@ void MMU2::mmu_loop() {
int filament = cmd - MMU_CMD_T0;
DEBUG_ECHOLNPAIR("MMU <= T", filament);
tx_printf_P(PSTR("T%d\n"), filament);
+ TERN_(MMU_EXTRUDER_SENSOR, mmu_idl_sens = 1); // enable idler sensor, if any
state = 3; // wait for response
}
else if (WITHIN(cmd, MMU_CMD_L0, MMU_CMD_L4)) {
@@ -286,11 +302,13 @@ void MMU2::mmu_loop() {
last_cmd = cmd;
cmd = MMU_CMD_NONE;
}
- else if (ELAPSED(millis(), next_P0_request)) {
+ else if (ELAPSED(millis(), prev_P0_request + 300)) {
// read FINDA
tx_str_P(PSTR("P0\n"));
state = 2; // wait for response
}
+
+ TERN_(PRUSA_MMU2_S_MODE, check_filament());
break;
case 2: // response to command P0
@@ -300,25 +318,35 @@ void MMU2::mmu_loop() {
// This is super annoying. Only activate if necessary
// if (finda_runout_valid) DEBUG_ECHOLNPAIR_F("MMU <= 'P0'\nMMU => ", finda, 6);
- state = 1;
-
- if (cmd == 0) ready = true;
-
if (!finda && finda_runout_valid) filament_runout();
+ if (cmd == 0) ready = true;
+ state = 1;
}
- else if (ELAPSED(millis(), last_request + MMU_P0_TIMEOUT)) // Resend request after timeout (3s)
+ else if (ELAPSED(millis(), prev_request + MMU_P0_TIMEOUT)) // Resend request after timeout (3s)
state = 1;
+ TERN_(PRUSA_MMU2_S_MODE, check_filament());
break;
case 3: // response to mmu commands
+ #if ENABLED(MMU_EXTRUDER_SENSOR)
+ if (mmu_idl_sens) {
+ if (FILAMENT_PRESENT() && mmu_loading_flag) {
+ DEBUG_ECHOLNPGM("MMU <= 'A'\n");
+ tx_str_P(PSTR("A\n")); // send 'abort' request
+ mmu_idl_sens = 0;
+ DEBUG_ECHOLNPGM("MMU IDLER_SENSOR = 0 - ABORT\n");
+ }
+ }
+ #endif
+
if (rx_ok()) {
DEBUG_ECHOLNPGM("MMU => 'ok'");
ready = true;
state = 1;
last_cmd = MMU_CMD_NONE;
}
- else if (ELAPSED(millis(), last_request + MMU_CMD_TIMEOUT)) {
+ else if (ELAPSED(millis(), prev_request + MMU_CMD_TIMEOUT)) {
// resend request after timeout
if (last_cmd) {
DEBUG_ECHOLNPGM("MMU retry");
@@ -327,6 +355,7 @@ void MMU2::mmu_loop() {
}
state = 1;
}
+ TERN_(PRUSA_MMU2_S_MODE, check_filament());
break;
}
}
@@ -337,7 +366,7 @@ void MMU2::mmu_loop() {
bool MMU2::rx_start() {
// check for start message
if (rx_str_P(PSTR("start\n"))) {
- next_P0_request = millis() + 300;
+ prev_P0_request = millis();
return true;
}
return false;
@@ -383,7 +412,7 @@ void MMU2::tx_str_P(const char* str) {
uint8_t len = strlen_P(str);
LOOP_L_N(i, len) mmuSerial.write(pgm_read_byte(str++));
rx_buffer[0] = '\0';
- last_request = millis();
+ prev_request = millis();
}
/**
@@ -394,7 +423,7 @@ void MMU2::tx_printf_P(const char* format, int argument = -1) {
uint8_t len = sprintf_P(tx_buffer, format, argument);
LOOP_L_N(i, len) mmuSerial.write(tx_buffer[i]);
rx_buffer[0] = '\0';
- last_request = millis();
+ prev_request = millis();
}
/**
@@ -405,7 +434,7 @@ void MMU2::tx_printf_P(const char* format, int argument1, int argument2) {
uint8_t len = sprintf_P(tx_buffer, format, argument1, argument2);
LOOP_L_N(i, len) mmuSerial.write(tx_buffer[i]);
rx_buffer[0] = '\0';
- last_request = millis();
+ prev_request = millis();
}
/**
@@ -421,7 +450,7 @@ void MMU2::clear_rx_buffer() {
*/
bool MMU2::rx_ok() {
if (rx_str_P(PSTR("ok\n"))) {
- next_P0_request = millis() + 300;
+ prev_P0_request = millis();
return true;
}
return false;
@@ -433,37 +462,235 @@ bool MMU2::rx_ok() {
void MMU2::check_version() {
if (buildnr < MMU_REQUIRED_FW_BUILDNR) {
SERIAL_ERROR_MSG("Invalid MMU2 firmware. Version >= " STRINGIFY(MMU_REQUIRED_FW_BUILDNR) " required.");
- kill(GET_TEXT(MSG_MMU2_WRONG_FIRMWARE));
+ kill(GET_TEXT(MSG_KILL_MMU2_FIRMWARE));
}
}
+static void mmu2_not_responding() {
+ LCD_MESSAGEPGM(MSG_MMU2_NOT_RESPONDING);
+ BUZZ(100, 659);
+ BUZZ(200, 698);
+ BUZZ(100, 659);
+ BUZZ(300, 440);
+ BUZZ(100, 659);
+}
+
+#if ENABLED(PRUSA_MMU2_S_MODE)
+
+ bool MMU2::load_to_gears() {
+ command(MMU_CMD_C0);
+ manage_response(true, true);
+ LOOP_L_N(i, MMU2_C0_RETRY) { // Keep loading until filament reaches gears
+ if (mmu2s_triggered) break;
+ command(MMU_CMD_C0);
+ manage_response(true, true);
+ check_filament();
+ }
+ const bool success = mmu2s_triggered && can_load();
+ if (!success) mmu2_not_responding();
+ return success;
+ }
+
+ /**
+ * Handle tool change
+ */
+ void MMU2::tool_change(const uint8_t index) {
+
+ if (!enabled) return;
+
+ set_runout_valid(false);
+
+ if (index != extruder) {
+
+ DISABLE_AXIS_E0();
+ ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1));
+
+ command(MMU_CMD_T0 + index);
+ manage_response(true, true);
+
+ if (load_to_gears()) {
+ extruder = index; // filament change is finished
+ active_extruder = 0;
+ ENABLE_AXIS_E0();
+ SERIAL_ECHO_START();
+ SERIAL_ECHOLNPAIR(STR_ACTIVE_EXTRUDER, int(extruder));
+ }
+ ui.reset_status();
+ }
+
+ set_runout_valid(true);
+ }
+
+ /**
+ * Handle special T?/Tx/Tc commands
+ *
+ * T? Gcode to extrude shouldn't have to follow, load to extruder wheels is done automatically
+ * Tx Same as T?, except nozzle doesn't have to be preheated. Tc must be placed after extruder nozzle is preheated to finish filament load.
+ * Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated.
+ */
+ void MMU2::tool_change(const char* special) {
+
+ if (!enabled) return;
+
+ #if ENABLED(MMU2_MENUS)
+
+ set_runout_valid(false);
+
+ switch (*special) {
+ case '?': {
+ uint8_t index = mmu2_choose_filament();
+ while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100);
+ load_filament_to_nozzle(index);
+ } break;
+
+ case 'x': {
+ planner.synchronize();
+ uint8_t index = mmu2_choose_filament();
+ DISABLE_AXIS_E0();
+ command(MMU_CMD_T0 + index);
+ manage_response(true, true);
+
+ if (load_to_gears()) {
+ mmu_loop();
+ ENABLE_AXIS_E0();
+ extruder = index;
+ active_extruder = 0;
+ }
+ } break;
+
+ case 'c': {
+ while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100);
+ execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence));
+ } break;
+ }
+
+ set_runout_valid(true);
+
+ #endif // MMU2_MENUS
+ }
+
+#elif ENABLED(MMU_EXTRUDER_SENSOR)
+
+ /**
+ * Handle tool change
+ */
+ void MMU2::tool_change(const uint8_t index) {
+ if (!enabled) return;
+
+ set_runout_valid(false);
+
+ if (index != extruder) {
+ DISABLE_AXIS_E0();
+ if (FILAMENT_PRESENT()) {
+ DEBUG_ECHOLNPGM("Unloading\n");
+ mmu_loading_flag = false;
+ command(MMU_CMD_U0);
+ manage_response(true, true);
+ }
+ ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1));
+ mmu_loading_flag = true;
+ command(MMU_CMD_T0 + index);
+ manage_response(true, true);
+ mmu_continue_loading();
+ command(MMU_CMD_C0);
+ extruder = index;
+ active_extruder = 0;
+
+ ENABLE_AXIS_E0();
+ SERIAL_ECHO_START();
+ SERIAL_ECHOLNPAIR(STR_ACTIVE_EXTRUDER, int(extruder));
+
+ ui.reset_status();
+ }
+
+ set_runout_valid(true);
+ }
+
+ /**
+ * Handle special T?/Tx/Tc commands
+ *
+ * T? Gcode to extrude shouldn't have to follow, load to extruder wheels is done automatically
+ * Tx Same as T?, except nozzle doesn't have to be preheated. Tc must be placed after extruder nozzle is preheated to finish filament load.
+ * Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated.
+ */
+ void MMU2::tool_change(const char* special) {
+ if (!enabled) return;
+
+ #if ENABLED(MMU2_MENUS)
+
+ set_runout_valid(false);
+
+ switch (*special) {
+ case '?': {
+ DEBUG_ECHOLNPGM("case ?\n");
+ uint8_t index = mmu2_choose_filament();
+ while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100);
+ load_filament_to_nozzle(index);
+ } break;
+
+ case 'x': {
+ DEBUG_ECHOLNPGM("case x\n");
+ planner.synchronize();
+ uint8_t index = mmu2_choose_filament();
+ DISABLE_AXIS_E0();
+ command(MMU_CMD_T0 + index);
+ manage_response(true, true);
+ mmu_continue_loading();
+ command(MMU_CMD_C0);
+ mmu_loop();
+
+ ENABLE_AXIS_E0();
+ extruder = index;
+ active_extruder = 0;
+ } break;
+
+ case 'c': {
+ DEBUG_ECHOLNPGM("case c\n");
+ while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100);
+ execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence));
+ } break;
+ }
+
+ set_runout_valid(true);
+
+ #endif // MMU2_MENUS
+ }
+
+ void MMU2::mmu_continue_loading() {
+ for (uint8_t i = 0; i < MMU_LOADING_ATTEMPTS_NR; i++) {
+ DEBUG_ECHOLNPAIR("Additional load attempt #", i);
+ if (FILAMENT_PRESENT()) break;
+ command(MMU_CMD_C0);
+ manage_response(true, true);
+ }
+ if (!FILAMENT_PRESENT()) {
+ DEBUG_ECHOLNPGM("Filament never reached sensor, runout");
+ filament_runout();
+ }
+ mmu_idl_sens = 0;
+ }
+
+#elif DISABLED(MMU_EXTRUDER_SENSOR) && DISABLED(PRUSA_MMU2_S_MODE)
+
/**
* Handle tool change
*/
-void MMU2::tool_change(uint8_t index) {
-
+void MMU2::tool_change(const uint8_t index) {
if (!enabled) return;
set_runout_valid(false);
if (index != extruder) {
-
DISABLE_AXIS_E0();
ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1));
-
command(MMU_CMD_T0 + index);
-
manage_response(true, true);
-
command(MMU_CMD_C0);
extruder = index; //filament change is finished
active_extruder = 0;
-
ENABLE_AXIS_E0();
-
SERIAL_ECHO_START();
SERIAL_ECHOLNPAIR(STR_ACTIVE_EXTRUDER, int(extruder));
-
ui.reset_status();
}
@@ -480,7 +707,6 @@ void MMU2::tool_change(uint8_t index) {
*
*/
void MMU2::tool_change(const char* special) {
-
if (!enabled) return;
#if ENABLED(MMU2_MENUS)
@@ -489,12 +715,14 @@ void MMU2::tool_change(const char* special) {
switch (*special) {
case '?': {
+ DEBUG_ECHOLNPGM("case ?\n");
uint8_t index = mmu2_choose_filament();
while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100);
load_filament_to_nozzle(index);
} break;
case 'x': {
+ DEBUG_ECHOLNPGM("case x\n");
planner.synchronize();
uint8_t index = mmu2_choose_filament();
DISABLE_AXIS_E0();
@@ -509,6 +737,7 @@ void MMU2::tool_change(const char* special) {
} break;
case 'c': {
+ DEBUG_ECHOLNPGM("case c\n");
while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100);
execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence));
} break;
@@ -517,7 +746,9 @@ void MMU2::tool_change(const char* special) {
set_runout_valid(true);
#endif
-}
+ }
+
+#endif // MMU_EXTRUDER_SENSOR
/**
* Set next command
@@ -554,7 +785,7 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) {
bool response = false;
mmu_print_saved = false;
xyz_pos_t resume_position;
- int16_t resume_hotend_temp;
+ int16_t resume_hotend_temp = thermalManager.degTargetHotend(active_extruder);
KEEPALIVE_STATE(PAUSED_FOR_USER);
@@ -575,16 +806,11 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) {
resume_position = current_position;
if (move_axes && all_axes_homed())
- nozzle.park(2, park_point /*= NOZZLE_PARK_POINT*/);
+ nozzle.park(0, park_point /*= NOZZLE_PARK_POINT*/);
if (turn_off_nozzle) thermalManager.setTargetHotend(0, active_extruder);
- LCD_MESSAGEPGM(MSG_MMU2_NOT_RESPONDING);
- BUZZ(100, 659);
- BUZZ(200, 698);
- BUZZ(100, 659);
- BUZZ(300, 440);
- BUZZ(100, 659);
+ mmu2_not_responding();
}
}
else if (mmu_print_saved) {
@@ -618,7 +844,7 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) {
}
}
-void MMU2::set_filament_type(uint8_t index, uint8_t filamentType) {
+void MMU2::set_filament_type(const uint8_t index, const uint8_t filamentType) {
if (!enabled) return;
cmd_arg = filamentType;
@@ -632,10 +858,44 @@ void MMU2::filament_runout() {
planner.synchronize();
}
-#if HAS_LCD_MENU && ENABLED(MMU2_MENUS)
+#if ENABLED(PRUSA_MMU2_S_MODE)
+
+ void MMU2::check_filament() {
+ const bool present = FILAMENT_PRESENT();
+ if (present && !mmu2s_triggered) {
+ DEBUG_ECHOLNPGM("MMU <= 'A'");
+ tx_str_P(PSTR("A\n"));
+ }
+ mmu2s_triggered = present;
+ }
+
+ bool MMU2::can_load() {
+ execute_extruder_sequence((const E_Step *)can_load_sequence, COUNT(can_load_sequence));
+
+ int filament_detected_count = 0;
+ const int steps = (MMU2_CAN_LOAD_RETRACT) / (MMU2_CAN_LOAD_INCREMENT);
+ DEBUG_ECHOLNPGM("MMU can_load:");
+ LOOP_L_N(i, steps) {
+ execute_extruder_sequence((const E_Step *)can_load_increment_sequence, COUNT(can_load_increment_sequence));
+ check_filament(); // Don't trust the idle function
+ DEBUG_CHAR(mmu2s_triggered ? 'O' : 'o');
+ if (mmu2s_triggered) ++filament_detected_count;
+ }
+
+ if (filament_detected_count <= steps - (MMU2_CAN_LOAD_DEVIATION) / (MMU2_CAN_LOAD_INCREMENT)) {
+ DEBUG_ECHOLNPGM(" failed.");
+ return false;
+ }
+
+ DEBUG_ECHOLNPGM(" succeeded.");
+ return true;
+ }
+#endif
+
+#if BOTH(HAS_LCD_MENU, MMU2_MENUS)
// Load filament into MMU2
- void MMU2::load_filament(uint8_t index) {
+ void MMU2::load_filament(const uint8_t index) {
if (!enabled) return;
command(MMU_CMD_L0 + index);
manage_response(false, false);
@@ -647,7 +907,7 @@ void MMU2::filament_runout() {
* Switch material and load to nozzle
*
*/
- bool MMU2::load_filament_to_nozzle(uint8_t index) {
+ bool MMU2::load_filament_to_nozzle(const uint8_t index) {
if (!enabled) return false;
@@ -656,24 +916,22 @@ void MMU2::filament_runout() {
LCD_ALERTMESSAGEPGM(MSG_HOTEND_TOO_COLD);
return false;
}
- else {
- command(MMU_CMD_T0 + index);
- manage_response(true, true);
- command(MMU_CMD_C0);
- mmu_loop();
+ command(MMU_CMD_T0 + index);
+ manage_response(true, true);
+
+ const bool success = load_to_gears();
+ if (success) {
+ mmu_loop();
extruder = index;
active_extruder = 0;
-
load_to_nozzle();
-
BUZZ(200, 404);
- return true;
}
+ return success;
}
/**
- *
* Load filament to nozzle of multimaterial printer
*
* This function is used only only after T? (user select filament) and M600 (change filament).
@@ -685,7 +943,7 @@ void MMU2::filament_runout() {
execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence));
}
- bool MMU2::eject_filament(uint8_t index, bool recover) {
+ bool MMU2::eject_filament(const uint8_t index, const bool recover) {
if (!enabled) return false;
@@ -707,12 +965,8 @@ void MMU2::filament_runout() {
if (recover) {
LCD_MESSAGEPGM(MSG_MMU2_EJECT_RECOVER);
BUZZ(200, 404);
- #if ENABLED(HOST_PROMPT_SUPPORT)
- host_prompt_do(PROMPT_USER_CONTINUE, PSTR("MMU2 Eject Recover"), CONTINUE_STR);
- #endif
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onUserConfirmRequired_P(PSTR("MMU2 Eject Recover"));
- #endif
+ TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("MMU2 Eject Recover"), CONTINUE_STR));
+ TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("MMU2 Eject Recover")));
wait_for_user_response();
BUZZ(200, 404);
BUZZ(200, 404);
@@ -736,9 +990,7 @@ void MMU2::filament_runout() {
}
/**
- *
- * unload from hotend and retract to MMU
- *
+ * Unload from hotend and retract to MMU
*/
bool MMU2::unload() {
diff --git a/Marlin/src/feature/mmu2/mmu2.h b/Marlin/src/feature/mmu2/mmu2.h
index 970b0b433..678f65d07 100644
--- a/Marlin/src/feature/mmu2/mmu2.h
+++ b/Marlin/src/feature/mmu2/mmu2.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -44,24 +44,24 @@ public:
static void init();
static void reset();
static void mmu_loop();
- static void tool_change(uint8_t index);
+ static void tool_change(const uint8_t index);
static void tool_change(const char* special);
static uint8_t get_current_tool();
- static void set_filament_type(uint8_t index, uint8_t type);
+ static void set_filament_type(const uint8_t index, const uint8_t type);
- #if HAS_LCD_MENU && ENABLED(MMU2_MENUS)
+ #if BOTH(HAS_LCD_MENU, MMU2_MENUS)
static bool unload();
static void load_filament(uint8_t);
static void load_all();
- static bool load_filament_to_nozzle(uint8_t index);
- static bool eject_filament(uint8_t index, bool recover);
+ static bool load_filament_to_nozzle(const uint8_t index);
+ static bool eject_filament(const uint8_t index, const bool recover);
#endif
private:
static bool rx_str_P(const char* str);
static void tx_str_P(const char* str);
- static void tx_printf_P(const char* format, int argument);
- static void tx_printf_P(const char* format, int argument1, int argument2);
+ static void tx_printf_P(const char* format, const int argument);
+ static void tx_printf_P(const char* format, const int argument1, const int argument2);
static void clear_rx_buffer();
static bool rx_ok();
@@ -72,7 +72,7 @@ private:
static bool get_response();
static void manage_response(const bool move_axes, const bool turn_off_nozzle);
- #if HAS_LCD_MENU && ENABLED(MMU2_MENUS)
+ #if BOTH(HAS_LCD_MENU, MMU2_MENUS)
static void load_to_nozzle();
static void filament_ramming();
static void execute_extruder_sequence(const E_Step * sequence, int steps);
@@ -80,13 +80,27 @@ private:
static void filament_runout();
+ #if ENABLED(PRUSA_MMU2_S_MODE)
+ static bool mmu2s_triggered;
+ static void check_filament();
+ static bool can_load();
+ static bool load_to_gears();
+ #else
+ FORCE_INLINE static bool load_to_gears() { return true; }
+ #endif
+
+ #if ENABLED(MMU_EXTRUDER_SENSOR)
+ static void mmu_continue_loading();
+ #endif
+
static bool enabled, ready, mmu_print_saved;
+
static uint8_t cmd, cmd_arg, last_cmd, extruder;
static int8_t state;
static volatile int8_t finda;
static volatile bool finda_runout_valid;
static int16_t version, buildnr;
- static millis_t last_request, next_P0_request;
+ static millis_t prev_request, prev_P0_request;
static char rx_buffer[MMU_RX_SIZE], tx_buffer[MMU_TX_SIZE];
static inline void set_runout_valid(const bool valid) {
diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp
index 9c615b6ff..77f352c39 100644
--- a/Marlin/src/feature/pause.cpp
+++ b/Marlin/src/feature/pause.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -53,7 +53,6 @@
#include "../lcd/extui/ui_api.h"
#endif
-#include "../core/language.h"
#include "../lcd/ultralcd.h"
#if HAS_BUZZER
@@ -85,26 +84,30 @@ fil_change_settings_t fc_settings[EXTRUDERS];
#endif
#if HAS_BUZZER
- static void filament_change_beep(const int8_t max_beep_count, const bool init=false) {
+ static void impatient_beep(const int8_t max_beep_count, const bool restart=false) {
- #if HAS_LCD_MENU
- if (pause_mode == PAUSE_MODE_PAUSE_PRINT) return;
- #endif
+ if (TERN0(HAS_LCD_MENU, pause_mode == PAUSE_MODE_PAUSE_PRINT)) return;
static millis_t next_buzz = 0;
static int8_t runout_beep = 0;
- if (init) next_buzz = runout_beep = 0;
+ if (restart) next_buzz = runout_beep = 0;
+
+ const bool always = max_beep_count < 0;
const millis_t ms = millis();
if (ELAPSED(ms, next_buzz)) {
- if (max_beep_count < 0 || runout_beep < max_beep_count + 5) { // Only beep as long as we're supposed to
- next_buzz = ms + ((max_beep_count < 0 || runout_beep < max_beep_count) ? 1000 : 500);
+ if (always || runout_beep < max_beep_count + 5) { // Only beep as long as we're supposed to
+ next_buzz = ms + ((always || runout_beep < max_beep_count) ? 1000 : 500);
BUZZ(50, 880 - (runout_beep & 1) * 220);
runout_beep++;
}
}
}
+ inline void first_impatient_beep(const int8_t max_beep_count) { impatient_beep(max_beep_count, true); }
+#else
+ inline void impatient_beep(const int8_t, const bool=false) {}
+ inline void first_impatient_beep(const int8_t) {}
#endif
/**
@@ -116,7 +119,7 @@ fil_change_settings_t fc_settings[EXTRUDERS];
*
* Returns 'true' if heating was completed, 'false' for abort
*/
-static bool ensure_safe_temperature(const PauseMode mode=PAUSE_MODE_SAME) {
+static bool ensure_safe_temperature(const bool wait=true, const PauseMode mode=PAUSE_MODE_SAME) {
#if ENABLED(PREVENT_COLD_EXTRUSION)
if (!DEBUGGING(DRYRUN) && thermalManager.targetTooColdToExtrude(active_extruder)) {
@@ -131,7 +134,13 @@ static bool ensure_safe_temperature(const PauseMode mode=PAUSE_MODE_SAME) {
UNUSED(mode);
#endif
- return thermalManager.wait_for_hotend(active_extruder);
+ if (wait)
+ return thermalManager.wait_for_hotend(active_extruder);
+
+ while (ABS(thermalManager.degHotend(active_extruder) - thermalManager.degTargetHotend(active_extruder)) > TEMP_WINDOW)
+ idle();
+
+ return true;
}
/**
@@ -151,11 +160,9 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l
const PauseMode mode/*=PAUSE_MODE_PAUSE_PRINT*/
DXC_ARGS
) {
- #if !HAS_LCD_MENU
- UNUSED(show_lcd);
- #endif
+ TERN(HAS_LCD_MENU,,UNUSED(show_lcd));
- if (!ensure_safe_temperature(mode)) {
+ if (!ensure_safe_temperature(false, mode)) {
#if HAS_LCD_MENU
if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_STATUS, mode);
#endif
@@ -168,11 +175,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l
#endif
SERIAL_ECHO_MSG(_PMSG(STR_FILAMENT_CHANGE_INSERT));
- #if HAS_BUZZER
- filament_change_beep(max_beep_count, true);
- #else
- UNUSED(max_beep_count);
- #endif
+ first_impatient_beep(max_beep_count);
KEEPALIVE_STATE(PAUSED_FOR_USER);
#if ENABLED(HOST_PROMPT_SUPPORT)
@@ -185,13 +188,9 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l
host_action_prompt_button(CONTINUE_STR);
host_action_prompt_show();
#endif
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onUserConfirmRequired_P(PSTR("Load Filament"));
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Load Filament")));
while (wait_for_user) {
- #if HAS_BUZZER
- filament_change_beep(max_beep_count);
- #endif
+ impatient_beep(max_beep_count);
idle_no_sleep();
}
}
@@ -236,12 +235,8 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l
if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_PURGE);
#endif
- #if ENABLED(HOST_PROMPT_SUPPORT)
- host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Filament Purging..."), CONTINUE_STR);
- #endif
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onUserConfirmRequired_P(PSTR("Filament Purging..."));
- #endif
+ TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Filament Purging..."), CONTINUE_STR));
+ TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Filament Purging...")));
wait_for_user = true; // A click or M108 breaks the purge_length loop
for (float purge_count = purge_length; purge_count > 0 && wait_for_user; --purge_count)
unscaled_e_move(1, ADVANCED_PAUSE_PURGE_FEEDRATE);
@@ -260,9 +255,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l
unscaled_e_move(purge_length, ADVANCED_PAUSE_PURGE_FEEDRATE);
}
- #if ENABLED(HOST_PROMPT_SUPPORT)
- filament_load_host_prompt(); // Initiate another host prompt. (NOTE: host_response_handler may also do this!)
- #endif
+ TERN_(HOST_PROMPT_SUPPORT, filament_load_host_prompt()); // Initiate another host prompt. (NOTE: host_response_handler may also do this!)
#if HAS_LCD_MENU
if (show_lcd) {
@@ -275,13 +268,10 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l
#endif
// Keep looping if "Purge More" was selected
- } while (false
- #if HAS_LCD_MENU
- || (show_lcd && pause_menu_response == PAUSE_RESPONSE_EXTRUDE_MORE)
- #endif
- );
+ } while (TERN0(HAS_LCD_MENU, show_lcd && pause_menu_response == PAUSE_RESPONSE_EXTRUDE_MORE));
#endif
+ TERN_(HOST_PROMPT_SUPPORT, host_action_prompt_end());
return true;
}
@@ -302,15 +292,13 @@ bool unload_filament(const float &unload_length, const bool show_lcd/*=false*/,
, const float &mix_multiplier/*=1.0*/
#endif
) {
- #if !HAS_LCD_MENU
- UNUSED(show_lcd);
- #endif
+ TERN(HAS_LCD_MENU,,UNUSED(show_lcd));
#if !BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER)
constexpr float mix_multiplier = 1.0;
#endif
- if (!ensure_safe_temperature(mode)) {
+ if (!ensure_safe_temperature(false, mode)) {
#if HAS_LCD_MENU
if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_STATUS);
#endif
@@ -370,10 +358,7 @@ bool unload_filament(const float &unload_length, const bool show_lcd/*=false*/,
uint8_t did_pause_print = 0;
bool pause_print(const float &retract, const xyz_pos_t &park_point, const float &unload_length/*=0*/, const bool show_lcd/*=false*/ DXC_ARGS) {
-
- #if !HAS_LCD_MENU
- UNUSED(show_lcd);
- #endif
+ TERN(HAS_LCD_MENU,,UNUSED(show_lcd));
if (did_pause_print) return false; // already paused
@@ -385,9 +370,7 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float
#endif
#endif
- #if ENABLED(HOST_PROMPT_SUPPORT)
- host_prompt_open(PROMPT_INFO, PSTR("Pause"), DISMISS_STR);
- #endif
+ TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, PSTR("Pause"), DISMISS_STR));
if (!DEBUGGING(DRYRUN) && unload_length && thermalManager.targetTooColdToExtrude(active_extruder)) {
SERIAL_ECHO_MSG(STR_ERR_HOTEND_TOO_COLD);
@@ -421,7 +404,7 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float
// Wait for buffered blocks to complete
planner.synchronize();
- #if ENABLED(ADVANCED_PAUSE_FANS_PAUSE) && FAN_COUNT > 0
+ #if ENABLED(ADVANCED_PAUSE_FANS_PAUSE) && HAS_FAN
thermalManager.set_fans_paused(true);
#endif
@@ -431,7 +414,7 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float
// Park the nozzle by moving up by z_lift and then moving to (x_pos, y_pos)
if (!axes_need_homing())
- nozzle.park(2, park_point);
+ nozzle.park(0, park_point);
#if ENABLED(DUAL_X_CARRIAGE)
const int8_t saved_ext = active_extruder;
@@ -466,9 +449,7 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float
*/
void show_continue_prompt(const bool is_reload) {
- #if HAS_LCD_MENU
- lcd_pause_show_message(is_reload ? PAUSE_MESSAGE_INSERT : PAUSE_MESSAGE_WAITING);
- #endif
+ TERN_(HAS_LCD_MENU, lcd_pause_show_message(is_reload ? PAUSE_MESSAGE_INSERT : PAUSE_MESSAGE_WAITING));
SERIAL_ECHO_START();
serialprintPGM(is_reload ? PSTR(_PMSG(STR_FILAMENT_CHANGE_INSERT) "\n") : PSTR(_PMSG(STR_FILAMENT_CHANGE_WAIT) "\n"));
}
@@ -478,14 +459,10 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep
show_continue_prompt(is_reload);
- #if HAS_BUZZER
- filament_change_beep(max_beep_count, true);
- #else
- UNUSED(max_beep_count);
- #endif
+ first_impatient_beep(max_beep_count);
// Start the heater idle timers
- const millis_t nozzle_timeout = (millis_t)(PAUSE_PARK_NOZZLE_TIMEOUT) * 1000UL;
+ const millis_t nozzle_timeout = SEC_TO_MS(PAUSE_PARK_NOZZLE_TIMEOUT);
HOTEND_LOOP() thermalManager.hotend_idle[e].start(nozzle_timeout);
@@ -498,17 +475,11 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep
// Wait for filament insert by user and press button
KEEPALIVE_STATE(PAUSED_FOR_USER);
- #if ENABLED(HOST_PROMPT_SUPPORT)
- host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Nozzle Parked"), CONTINUE_STR);
- #endif
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onUserConfirmRequired_P(PSTR("Nozzle Parked"));
- #endif
+ TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_NOZZLE_PARKED), CONTINUE_STR));
+ TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_NOZZLE_PARKED)));
wait_for_user = true; // LCD click or M108 will clear this
while (wait_for_user) {
- #if HAS_BUZZER
- filament_change_beep(max_beep_count);
- #endif
+ impatient_beep(max_beep_count);
// If the nozzle has timed out...
if (!nozzle_timed_out)
@@ -517,53 +488,38 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep
// Wait for the user to press the button to re-heat the nozzle, then
// re-heat the nozzle, re-show the continue prompt, restart idle timers, start over
if (nozzle_timed_out) {
- #if HAS_LCD_MENU
- lcd_pause_show_message(PAUSE_MESSAGE_HEAT);
- #endif
+ TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_HEAT));
SERIAL_ECHO_MSG(_PMSG(STR_FILAMENT_CHANGE_HEAT));
- #if ENABLED(HOST_PROMPT_SUPPORT)
- host_prompt_do(PROMPT_USER_CONTINUE, PSTR("HeaterTimeout"), PSTR("Reheat"));
- #endif
+ TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_HEATER_TIMEOUT), GET_TEXT(MSG_REHEAT)));
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onUserConfirmRequired_P(PSTR("HeaterTimeout"));
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_HEATER_TIMEOUT)));
wait_for_user_response(0, true); // Wait for LCD click or M108
- #if ENABLED(HOST_PROMPT_SUPPORT)
- host_prompt_do(PROMPT_INFO, PSTR("Reheating"));
- #endif
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onStatusChanged(PSTR("Reheating..."));
- #endif
+ TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_INFO, GET_TEXT(MSG_REHEATING)));
+
+ TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged_P(GET_TEXT(MSG_REHEATING)));
// Re-enable the heaters if they timed out
HOTEND_LOOP() thermalManager.reset_hotend_idle_timer(e);
// Wait for the heaters to reach the target temperatures
- ensure_safe_temperature();
+ ensure_safe_temperature(false);
// Show the prompt to continue
show_continue_prompt(is_reload);
// Start the heater idle timers
- const millis_t nozzle_timeout = (millis_t)(PAUSE_PARK_NOZZLE_TIMEOUT) * 1000UL;
+ const millis_t nozzle_timeout = SEC_TO_MS(PAUSE_PARK_NOZZLE_TIMEOUT);
HOTEND_LOOP() thermalManager.hotend_idle[e].start(nozzle_timeout);
- #if ENABLED(HOST_PROMPT_SUPPORT)
- host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Reheat Done"), CONTINUE_STR);
- #endif
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onUserConfirmRequired_P(PSTR("Reheat finished."));
- #endif
+ TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Reheat Done"), CONTINUE_STR));
+ TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Reheat finished.")));
wait_for_user = true;
nozzle_timed_out = false;
- #if HAS_BUZZER
- filament_change_beep(max_beep_count, true);
- #endif
+ first_impatient_beep(max_beep_count);
}
idle_no_sleep();
}
@@ -583,16 +539,18 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep
* - a nozzle timed out, or
* - the nozzle is already heated.
* - Display "wait for print to resume"
+ * - Retract to prevent oozing
+ * - Move the nozzle back to resume_position
+ * - Unretract
* - Re-prime the nozzle...
* - FWRETRACT: Recover/prime from the prior G10.
* - !FWRETRACT: Retract by resume_position.e, if negative.
* Not sure how this logic comes into use.
- * - Move the nozzle back to resume_position
* - Sync the planner E to resume_position.e
* - Send host action for resume, if configured
* - Resume the current SD print job, if any
*/
-void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_length/*=0*/, const float &purge_length/*=ADVANCED_PAUSE_PURGE_LENGTH*/, const int8_t max_beep_count/*=0*/ DXC_ARGS) {
+void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_length/*=0*/, const float &purge_length/*=ADVANCED_PAUSE_PURGE_LENGTH*/, const int8_t max_beep_count/*=0*/, int16_t targetTemp/*=0*/ DXC_ARGS) {
/*
SERIAL_ECHOLNPAIR(
"start of resume_print()\ndual_x_carriage_mode:", dual_x_carriage_mode,
@@ -611,12 +569,32 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le
thermalManager.reset_hotend_idle_timer(e);
}
+ if (targetTemp > thermalManager.degTargetHotend(active_extruder))
+ thermalManager.setTargetHotend(targetTemp, active_extruder);
+
if (nozzle_timed_out || thermalManager.hotEnoughToExtrude(active_extruder)) // Load the new filament
load_filament(slow_load_length, fast_load_length, purge_length, max_beep_count, true, nozzle_timed_out, PAUSE_MODE_SAME DXC_PASS);
- #if HAS_LCD_MENU
- lcd_pause_show_message(PAUSE_MESSAGE_RESUME);
- #endif
+ if (targetTemp > 0) {
+ thermalManager.setTargetHotend(targetTemp, active_extruder);
+ thermalManager.wait_for_hotend(active_extruder, false);
+ }
+
+ TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_RESUME));
+
+ // Retract to prevent oozing
+ unscaled_e_move(-(PAUSE_PARK_RETRACT_LENGTH), feedRate_t(PAUSE_PARK_RETRACT_FEEDRATE));
+
+ // Move XY to starting position, then Z
+ do_blocking_move_to_xy(resume_position, feedRate_t(NOZZLE_PARK_XY_FEEDRATE));
+
+ // Move Z_AXIS to saved position
+ do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE));
+
+ // Unretract
+ unscaled_e_move(PAUSE_PARK_RETRACT_LENGTH, feedRate_t(PAUSE_PARK_RETRACT_FEEDRATE));
+
+ ensure_safe_temperature();
// Intelligent resuming
#if ENABLED(FWRETRACT)
@@ -627,13 +605,6 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le
// If resume_position is negative
if (resume_position.e < 0) unscaled_e_move(resume_position.e, feedRate_t(PAUSE_PARK_RETRACT_FEEDRATE));
-
- // Move XY to starting position, then Z
- do_blocking_move_to_xy(resume_position, feedRate_t(NOZZLE_PARK_XY_FEEDRATE));
-
- // Move Z_AXIS to saved position
- do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE));
-
#if ADVANCED_PAUSE_RESUME_PRIME != 0
unscaled_e_move(ADVANCED_PAUSE_RESUME_PRIME, feedRate_t(ADVANCED_PAUSE_PURGE_FEEDRATE));
#endif
@@ -642,9 +613,7 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le
// Set extruder to saved position
planner.set_e_position_mm((destination.e = current_position.e = resume_position.e));
- #if HAS_LCD_MENU
- lcd_pause_show_message(PAUSE_MESSAGE_STATUS);
- #endif
+ TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_STATUS));
#ifdef ACTION_ON_RESUMED
host_action_resumed();
@@ -654,34 +623,23 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le
--did_pause_print;
- #if ENABLED(HOST_PROMPT_SUPPORT)
- host_prompt_open(PROMPT_INFO, PSTR("Resuming"), DISMISS_STR);
- #endif
+ TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, PSTR("Resuming"), DISMISS_STR));
#if ENABLED(SDSUPPORT)
- if (did_pause_print) {
- card.startFileprint();
- --did_pause_print;
- }
+ if (did_pause_print) { card.startFileprint(); --did_pause_print; }
#endif
- #if ENABLED(ADVANCED_PAUSE_FANS_PAUSE) && FAN_COUNT > 0
+ #if ENABLED(ADVANCED_PAUSE_FANS_PAUSE) && HAS_FAN
thermalManager.set_fans_paused(false);
#endif
- #if HAS_FILAMENT_SENSOR
- runout.reset();
- #endif
+ TERN_(HAS_FILAMENT_SENSOR, runout.reset());
// Resume the print job timer if it was running
if (print_job_timer.isPaused()) print_job_timer.start();
- #if HAS_DISPLAY
- ui.reset_status();
- #if HAS_LCD_MENU
- ui.return_to_status();
- #endif
- #endif
+ TERN_(HAS_DISPLAY, ui.reset_status());
+ TERN_(HAS_LCD_MENU, ui.return_to_status());
}
#endif // ADVANCED_PAUSE_FEATURE
diff --git a/Marlin/src/feature/pause.h b/Marlin/src/feature/pause.h
index f1c8eed4d..d8a676afa 100644
--- a/Marlin/src/feature/pause.h
+++ b/Marlin/src/feature/pause.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -45,7 +45,7 @@ enum PauseMode : char {
};
enum PauseMessage : char {
- PAUSE_MESSAGE_PAUSING,
+ PAUSE_MESSAGE_PARKING,
PAUSE_MESSAGE_CHANGING,
PAUSE_MESSAGE_WAITING,
PAUSE_MESSAGE_UNLOAD,
@@ -87,7 +87,7 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float
void wait_for_confirmation(const bool is_reload=false, const int8_t max_beep_count=0 DXC_PARAMS);
-void resume_print(const float &slow_load_length=0, const float &fast_load_length=0, const float &extrude_length=ADVANCED_PAUSE_PURGE_LENGTH, const int8_t max_beep_count=0 DXC_PARAMS);
+void resume_print(const float &slow_load_length=0, const float &fast_load_length=0, const float &extrude_length=ADVANCED_PAUSE_PURGE_LENGTH, const int8_t max_beep_count=0, int16_t targetTemp=0 DXC_PARAMS);
bool load_filament(const float &slow_load_length=0, const float &fast_load_length=0, const float &extrude_length=0, const int8_t max_beep_count=0, const bool show_lcd=false,
const bool pause_for_user=false, const PauseMode mode=PAUSE_MODE_PAUSE_PRINT DXC_PARAMS);
diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp
index 1fa751811..74850122c 100644
--- a/Marlin/src/feature/power.cpp
+++ b/Marlin/src/feature/power.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -33,6 +33,10 @@
#include "../module/stepper/indirection.h"
#include "../MarlinCore.h"
+#if BOTH(USE_CONTROLLER_FAN, AUTO_POWER_CONTROLLERFAN)
+ #include "controllerfan.h"
+#endif
+
Power powerManager;
millis_t Power::lastPowerOn;
@@ -50,15 +54,12 @@ bool Power::is_power_needed() {
if (controllerFan.state()) return true;
#endif
- #if ENABLED(AUTO_POWER_CHAMBER_FAN)
- if (thermalManager.chamberfan_speed) return true;
- #endif
+ if (TERN0(AUTO_POWER_CHAMBER_FAN, thermalManager.chamberfan_speed))
+ return true;
// If any of the drivers or the bed are enabled...
if (X_ENABLE_READ() == X_ENABLE_ON || Y_ENABLE_READ() == Y_ENABLE_ON || Z_ENABLE_READ() == Z_ENABLE_ON
- #if HAS_HEATED_BED
- || thermalManager.temp_bed.soft_pwm_amount > 0
- #endif
+ || TERN0(HAS_HEATED_BED, thermalManager.temp_bed.soft_pwm_amount > 0)
#if HAS_X2_ENABLE
|| X2_ENABLE_READ() == X_ENABLE_ON
#endif
@@ -75,12 +76,9 @@ bool Power::is_power_needed() {
) return true;
HOTEND_LOOP() if (thermalManager.degTargetHotend(e) > 0) return true;
+ if (TERN0(HAS_HEATED_BED, thermalManager.degTargetBed() > 0)) return true;
- #if HAS_HEATED_BED
- if (thermalManager.degTargetBed() > 0) return true;
- #endif
-
- #if HOTENDS && AUTO_POWER_E_TEMP
+ #if HAS_HOTEND && AUTO_POWER_E_TEMP
HOTEND_LOOP() if (thermalManager.degHotend(e) >= AUTO_POWER_E_TEMP) return true;
#endif
@@ -98,7 +96,7 @@ void Power::check() {
nextPowerCheck = ms + 2500UL;
if (is_power_needed())
power_on();
- else if (!lastPowerOn || ELAPSED(ms, lastPowerOn + (POWER_TIMEOUT) * 1000UL))
+ else if (!lastPowerOn || ELAPSED(ms, lastPowerOn + SEC_TO_MS(POWER_TIMEOUT)))
power_off();
}
}
@@ -107,11 +105,9 @@ void Power::power_on() {
lastPowerOn = millis();
if (!powersupply_on) {
PSU_PIN_ON();
-
- #if HAS_TRINAMIC_CONFIG
- delay(PSU_POWERUP_DELAY); // Wait for power to settle
- restore_stepper_drivers();
- #endif
+ safe_delay(PSU_POWERUP_DELAY);
+ restore_stepper_drivers();
+ TERN_(HAS_TRINAMIC_CONFIG, safe_delay(PSU_POWERUP_DELAY));
}
}
diff --git a/Marlin/src/feature/power.h b/Marlin/src/feature/power.h
index 0bad7736e..8b988907e 100644
--- a/Marlin/src/feature/power.h
+++ b/Marlin/src/feature/power.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/power_monitor.cpp b/Marlin/src/feature/power_monitor.cpp
new file mode 100644
index 000000000..bf5ac748a
--- /dev/null
+++ b/Marlin/src/feature/power_monitor.cpp
@@ -0,0 +1,75 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (C) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+
+#include "../inc/MarlinConfigPre.h"
+
+#if HAS_POWER_MONITOR
+
+#include "power_monitor.h"
+
+#include "../lcd/ultralcd.h"
+#include "../lcd/lcdprint.h"
+#include "../libs/numtostr.h"
+
+uint8_t PowerMonitor::flags; // = 0
+
+#if ENABLED(POWER_MONITOR_CURRENT)
+ pm_lpf_t PowerMonitor::amps;
+#endif
+#if ENABLED(POWER_MONITOR_VOLTAGE)
+ pm_lpf_t PowerMonitor::volts;
+#endif
+
+millis_t PowerMonitor::display_item_ms;
+uint8_t PowerMonitor::display_item;
+
+PowerMonitor power_monitor; // Single instance - this calls the constructor
+
+#if HAS_GRAPHICAL_LCD
+
+ #if ENABLED(POWER_MONITOR_CURRENT)
+ void PowerMonitor::draw_current() {
+ const float amps = getAmps();
+ lcd_put_u8str(amps < 100 ? ftostr31ns(amps) : ui16tostr4rj((uint16_t)amps));
+ lcd_put_wchar('A');
+ }
+ #endif
+
+ #if HAS_POWER_MONITOR_VREF
+ void PowerMonitor::draw_voltage() {
+ const float volts = getVolts();
+ lcd_put_u8str(volts < 100 ? ftostr31ns(volts) : ui16tostr4rj((uint16_t)volts));
+ lcd_put_wchar('V');
+ }
+ #endif
+
+ #if HAS_POWER_MONITOR_WATTS
+ void PowerMonitor::draw_power() {
+ const float power = getPower();
+ lcd_put_u8str(power < 100 ? ftostr31ns(power) : ui16tostr4rj((uint16_t)power));
+ lcd_put_wchar('W');
+ }
+ #endif
+
+#endif // HAS_GRAPHICAL_LCD
+
+#endif // HAS_POWER_MONITOR
diff --git a/Marlin/src/feature/power_monitor.h b/Marlin/src/feature/power_monitor.h
new file mode 100644
index 000000000..ca52ed74c
--- /dev/null
+++ b/Marlin/src/feature/power_monitor.h
@@ -0,0 +1,140 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (C) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#pragma once
+
+#include "../inc/MarlinConfig.h"
+
+#define PM_SAMPLE_RANGE 1024
+#define PM_K_VALUE 6
+#define PM_K_SCALE 6
+
+template
+struct pm_lpf_t {
+ uint32_t filter_buf;
+ float value;
+ void add_sample(const uint16_t sample) {
+ filter_buf = filter_buf - (filter_buf >> K_VALUE) + (uint32_t(sample) << K_SCALE);
+ }
+ void capture() {
+ value = filter_buf * (SCALE * (1.0f / (1UL << (PM_K_VALUE + PM_K_SCALE)))) + (POWER_MONITOR_CURRENT_OFFSET);
+ }
+ void reset(uint16_t reset_value = 0) {
+ filter_buf = uint32_t(reset_value) << (K_VALUE + K_SCALE);
+ capture();
+ }
+};
+
+class PowerMonitor {
+private:
+ #if ENABLED(POWER_MONITOR_CURRENT)
+ static constexpr float amps_adc_scale = float(ADC_VREF) / (POWER_MONITOR_VOLTS_PER_AMP * PM_SAMPLE_RANGE);
+ static pm_lpf_t amps;
+ #endif
+ #if ENABLED(POWER_MONITOR_VOLTAGE)
+ static constexpr float volts_adc_scale = float(ADC_VREF) / (POWER_MONITOR_VOLTS_PER_VOLT * PM_SAMPLE_RANGE);
+ static pm_lpf_t volts;
+ #endif
+
+public:
+ static uint8_t flags; // M430 flags to display current
+
+ static millis_t display_item_ms;
+ static uint8_t display_item;
+
+ PowerMonitor() { reset(); }
+
+ enum PM_Display_Bit : uint8_t {
+ PM_DISP_BIT_I, // Current display enable bit
+ PM_DISP_BIT_V, // Voltage display enable bit
+ PM_DISP_BIT_P // Power display enable bit
+ };
+
+ #if ENABLED(POWER_MONITOR_CURRENT)
+ FORCE_INLINE static float getAmps() { return amps.value; }
+ void add_current_sample(const uint16_t value) { amps.add_sample(value); }
+ #endif
+
+ #if HAS_POWER_MONITOR_VREF
+ #if ENABLED(POWER_MONITOR_VOLTAGE)
+ FORCE_INLINE static float getVolts() { return volts.value; }
+ #else
+ FORCE_INLINE static float getVolts() { return POWER_MONITOR_FIXED_VOLTAGE; } // using a specified fixed valtage as the voltage measurement
+ #endif
+ #if ENABLED(POWER_MONITOR_VOLTAGE)
+ void add_voltage_sample(const uint16_t value) { volts.add_sample(value); }
+ #endif
+ #endif
+
+ #if HAS_POWER_MONITOR_WATTS
+ FORCE_INLINE static float getPower() { return getAmps() * getVolts(); }
+ #endif
+
+ #if HAS_SPI_LCD
+ FORCE_INLINE static bool display_enabled() { return flags != 0x00; }
+ #if ENABLED(POWER_MONITOR_CURRENT)
+ static void draw_current();
+ FORCE_INLINE static bool current_display_enabled() { return TEST(flags, PM_DISP_BIT_I); }
+ FORCE_INLINE static void set_current_display(const bool b) { SET_BIT_TO(flags, PM_DISP_BIT_I, b); }
+ FORCE_INLINE static void toggle_current_display() { TBI(flags, PM_DISP_BIT_I); }
+ #endif
+ #if HAS_POWER_MONITOR_VREF
+ static void draw_voltage();
+ FORCE_INLINE static bool voltage_display_enabled() { return TEST(flags, PM_DISP_BIT_V); }
+ FORCE_INLINE static void set_voltage_display(const bool b) { SET_BIT_TO(flags, PM_DISP_BIT_V, b); }
+ FORCE_INLINE static void toggle_voltage_display() { TBI(flags, PM_DISP_BIT_V); }
+ #endif
+ #if HAS_POWER_MONITOR_WATTS
+ static void draw_power();
+ FORCE_INLINE static bool power_display_enabled() { return TEST(flags, PM_DISP_BIT_P); }
+ FORCE_INLINE static void set_power_display(const bool b) { SET_BIT_TO(flags, PM_DISP_BIT_P, b); }
+ FORCE_INLINE static void toggle_power_display() { TBI(flags, PM_DISP_BIT_P); }
+ #endif
+ #endif
+
+ static void reset() {
+ flags = 0x00;
+
+ #if ENABLED(POWER_MONITOR_CURRENT)
+ amps.reset();
+ #endif
+
+ #if ENABLED(POWER_MONITOR_VOLTAGE)
+ volts.reset();
+ #endif
+
+ #if ENABLED(SDSUPPORT)
+ display_item_ms = 0;
+ display_item = 0;
+ #endif
+ }
+
+ static void capture_values() {
+ #if ENABLED(POWER_MONITOR_CURRENT)
+ amps.capture();
+ #endif
+ #if ENABLED(POWER_MONITOR_VOLTAGE)
+ volts.capture();
+ #endif
+ }
+};
+
+extern PowerMonitor power_monitor;
diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp
index bb0062d4e..29a2cef97 100644
--- a/Marlin/src/feature/powerloss.cpp
+++ b/Marlin/src/feature/powerloss.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -40,6 +40,10 @@ uint8_t PrintJobRecovery::queue_index_r;
uint32_t PrintJobRecovery::cmd_sdpos, // = 0
PrintJobRecovery::sdpos[BUFSIZE];
+#if ENABLED(DWIN_CREALITY_LCD)
+ bool PrintJobRecovery::dwin_flag; // = false
+#endif
+
#include "../sd/cardreader.h"
#include "../lcd/ultralcd.h"
#include "../gcode/queue.h"
@@ -62,12 +66,16 @@ PrintJobRecovery recovery;
#ifndef POWER_LOSS_PURGE_LEN
#define POWER_LOSS_PURGE_LEN 0
#endif
+#ifndef POWER_LOSS_ZRAISE
+ #define POWER_LOSS_ZRAISE 2 // Move on loss with backup power, or on resume without it
+#endif
+
+#if DISABLED(BACKUP_POWER_SUPPLY)
+ #undef POWER_LOSS_RETRACT_LEN // No retract at outage without backup power
+#endif
#ifndef POWER_LOSS_RETRACT_LEN
#define POWER_LOSS_RETRACT_LEN 0
#endif
-#ifndef POWER_LOSS_ZRAISE
- #define POWER_LOSS_ZRAISE 2
-#endif
/**
* Clear the recovery info
@@ -103,8 +111,9 @@ void PrintJobRecovery::check() {
//if (!card.isMounted()) card.mount();
if (card.isMounted()) {
load();
- if (!valid()) return purge();
+ if (!valid()) return cancel();
queue.inject_P(PSTR("M1000 S"));
+ TERN_(DWIN_CREALITY_LCD, dwin_flag = true);
}
}
@@ -139,7 +148,7 @@ void PrintJobRecovery::prepare() {
/**
* Save the current machine state to the power-loss recovery file
*/
-void PrintJobRecovery::save(const bool force/*=false*/) {
+void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/) {
#if SAVE_INFO_INTERVAL_MS > 0
static millis_t next_save_ms; // = 0
@@ -172,12 +181,9 @@ void PrintJobRecovery::save(const bool force/*=false*/) {
// Machine state
info.current_position = current_position;
- #if HAS_HOME_OFFSET
- info.home_offset = home_offset;
- #endif
- #if HAS_POSITION_SHIFT
- info.position_shift = position_shift;
- #endif
+ info.zraise = zraise;
+ TERN_(HAS_HOME_OFFSET, info.home_offset = home_offset);
+ TERN_(HAS_POSITION_SHIFT, info.position_shift = position_shift);
info.feedrate = uint16_t(feedrate_mm_s * 60.0f);
#if EXTRUDERS > 1
@@ -189,7 +195,7 @@ void PrintJobRecovery::save(const bool force/*=false*/) {
#if EXTRUDERS > 1
for (int8_t e = 0; e < EXTRUDERS; e++) info.filament_size[e] = planner.filament_size[e];
#else
- if (parser.volumetric_enabled) info.filament_size = planner.filament_size[active_extruder];
+ if (parser.volumetric_enabled) info.filament_size[0] = planner.filament_size[active_extruder];
#endif
#endif
@@ -197,28 +203,18 @@ void PrintJobRecovery::save(const bool force/*=false*/) {
HOTEND_LOOP() info.target_temperature[e] = thermalManager.temp_hotend[e].target;
#endif
- #if HAS_HEATED_BED
- info.target_temperature_bed = thermalManager.temp_bed.target;
- #endif
+ TERN_(HAS_HEATED_BED, info.target_temperature_bed = thermalManager.temp_bed.target);
- #if FAN_COUNT
+ #if HAS_FAN
COPY(info.fan_speed, thermalManager.fan_speed);
#endif
#if HAS_LEVELING
info.leveling = planner.leveling_active;
- info.fade = (
- #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
- planner.z_fade_height
- #else
- 0
- #endif
- );
+ info.fade = TERN0(ENABLE_LEVELING_FADE_HEIGHT, planner.z_fade_height);
#endif
- #if ENABLED(GRADIENT_MIX)
- memcpy(&info.gradient, &mixer.gradient, sizeof(info.gradient));
- #endif
+ TERN_(GRADIENT_MIX, memcpy(&info.gradient, &mixer.gradient, sizeof(info.gradient)));
#if ENABLED(FWRETRACT)
COPY(info.retract, fwretract.current_retract);
@@ -237,33 +233,74 @@ void PrintJobRecovery::save(const bool force/*=false*/) {
#if PIN_EXISTS(POWER_LOSS)
+ #if ENABLED(BACKUP_POWER_SUPPLY)
+
+ void PrintJobRecovery::retract_and_lift(const float &zraise) {
+ #if POWER_LOSS_RETRACT_LEN || POWER_LOSS_ZRAISE
+
+ gcode.set_relative_mode(true); // Use relative coordinates
+
+ #if POWER_LOSS_RETRACT_LEN
+ // Retract filament now
+ gcode.process_subcommands_now_P(PSTR("G1 F3000 E-" STRINGIFY(POWER_LOSS_RETRACT_LEN)));
+ #endif
+
+ #if POWER_LOSS_ZRAISE
+ // Raise the Z axis now
+ if (zraise) {
+ char cmd[20], str_1[16];
+ sprintf_P(cmd, PSTR("G0 Z%s"), dtostrf(zraise, 1, 3, str_1));
+ gcode.process_subcommands_now(cmd);
+ }
+ #else
+ UNUSED(zraise);
+ #endif
+
+ //gcode.axis_relative = info.axis_relative;
+ planner.synchronize();
+ #endif
+ }
+
+ #endif
+
+ /**
+ * An outage was detected by a sensor pin.
+ * - If not SD printing, let the machine turn off on its own with no "KILL" screen
+ * - Disable all heaters first to save energy
+ * - Save the recovery data for the current instant
+ * - If backup power is available Retract E and Raise Z
+ * - Go to the KILL screen
+ */
void PrintJobRecovery::_outage() {
#if ENABLED(BACKUP_POWER_SUPPLY)
static bool lock = false;
- if (lock) return; // No re-entrance from idle() during raise_z()
+ if (lock) return; // No re-entrance from idle() during retract_and_lift()
lock = true;
#endif
- if (IS_SD_PRINTING()) save(true);
+
+ #if POWER_LOSS_ZRAISE
+ // Get the limited Z-raise to do now or on resume
+ const float zraise = _MAX(0, _MIN(current_position.z + POWER_LOSS_ZRAISE, Z_MAX_POS - 1) - current_position.z);
+ #else
+ constexpr float zraise = 0;
+ #endif
+
+ // Save, including the limited Z raise
+ if (IS_SD_PRINTING()) save(true, zraise);
+
+ // Disable all heaters to reduce power loss
+ thermalManager.disable_all_heaters();
+
#if ENABLED(BACKUP_POWER_SUPPLY)
- raise_z();
+ // Do a hard-stop of the steppers (with possibly a loud thud)
+ quickstop_stepper();
+ // With backup power a retract and raise can be done now
+ retract_and_lift(zraise);
#endif
kill(GET_TEXT(MSG_OUTAGE_RECOVERY));
}
- #if ENABLED(BACKUP_POWER_SUPPLY)
-
- void PrintJobRecovery::raise_z() {
- // Disable all heaters to reduce power loss
- thermalManager.disable_all_heaters();
- quickstop_stepper();
- // Raise Z axis
- gcode.process_subcommands_now_P(PSTR("G91\nG0 Z" STRINGIFY(POWER_LOSS_ZRAISE)));
- planner.synchronize();
- }
-
- #endif
-
#endif
/**
@@ -285,6 +322,8 @@ void PrintJobRecovery::write() {
*/
void PrintJobRecovery::resume() {
+ char cmd[MAX_CMD_SIZE+16], str_1[16], str_2[16];
+
const uint32_t resume_sdpos = info.sdpos; // Get here before the stepper ISR overwrites it
#if HAS_LEVELING
@@ -293,54 +332,46 @@ void PrintJobRecovery::resume() {
#endif
// Reset E, raise Z, home XY...
- gcode.process_subcommands_now_P(PSTR("G92.9 E0"
- #if Z_HOME_DIR > 0
+ #if Z_HOME_DIR > 0
- // If Z homing goes to max, just reset E and home all
- "\n"
- "G28R0"
- #if ENABLED(MARLIN_DEV_MODE)
- "S"
- #endif
+ // If Z homing goes to max, just reset E and home all
+ gcode.process_subcommands_now_P(PSTR(
+ "G92.9 E0\n"
+ "G28R0" TERN_(MARLIN_DEV_MODE, "S")
+ ));
- #else // "G92.9 E0 ..."
+ #else // "G92.9 E0 ..."
- // Set Z to 0, raise Z by RECOVERY_ZRAISE, and Home (XY only for Cartesian)
- // with no raise. (Only do simulated homing in Marlin Dev Mode.)
- #if ENABLED(BACKUP_POWER_SUPPLY)
- "Z" STRINGIFY(POWER_LOSS_ZRAISE) // Z-axis was already raised at outage
- #else
- "Z0\n" // Set Z=0
- "G1Z" STRINGIFY(POWER_LOSS_ZRAISE) // Raise Z
- #endif
- "\n"
+ // Set Z to 0, raise Z by info.zraise, and Home (XY only for Cartesian)
+ // with no raise. (Only do simulated homing in Marlin Dev Mode.)
- "G28R0"
- #if ENABLED(MARLIN_DEV_MODE)
- "S"
- #elif !IS_KINEMATIC
- "XY"
- #endif
- #endif
- ));
+ sprintf_P(cmd, PSTR("G92.9 E0 "
+ #if ENABLED(BACKUP_POWER_SUPPLY)
+ "Z%s" // Z was already raised at outage
+ #else
+ "Z0\nG1Z%s" // Set Z=0 and Raise Z now
+ #endif
+ ),
+ dtostrf(info.zraise, 1, 3, str_1)
+ );
+ gcode.process_subcommands_now(cmd);
+
+ gcode.process_subcommands_now_P(PSTR(
+ "G28R0" // No raise during G28
+ TERN_(MARLIN_DEV_MODE, "S") // Simulated Homing
+ TERN_(IS_CARTESIAN, "XY") // Don't home Z on Cartesian
+ ));
+
+ #endif
// Pretend that all axes are homed
axis_homed = axis_known_position = xyz_bits;
- char cmd[MAX_CMD_SIZE+16], str_1[16], str_2[16];
-
- // Select the previously active tool (with no_move)
- #if EXTRUDERS > 1
- sprintf_P(cmd, PSTR("T%i S"), info.active_extruder);
- gcode.process_subcommands_now(cmd);
- #endif
-
// Recover volumetric extrusion state
#if DISABLED(NO_VOLUMETRICS)
#if EXTRUDERS > 1
for (int8_t e = 0; e < EXTRUDERS; e++) {
- dtostrf(info.filament_size[e], 1, 3, str_1);
- sprintf_P(cmd, PSTR("M200 T%i D%s"), e, str_1);
+ sprintf_P(cmd, PSTR("M200 T%i D%s"), e, dtostrf(info.filament_size[e], 1, 3, str_1));
gcode.process_subcommands_now(cmd);
}
if (!info.volumetric_enabled) {
@@ -349,8 +380,7 @@ void PrintJobRecovery::resume() {
}
#else
if (info.volumetric_enabled) {
- dtostrf(info.filament_size, 1, 3, str_1);
- sprintf_P(cmd, PSTR("M200 D%s"), str_1);
+ sprintf_P(cmd, PSTR("M200 D%s"), dtostrf(info.filament_size[0], 1, 3, str_1));
gcode.process_subcommands_now(cmd);
}
#endif
@@ -366,12 +396,12 @@ void PrintJobRecovery::resume() {
#endif
// Restore all hotend temperatures
- #if HOTENDS
+ #if HAS_HOTEND
HOTEND_LOOP() {
const int16_t et = info.target_temperature[e];
if (et) {
- #if HOTENDS > 1
- sprintf_P(cmd, PSTR("T%i"), e);
+ #if HAS_MULTI_HOTEND
+ sprintf_P(cmd, PSTR("T%i S"), e);
gcode.process_subcommands_now(cmd);
#endif
sprintf_P(cmd, PSTR("M109 S%i"), et);
@@ -380,6 +410,12 @@ void PrintJobRecovery::resume() {
}
#endif
+ // Select the previously active tool (with no_move)
+ #if EXTRUDERS > 1
+ sprintf_P(cmd, PSTR("T%i S"), info.active_extruder);
+ gcode.process_subcommands_now(cmd);
+ #endif
+
// Restore print cooling fan speeds
FANS_LOOP(i) {
uint8_t f = info.fan_speed[i];
@@ -413,18 +449,21 @@ void PrintJobRecovery::resume() {
memcpy(&mixer.gradient, &info.gradient, sizeof(info.gradient));
#endif
- // Extrude and retract to clean the nozzle
- #if POWER_LOSS_PURGE_LEN
- //sprintf_P(cmd, PSTR("G1 E%d F200"), POWER_LOSS_PURGE_LEN);
- //gcode.process_subcommands_now(cmd);
- gcode.process_subcommands_now_P(PSTR("G1 E" STRINGIFY(POWER_LOSS_PURGE_LEN) " F200"));
+ // Un-retract if there was a retract at outage
+ #if POWER_LOSS_RETRACT_LEN
+ gcode.process_subcommands_now_P(PSTR("G1 E" STRINGIFY(POWER_LOSS_RETRACT_LEN) " F3000"));
#endif
- #if POWER_LOSS_RETRACT_LEN
- sprintf_P(cmd, PSTR("G1 E%d F3000"), POWER_LOSS_PURGE_LEN - (POWER_LOSS_RETRACT_LEN));
+ // Additional purge if configured
+ #if POWER_LOSS_PURGE_LEN
+ sprintf_P(cmd, PSTR("G1 E%d F200"), (POWER_LOSS_PURGE_LEN) + (POWER_LOSS_RETRACT_LEN));
gcode.process_subcommands_now(cmd);
#endif
+ #if ENABLED(NOZZLE_CLEAN_FEATURE)
+ gcode.process_subcommands_now_P(PSTR("G12"));
+ #endif
+
// Move back to the saved XY
sprintf_P(cmd, PSTR("G1 X%s Y%s F3000"),
dtostrf(info.current_position.x, 1, 3, str_1),
@@ -442,13 +481,6 @@ void PrintJobRecovery::resume() {
#endif
gcode.process_subcommands_now(cmd);
- // Un-retract
- #if POWER_LOSS_PURGE_LEN
- //sprintf_P(cmd, PSTR("G1 E%d F3000"), POWER_LOSS_PURGE_LEN);
- //gcode.process_subcommands_now(cmd);
- gcode.process_subcommands_now_P(PSTR("G1 E" STRINGIFY(POWER_LOSS_PURGE_LEN) " F3000"));
- #endif
-
// Restore the feedrate
sprintf_P(cmd, PSTR("G1 F%d"), info.feedrate);
gcode.process_subcommands_now(cmd);
@@ -460,12 +492,8 @@ void PrintJobRecovery::resume() {
// Relative axis modes
gcode.axis_relative = info.axis_relative;
- #if HAS_HOME_OFFSET
- home_offset = info.home_offset;
- #endif
- #if HAS_POSITION_SHIFT
- position_shift = info.position_shift;
- #endif
+ TERN_(HAS_HOME_OFFSET, home_offset = info.home_offset);
+ TERN_(HAS_POSITION_SHIFT, position_shift = info.position_shift);
#if HAS_HOME_OFFSET || HAS_POSITION_SHIFT
LOOP_XYZ(i) update_workspace_offset((AxisEnum)i);
#endif
@@ -489,15 +517,17 @@ void PrintJobRecovery::resume() {
DEBUG_ECHOPGM("current_position: ");
LOOP_XYZE(i) {
if (i) DEBUG_CHAR(',');
- DEBUG_ECHO(info.current_position[i]);
+ DEBUG_DECIMAL(info.current_position[i]);
}
DEBUG_EOL();
+ DEBUG_ECHOLNPAIR("zraise: ", info.zraise);
+
#if HAS_HOME_OFFSET
DEBUG_ECHOPGM("home_offset: ");
LOOP_XYZ(i) {
if (i) DEBUG_CHAR(',');
- DEBUG_ECHO(info.home_offset[i]);
+ DEBUG_DECIMAL(info.home_offset[i]);
}
DEBUG_EOL();
#endif
@@ -506,7 +536,7 @@ void PrintJobRecovery::resume() {
DEBUG_ECHOPGM("position_shift: ");
LOOP_XYZ(i) {
if (i) DEBUG_CHAR(',');
- DEBUG_ECHO(info.position_shift[i]);
+ DEBUG_DECIMAL(info.position_shift[i]);
}
DEBUG_EOL();
#endif
@@ -517,7 +547,7 @@ void PrintJobRecovery::resume() {
DEBUG_ECHOLNPAIR("active_extruder: ", int(info.active_extruder));
#endif
- #if HOTENDS
+ #if HAS_HOTEND
DEBUG_ECHOPGM("target_temperature: ");
HOTEND_LOOP() {
DEBUG_ECHO(info.target_temperature[e]);
@@ -530,7 +560,7 @@ void PrintJobRecovery::resume() {
DEBUG_ECHOLNPAIR("target_temperature_bed: ", info.target_temperature_bed);
#endif
- #if FAN_COUNT
+ #if HAS_FAN
DEBUG_ECHOPGM("fan_speed: ");
FANS_LOOP(i) {
DEBUG_ECHO(int(info.fan_speed[i]));
@@ -540,7 +570,7 @@ void PrintJobRecovery::resume() {
#endif
#if HAS_LEVELING
- DEBUG_ECHOLNPAIR("leveling: ", int(info.leveling), "\n fade: ", int(info.fade));
+ DEBUG_ECHOLNPAIR("leveling: ", int(info.leveling), " fade: ", info.fade);
#endif
#if ENABLED(FWRETRACT)
DEBUG_ECHOPGM("retract: ");
diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h
index 049656078..30ea34342 100644
--- a/Marlin/src/feature/powerloss.h
+++ b/Marlin/src/feature/powerloss.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -26,6 +26,8 @@
*/
#include "../sd/cardreader.h"
+#include "../gcode/gcode.h"
+
#include "../inc/MarlinConfig.h"
#if ENABLED(MIXING_EXTRUDER)
@@ -45,6 +47,7 @@ typedef struct {
// Machine state
xyze_pos_t current_position;
+ float zraise;
#if HAS_HOME_OFFSET
xyz_pos_t home_offset;
@@ -61,14 +64,10 @@ typedef struct {
#if DISABLED(NO_VOLUMETRICS)
bool volumetric_enabled;
- #if EXTRUDERS > 1
- float filament_size[EXTRUDERS];
- #else
- float filament_size;
- #endif
+ float filament_size[EXTRUDERS];
#endif
- #if HOTENDS
+ #if HAS_HOTEND
int16_t target_temperature[HOTENDS];
#endif
@@ -76,7 +75,7 @@ typedef struct {
int16_t target_temperature_bed;
#endif
- #if FAN_COUNT
+ #if HAS_FAN
uint8_t fan_speed[FAN_COUNT];
#endif
@@ -110,6 +109,8 @@ typedef struct {
uint8_t valid_foot;
+ bool valid() { return valid_head && valid_head == valid_foot; }
+
} job_recovery_info_t;
class PrintJobRecovery {
@@ -123,6 +124,10 @@ class PrintJobRecovery {
static uint32_t cmd_sdpos, //!< SD position of the next command
sdpos[BUFSIZE]; //!< SD positions of queued commands
+ #if ENABLED(DWIN_CREALITY_LCD)
+ static bool dwin_flag;
+ #endif
+
static void init();
static void prepare();
@@ -159,33 +164,34 @@ class PrintJobRecovery {
static inline void cancel() { purge(); card.autostart_index = 0; }
static void load();
- static void save(const bool force=ENABLED(SAVE_EACH_CMD_MODE));
+ static void save(const bool force=ENABLED(SAVE_EACH_CMD_MODE), const float zraise=0);
- #if PIN_EXISTS(POWER_LOSS)
- static inline void outage() {
- if (enabled && READ(POWER_LOSS_PIN) == POWER_LOSS_STATE)
- _outage();
- }
- #endif
+ #if PIN_EXISTS(POWER_LOSS)
+ static inline void outage() {
+ if (enabled && READ(POWER_LOSS_PIN) == POWER_LOSS_STATE)
+ _outage();
+ }
+ #endif
- static inline bool valid() { return info.valid_head && info.valid_head == info.valid_foot; }
+ static inline bool valid() { return info.valid(); }
- #if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
- static void debug(PGM_P const prefix);
- #else
- static inline void debug(PGM_P const) {}
- #endif
+ #if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
+ static void debug(PGM_P const prefix);
+ #else
+ static inline void debug(PGM_P const) {}
+ #endif
private:
static void write();
- #if ENABLED(BACKUP_POWER_SUPPLY)
- static void raise_z();
- #endif
+ #if ENABLED(BACKUP_POWER_SUPPLY)
+ static void retract_and_lift(const float &zraise);
+ #endif
- #if PIN_EXISTS(POWER_LOSS)
- static void _outage();
- #endif
+ #if PIN_EXISTS(POWER_LOSS)
+ friend class GcodeSuite;
+ static void _outage();
+ #endif
};
extern PrintJobRecovery recovery;
diff --git a/Marlin/src/feature/probe_temp_comp.cpp b/Marlin/src/feature/probe_temp_comp.cpp
index 6b787f420..af8039d8b 100644
--- a/Marlin/src/feature/probe_temp_comp.cpp
+++ b/Marlin/src/feature/probe_temp_comp.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -29,11 +29,11 @@
ProbeTempComp temp_comp;
-int16_t ProbeTempComp::z_offsets_probe[ProbeTempComp::cali_info_init[TSI_PROBE].measurements], // = {0}
- ProbeTempComp::z_offsets_bed[ProbeTempComp::cali_info_init[TSI_BED].measurements]; // = {0}
+int16_t ProbeTempComp::z_offsets_probe[cali_info_init[TSI_PROBE].measurements], // = {0}
+ ProbeTempComp::z_offsets_bed[cali_info_init[TSI_BED].measurements]; // = {0}
#if ENABLED(USE_TEMP_EXT_COMPENSATION)
- int16_t ProbeTempComp::z_offsets_ext[ProbeTempComp::cali_info_init[TSI_EXT].measurements]; // = {0}
+ int16_t ProbeTempComp::z_offsets_ext[cali_info_init[TSI_EXT].measurements]; // = {0}
#endif
int16_t *ProbeTempComp::sensor_z_offsets[TSI_COUNT] = {
@@ -44,12 +44,16 @@ int16_t *ProbeTempComp::sensor_z_offsets[TSI_COUNT] = {
};
const temp_calib_t ProbeTempComp::cali_info[TSI_COUNT] = {
- ProbeTempComp::cali_info_init[TSI_PROBE], ProbeTempComp::cali_info_init[TSI_BED]
+ cali_info_init[TSI_PROBE], cali_info_init[TSI_BED]
#if ENABLED(USE_TEMP_EXT_COMPENSATION)
- , ProbeTempComp::cali_info_init[TSI_EXT]
+ , cali_info_init[TSI_EXT]
#endif
};
+constexpr xyz_pos_t ProbeTempComp::park_point;
+constexpr xy_pos_t ProbeTempComp::measure_point;
+constexpr int ProbeTempComp::probe_calib_bed_temp;
+
uint8_t ProbeTempComp::calib_idx; // = 0
float ProbeTempComp::init_measurement; // = 0.0
@@ -161,28 +165,41 @@ void ProbeTempComp::compensate_measurement(const TempSensorID tsi, const float &
}
float ProbeTempComp::get_offset_for_temperature(const TempSensorID tsi, const float &temp) {
-
const uint8_t measurements = cali_info[tsi].measurements;
const float start_temp = cali_info[tsi].start_temp,
- end_temp = cali_info[tsi].end_temp,
res_temp = cali_info[tsi].temp_res;
const int16_t * const data = sensor_z_offsets[tsi];
- if (temp <= start_temp) return 0.0f;
- if (temp >= end_temp) return static_cast(data[measurements - 1]) / 1000.0f;
+ auto point = [&](uint8_t i) {
+ return xy_float_t({start_temp + i*res_temp, static_cast(data[i])});
+ };
+
+ auto linear_interp = [](float x, xy_float_t p1, xy_float_t p2) {
+ return (p2.y - p1.y) / (p2.x - p2.y) * (x - p1.x) + p1.y;
+ };
// Linear interpolation
- int16_t val1 = 0, val2 = data[0];
- uint8_t idx = 0;
- float meas_temp = start_temp + res_temp;
- while (meas_temp < temp) {
- if (++idx >= measurements) return static_cast(val2) / 1000.0f;
- meas_temp += res_temp;
- val1 = val2;
- val2 = data[idx];
- }
- const float factor = (meas_temp - temp) / static_cast(res_temp);
- return (static_cast(val2) - static_cast(val2 - val1) * factor) / 1000.0f;
+ uint8_t idx = static_cast((temp - start_temp) / res_temp);
+
+ // offset in um
+ float offset = 0.0f;
+
+ #if !defined(PTC_LINEAR_EXTRAPOLATION) || PTC_LINEAR_EXTRAPOLATION <= 0
+ if (idx < 0)
+ offset = 0.0f;
+ else if (idx > measurements - 2)
+ offset = static_cast(data[measurements - 1]);
+ #else
+ if (idx < 0)
+ offset = linear_interp(temp, point(0), point(PTC_LINEAR_EXTRAPOLATION));
+ else if (idx > measurements - 2)
+ offset = linear_interp(temp, point(measurements - PTC_LINEAR_EXTRAPOLATION - 1), point(measurements - 1));
+ #endif
+ else
+ offset = linear_interp(temp, point(idx), point(idx + 1));
+
+ // return offset in mm
+ return offset / 1000.0f;
}
bool ProbeTempComp::linear_regression(const TempSensorID tsi, float &k, float &d) {
diff --git a/Marlin/src/feature/probe_temp_comp.h b/Marlin/src/feature/probe_temp_comp.h
index 2ed10eeb9..626dd87f9 100644
--- a/Marlin/src/feature/probe_temp_comp.h
+++ b/Marlin/src/feature/probe_temp_comp.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -44,31 +44,64 @@ typedef struct {
* Z-probes like the P.I.N.D.A V2 allow for compensation of
* measurement errors/shifts due to changed temperature.
*/
+
+// Probe temperature calibration constants
+#ifndef PTC_SAMPLE_COUNT
+ #define PTC_SAMPLE_COUNT 10U
+#endif
+#ifndef PTC_SAMPLE_RES
+ #define PTC_SAMPLE_RES 5.0f
+#endif
+#ifndef PTC_SAMPLE_START
+ #define PTC_SAMPLE_START 30.0f
+#endif
+#define PTC_SAMPLE_END ((PTC_SAMPLE_START) + (PTC_SAMPLE_COUNT) * (PTC_SAMPLE_RES))
+
+// Bed temperature calibration constants
+#ifndef BTC_PROBE_TEMP
+ #define BTC_PROBE_TEMP 30.0f
+#endif
+#ifndef BTC_SAMPLE_COUNT
+ #define BTC_SAMPLE_COUNT 10U
+#endif
+#ifndef BTC_SAMPLE_STEP
+ #define BTC_SAMPLE_RES 5.0f
+#endif
+#ifndef BTC_SAMPLE_START
+ #define BTC_SAMPLE_START 60.0f
+#endif
+#define BTC_SAMPLE_END ((BTC_SAMPLE_START) + (BTC_SAMPLE_COUNT) * (BTC_SAMPLE_RES))
+
+#ifndef PTC_PROBE_HEATING_OFFSET
+ #define PTC_PROBE_HEATING_OFFSET 0.5f
+#endif
+
+#ifndef PTC_PROBE_RAISE
+ #define PTC_PROBE_RAISE 10.0f
+#endif
+
+static constexpr temp_calib_t cali_info_init[TSI_COUNT] = {
+ { PTC_SAMPLE_COUNT, PTC_SAMPLE_RES, PTC_SAMPLE_START, PTC_SAMPLE_END }, // Probe
+ { BTC_SAMPLE_COUNT, BTC_SAMPLE_RES, BTC_SAMPLE_START, BTC_SAMPLE_END }, // Bed
+ #if ENABLED(USE_TEMP_EXT_COMPENSATION)
+ { 20, 5, 180, 180 + 5 * 20 } // Extruder
+ #endif
+};
+
class ProbeTempComp {
public:
- static constexpr temp_calib_t cali_info_init[TSI_COUNT] = {
- { 10, 5, 30, 30 + 10 * 5 }, // Probe
- { 10, 5, 60, 60 + 10 * 5 }, // Bed
- #if ENABLED(USE_TEMP_EXT_COMPENSATION)
- { 20, 5, 180, 180 + 5 * 20 } // Extruder
- #endif
- };
static const temp_calib_t cali_info[TSI_COUNT];
// Where to park nozzle to wait for probe cooldown
- static constexpr float park_point_x = PTC_PARK_POS_X,
- park_point_y = PTC_PARK_POS_Y,
- park_point_z = PTC_PARK_POS_Z,
- // XY coordinates of nozzle for probing the bed
- measure_point_x = PTC_PROBE_POS_X, // Coordinates to probe
- measure_point_y = PTC_PROBE_POS_Y;
- //measure_point_x = 12.0f, // Coordinates to probe on MK52 magnetic heatbed
- //measure_point_y = 7.3f;
+ static constexpr xyz_pos_t park_point = PTC_PARK_POS;
- static constexpr int max_bed_temp = PTC_MAX_BED_TEMP, // Max temperature to avoid heating errors
- probe_calib_bed_temp = max_bed_temp, // Bed temperature while calibrating probe
- bed_calib_probe_temp = 30; // Probe temperature while calibrating bed
+ // XY coordinates of nozzle for probing the bed
+ static constexpr xy_pos_t measure_point = PTC_PROBE_POS; // Coordinates to probe
+ //measure_point = { 12.0f, 7.3f }; // Coordinates for the MK52 magnetic heatbed
+
+ static constexpr int probe_calib_bed_temp = BED_MAX_TARGET, // Bed temperature while calibrating probe
+ bed_calib_probe_temp = BTC_PROBE_TEMP; // Probe temperature while calibrating bed
static int16_t *sensor_z_offsets[TSI_COUNT],
z_offsets_probe[cali_info_init[TSI_PROBE].measurements], // (µm)
@@ -84,9 +117,7 @@ class ProbeTempComp {
static inline void clear_all_offsets() {
clear_offsets(TSI_BED);
clear_offsets(TSI_PROBE);
- #if ENABLED(USE_TEMP_EXT_COMPENSATION)
- clear_offsets(TSI_EXT);
- #endif
+ TERN_(USE_TEMP_EXT_COMPENSATION, clear_offsets(TSI_EXT));
}
static bool set_offset(const TempSensorID tsi, const uint8_t idx, const int16_t offset);
static void print_offsets();
diff --git a/Marlin/src/feature/runout.cpp b/Marlin/src/feature/runout.cpp
index bd4a653e9..0b5c0ebc2 100644
--- a/Marlin/src/feature/runout.cpp
+++ b/Marlin/src/feature/runout.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -39,6 +39,11 @@ bool FilamentMonitorBase::enabled = true,
bool FilamentMonitorBase::host_handling; // = false
#endif
+#if ENABLED(TOOLCHANGE_MIGRATION_FEATURE)
+ //#define DEBUG_TOOLCHANGE_MIGRATION_FEATURE
+ #include "../module/tool_change.h"
+#endif
+
/**
* Called by FilamentSensorSwitch::run when filament is detected.
* Called by FilamentSensorEncoder::block_completed when motion is detected.
@@ -47,13 +52,12 @@ void FilamentSensorBase::filament_present(const uint8_t extruder) {
runout.filament_present(extruder); // calls response.filament_present(extruder)
}
-#if ENABLED(FILAMENT_MOTION_SENSOR)
- uint8_t FilamentSensorEncoder::motion_detected;
-#endif
-
-#ifdef FILAMENT_RUNOUT_DISTANCE_MM
+#if HAS_FILAMENT_RUNOUT_DISTANCE
float RunoutResponseDelayed::runout_distance_mm = FILAMENT_RUNOUT_DISTANCE_MM;
volatile float RunoutResponseDelayed::runout_mm_countdown[EXTRUDERS];
+ #if ENABLED(FILAMENT_MOTION_SENSOR)
+ uint8_t FilamentSensorEncoder::motion_detected;
+ #endif
#else
int8_t RunoutResponseDebounced::runout_count; // = 0
#endif
@@ -74,13 +78,24 @@ void FilamentSensorBase::filament_present(const uint8_t extruder) {
void event_filament_runout() {
- #if ENABLED(ADVANCED_PAUSE_FEATURE)
- if (did_pause_print) return; // Action already in progress. Purge triggered repeated runout.
+ if (TERN0(ADVANCED_PAUSE_FEATURE, did_pause_print)) return; // Action already in progress. Purge triggered repeated runout.
+
+ #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE)
+ if (migration.in_progress) {
+ #if ENABLED(DEBUG_TOOLCHANGE_MIGRATION_FEATURE)
+ SERIAL_ECHOLN("Migration Already In Progress");
+ #endif
+ return; // Action already in progress. Purge triggered repeated runout.
+ }
+ if (migration.automode) {
+ #if ENABLED(DEBUG_TOOLCHANGE_MIGRATION_FEATURE)
+ SERIAL_ECHOLN("Migration Starting");
+ #endif
+ if (extruder_migration()) return;
+ }
#endif
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onFilamentRunout(ExtUI::getActiveTool());
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onFilamentRunout(ExtUI::getActiveTool()));
#if EITHER(HOST_PROMPT_SUPPORT, HOST_ACTION_COMMANDS)
const char tool = '0'
diff --git a/Marlin/src/feature/runout.h b/Marlin/src/feature/runout.h
index b975551c6..450ae1830 100644
--- a/Marlin/src/feature/runout.h
+++ b/Marlin/src/feature/runout.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -84,7 +84,7 @@ class TFilamentMonitor : public FilamentMonitorBase {
response.filament_present(extruder);
}
- #ifdef FILAMENT_RUNOUT_DISTANCE_MM
+ #if HAS_FILAMENT_RUNOUT_DISTANCE
static inline float& runout_distance() { return response.runout_distance_mm; }
static inline void set_runout_distance(const float &mm) { response.runout_distance_mm = mm; }
#endif
@@ -100,20 +100,14 @@ class TFilamentMonitor : public FilamentMonitorBase {
// Give the response a chance to update its counter.
static inline void run() {
- if (enabled && !filament_ran_out && (printingIsActive()
- #if ENABLED(ADVANCED_PAUSE_FEATURE)
- || did_pause_print
- #endif
- )) {
- #ifdef FILAMENT_RUNOUT_DISTANCE_MM
- cli(); // Prevent RunoutResponseDelayed::block_completed from accumulating here
- #endif
+ if ( enabled && !filament_ran_out
+ && (printingIsActive() || TERN0(ADVANCED_PAUSE_FEATURE, did_pause_print))
+ ) {
+ TERN_(HAS_FILAMENT_RUNOUT_DISTANCE, cli()); // Prevent RunoutResponseDelayed::block_completed from accumulating here
response.run();
sensor.run();
const bool ran_out = response.has_run_out();
- #ifdef FILAMENT_RUNOUT_DISTANCE_MM
- sei();
- #endif
+ TERN_(HAS_FILAMENT_RUNOUT_DISTANCE, sei());
if (ran_out) {
filament_ran_out = true;
event_filament_runout();
@@ -142,6 +136,7 @@ class FilamentSensorBase {
#define _INIT_RUNOUT(N) INIT_RUNOUT_PIN(FIL_RUNOUT##N##_PIN);
REPEAT_S(1, INCREMENT(NUM_RUNOUT_SENSORS), _INIT_RUNOUT)
#undef _INIT_RUNOUT
+ #undef INIT_RUNOUT_PIN
}
// Return a bitmask of runout pin states
@@ -153,14 +148,12 @@ class FilamentSensorBase {
// Return a bitmask of runout flag states (1 bits always indicates runout)
static inline uint8_t poll_runout_states() {
- return (poll_runout_pins()
- #if DISABLED(FIL_RUNOUT_INVERTING)
+ return poll_runout_pins()
+ #if FIL_RUNOUT_STATE == LOW
^ uint8_t(_BV(NUM_RUNOUT_SENSORS) - 1)
#endif
- );
+ ;
}
-
- #undef INIT_RUNOUT_PIN
};
#if ENABLED(FILAMENT_MOTION_SENSOR)
@@ -217,26 +210,14 @@ class FilamentSensorBase {
private:
static inline bool poll_runout_state(const uint8_t extruder) {
const uint8_t runout_states = poll_runout_states();
-
#if NUM_RUNOUT_SENSORS == 1
UNUSED(extruder);
+ #else
+ if ( !TERN0(DUAL_X_CARRIAGE, dxc_is_duplicating())
+ && !TERN0(MULTI_NOZZLE_DUPLICATION, extruder_duplication_enabled)
+ ) return TEST(runout_states, extruder); // A specific extruder ran out
#endif
-
- if (true
- #if NUM_RUNOUT_SENSORS > 1
- #if ENABLED(DUAL_X_CARRIAGE)
- && (dual_x_carriage_mode == DXC_DUPLICATION_MODE || dual_x_carriage_mode == DXC_MIRRORED_MODE)
- #elif ENABLED(MULTI_NOZZLE_DUPLICATION)
- && extruder_duplication_enabled
- #else
- && false
- #endif
- #endif
- ) return runout_states; // Any extruder
-
- #if NUM_RUNOUT_SENSORS > 1
- return TEST(runout_states, extruder); // Specific extruder
- #endif
+ return !!runout_states; // Any extruder ran out
}
public:
@@ -261,7 +242,7 @@ class FilamentSensorBase {
/********************************* RESPONSE TYPE *********************************/
-#ifdef FILAMENT_RUNOUT_DISTANCE_MM
+#if HAS_FILAMENT_RUNOUT_DISTANCE
// RunoutResponseDelayed triggers a runout event only if the length
// of filament specified by FILAMENT_RUNOUT_DISTANCE_MM has been fed
@@ -302,9 +283,7 @@ class FilamentSensorBase {
static inline void block_completed(const block_t* const b) {
if (b->steps.x || b->steps.y || b->steps.z
- #if ENABLED(ADVANCED_PAUSE_FEATURE)
- || did_pause_print // Allow pause purge move to re-trigger runout state
- #endif
+ || TERN0(ADVANCED_PAUSE_FEATURE, did_pause_print) // Allow pause purge move to re-trigger runout state
) {
// Only trigger on extrusion with XYZ movement to allow filament change and retract/recover.
const uint8_t e = b->extruder;
@@ -314,7 +293,7 @@ class FilamentSensorBase {
}
};
-#else // !FILAMENT_RUNOUT_DISTANCE_MM
+#else // !HAS_FILAMENT_RUNOUT_DISTANCE
// RunoutResponseDebounced triggers a runout event after a runout
// condition has been detected runout_threshold times in a row.
@@ -331,21 +310,13 @@ class FilamentSensorBase {
static inline void filament_present(const uint8_t) { runout_count = runout_threshold; }
};
-#endif // !FILAMENT_RUNOUT_DISTANCE_MM
+#endif // !HAS_FILAMENT_RUNOUT_DISTANCE
/********************************* TEMPLATE SPECIALIZATION *********************************/
typedef TFilamentMonitor<
- #ifdef FILAMENT_RUNOUT_DISTANCE_MM
- RunoutResponseDelayed,
- #if ENABLED(FILAMENT_MOTION_SENSOR)
- FilamentSensorEncoder
- #else
- FilamentSensorSwitch
- #endif
- #else
- RunoutResponseDebounced, FilamentSensorSwitch
- #endif
-> FilamentMonitor;
+ TERN(HAS_FILAMENT_RUNOUT_DISTANCE, RunoutResponseDelayed, RunoutResponseDebounced),
+ TERN(FILAMENT_MOTION_SENSOR, FilamentSensorEncoder, FilamentSensorSwitch)
+ > FilamentMonitor;
extern FilamentMonitor runout;
diff --git a/Marlin/src/feature/snmm.cpp b/Marlin/src/feature/snmm.cpp
index e994028d9..25723f7b3 100644
--- a/Marlin/src/feature/snmm.cpp
+++ b/Marlin/src/feature/snmm.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/feature/snmm.h b/Marlin/src/feature/snmm.h
index 671542e3b..10805c8e2 100644
--- a/Marlin/src/feature/snmm.h
+++ b/Marlin/src/feature/snmm.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/solenoid.cpp b/Marlin/src/feature/solenoid.cpp
index d53118fdd..8646ec872 100644
--- a/Marlin/src/feature/solenoid.cpp
+++ b/Marlin/src/feature/solenoid.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/feature/solenoid.h b/Marlin/src/feature/solenoid.h
index 5a503b105..2ba4983fb 100644
--- a/Marlin/src/feature/solenoid.h
+++ b/Marlin/src/feature/solenoid.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp
index 0567ba5d3..3dcf6e928 100644
--- a/Marlin/src/feature/spindle_laser.cpp
+++ b/Marlin/src/feature/spindle_laser.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -31,71 +31,85 @@
#include "spindle_laser.h"
SpindleLaser cutter;
+uint8_t SpindleLaser::power;
+bool SpindleLaser::isReady; // Ready to apply power setting from the UI to OCR
+cutter_power_t SpindleLaser::menuPower, // Power set via LCD menu in PWM, PERCENT, or RPM
+ SpindleLaser::unitPower; // LCD status power in PWM, PERCENT, or RPM
-cutter_power_t SpindleLaser::power; // = 0
-
+#if ENABLED(MARLIN_DEV_MODE)
+ cutter_frequency_t SpindleLaser::frequency; // setting PWM frequency; range: 2K - 50K
+#endif
#define SPINDLE_LASER_PWM_OFF ((SPINDLE_LASER_PWM_INVERT) ? 255 : 0)
+//
+// Init the cutter to a safe OFF state
+//
void SpindleLaser::init() {
- OUT_WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_HIGH); // Init spindle to off
+ OUT_WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_HIGH); // Init spindle to off
#if ENABLED(SPINDLE_CHANGE_DIR)
- OUT_WRITE(SPINDLE_DIR_PIN, SPINDLE_INVERT_DIR ? 255 : 0); // Init rotation to clockwise (M3)
+ OUT_WRITE(SPINDLE_DIR_PIN, SPINDLE_INVERT_DIR ? 255 : 0); // Init rotation to clockwise (M3)
#endif
#if ENABLED(SPINDLE_LASER_PWM)
SET_PWM(SPINDLE_LASER_PWM_PIN);
- analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // set to lowest speed
+ analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // set to lowest speed
+ #endif
+ #if ENABLED(HAL_CAN_SET_PWM_FREQ) && defined(SPINDLE_LASER_FREQUENCY)
+ set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY);
+ TERN_(MARLIN_DEV_MODE, frequency = SPINDLE_LASER_FREQUENCY);
#endif
}
#if ENABLED(SPINDLE_LASER_PWM)
-
/**
- * ocr_val_mode() is used for debugging and to get the points needed to compute the RPM vs ocr_val line
- *
- * it accepts inputs of 0-255
+ * Set the cutter PWM directly to the given ocr value
*/
void SpindleLaser::set_ocr(const uint8_t ocr) {
- WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ACTIVE_HIGH); // turn spindle on (active low)
+ WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ACTIVE_HIGH); // turn spindle on
analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF);
}
-
+ void SpindleLaser::ocr_off() {
+ WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_HIGH); // Turn spindle off
+ analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Only write low byte
+ }
#endif
-void SpindleLaser::apply_power(const cutter_power_t inpow) {
- static cutter_power_t last_power_applied = 0;
- if (inpow == last_power_applied) return;
- last_power_applied = inpow;
+//
+// Set cutter ON/OFF state (and PWM) to the given cutter power value
+//
+void SpindleLaser::apply_power(const uint8_t opwr) {
+ static uint8_t last_power_applied = 0;
+ if (opwr == last_power_applied) return;
+ last_power_applied = opwr;
+ power = opwr;
#if ENABLED(SPINDLE_LASER_PWM)
- if (enabled()) {
- #define _scaled(F) ((F - (SPEED_POWER_INTERCEPT)) * inv_slope)
- constexpr float inv_slope = RECIPROCAL(SPEED_POWER_SLOPE),
- min_ocr = _scaled(SPEED_POWER_MIN),
- max_ocr = _scaled(SPEED_POWER_MAX);
- int16_t ocr_val;
- if (inpow <= SPEED_POWER_MIN) ocr_val = min_ocr; // Use minimum if set below
- else if (inpow >= SPEED_POWER_MAX) ocr_val = max_ocr; // Use maximum if set above
- else ocr_val = _scaled(inpow); // Use calculated OCR value
- set_ocr(ocr_val & 0xFF); // ...limited to Atmel PWM max
+ if (cutter.unitPower == 0 && CUTTER_UNIT_IS(RPM)) {
+ ocr_off();
+ isReady = false;
+ }
+ else if (enabled() || ENABLED(CUTTER_POWER_RELATIVE)) {
+ set_ocr(power);
+ isReady = true;
}
else {
- WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_HIGH); // Turn spindle off (active low)
- analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Only write low byte
+ ocr_off();
+ isReady = false;
}
#else
- WRITE(SPINDLE_LASER_ENA_PIN, (SPINDLE_LASER_ACTIVE_HIGH) ? enabled() : !enabled());
+ WRITE(SPINDLE_LASER_ENA_PIN, enabled() == SPINDLE_LASER_ACTIVE_HIGH);
+ isReady = true;
#endif
}
#if ENABLED(SPINDLE_CHANGE_DIR)
-
+ //
+ // Set the spindle direction and apply immediately
+ // Stop on direction change if SPINDLE_STOP_ON_DIR_CHANGE is enabled
+ //
void SpindleLaser::set_direction(const bool reverse) {
const bool dir_state = (reverse == SPINDLE_INVERT_DIR); // Forward (M3) HIGH when not inverted
- #if ENABLED(SPINDLE_STOP_ON_DIR_CHANGE)
- if (enabled() && READ(SPINDLE_DIR_PIN) != dir_state) disable();
- #endif
+ if (TERN0(SPINDLE_STOP_ON_DIR_CHANGE, enabled()) && READ(SPINDLE_DIR_PIN) != dir_state) disable();
WRITE(SPINDLE_DIR_PIN, dir_state);
}
-
#endif
#endif // HAS_CUTTER
diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h
index ea035299b..8240efa2d 100644
--- a/Marlin/src/feature/spindle_laser.h
+++ b/Marlin/src/feature/spindle_laser.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -28,55 +28,159 @@
#include "../inc/MarlinConfig.h"
-#if ENABLED(SPINDLE_FEATURE)
- #define _MSG_CUTTER(M) MSG_SPINDLE_##M
-#else
- #define _MSG_CUTTER(M) MSG_LASER_##M
-#endif
-#define MSG_CUTTER(M) _MSG_CUTTER(M)
+#include "spindle_laser_types.h"
-#if SPEED_POWER_MAX > 255
- typedef uint16_t cutter_power_t;
- #define CUTTER_MENU_TYPE uint16_5
-#else
- typedef uint8_t cutter_power_t;
- #define CUTTER_MENU_TYPE uint8
+#if ENABLED(LASER_POWER_INLINE)
+ #include "../module/planner.h"
#endif
+#define PCT_TO_PWM(X) ((X) * 255 / 100)
+
+#ifndef SPEED_POWER_INTERCEPT
+ #define SPEED_POWER_INTERCEPT 0
+#endif
+#define SPEED_POWER_FLOOR TERN(CUTTER_POWER_RELATIVE, SPEED_POWER_MIN, 0)
+
+// #define _MAP(N,S1,S2,D1,D2) ((N)*_MAX((D2)-(D1),0)/_MAX((S2)-(S1),1)+(D1))
+
class SpindleLaser {
public:
- static cutter_power_t power;
- static inline uint8_t powerPercent(const uint8_t pp) { return ui8_to_percent(pp); } // for display
+ static constexpr float
+ min_pct = round(TERN(CUTTER_POWER_RELATIVE, 0, (100 * float(SPEED_POWER_MIN) / TERN(SPINDLE_FEATURE, float(SPEED_POWER_MAX), 100)))),
+ max_pct = round(TERN(SPINDLE_FEATURE, 100, float(SPEED_POWER_MAX)));
+
+ static const inline uint8_t pct_to_ocr(const float pct) { return uint8_t(PCT_TO_PWM(pct)); }
+
+ // cpower = configured values (ie SPEED_POWER_MAX)
+ static const inline uint8_t cpwr_to_pct(const cutter_cpower_t cpwr) { // configured value to pct
+ return unitPower ? round(100 * (cpwr - SPEED_POWER_FLOOR) / (SPEED_POWER_MAX - SPEED_POWER_FLOOR)) : 0;
+ }
+
+ // Convert a configured value (cpower)(ie SPEED_POWER_STARTUP) to unit power (upwr, upower),
+ // which can be PWM, Percent, or RPM (rel/abs).
+ static const inline cutter_power_t cpwr_to_upwr(const cutter_cpower_t cpwr) { // STARTUP power to Unit power
+ const cutter_power_t upwr = (
+ #if ENABLED(SPINDLE_FEATURE)
+ // Spindle configured values are in RPM
+ #if CUTTER_UNIT_IS(RPM)
+ cpwr // to RPM
+ #elif CUTTER_UNIT_IS(PERCENT) // to PCT
+ cpwr_to_pct(cpwr)
+ #else // to PWM
+ PCT_TO_PWM(cpwr_to_pct(cpwr))
+ #endif
+ #else
+ // Laser configured values are in PCT
+ #if CUTTER_UNIT_IS(PWM255)
+ PCT_TO_PWM(cpwr)
+ #else
+ cpwr // to RPM/PCT
+ #endif
+ #endif
+ );
+ return upwr;
+ }
+
+ static const cutter_power_t mpower_min() { return cpwr_to_upwr(SPEED_POWER_MIN); }
+ static const cutter_power_t mpower_max() { return cpwr_to_upwr(SPEED_POWER_MAX); }
+
+ static bool isReady; // Ready to apply power setting from the UI to OCR
+ static uint8_t power;
+
+ #if ENABLED(MARLIN_DEV_MODE)
+ static cutter_frequency_t frequency; // Set PWM frequency; range: 2K-50K
+ #endif
+
+ static cutter_power_t menuPower, // Power as set via LCD menu in PWM, Percentage or RPM
+ unitPower; // Power as displayed status in PWM, Percentage or RPM
static void init();
- static inline bool enabled() { return !!power; }
-
- static inline void set_power(const cutter_power_t pwr) { power = pwr; }
-
- static inline void refresh() { apply_power(power); }
-
- static inline void set_enabled(const bool enable) {
- const bool was = enabled();
- set_power(enable ? 255 : 0);
- if (was != enable) power_delay();
- }
-
- static void apply_power(const cutter_power_t inpow);
-
- //static bool active() { return READ(SPINDLE_LASER_ENA_PIN) == SPINDLE_LASER_ACTIVE_HIGH; }
-
- static void update_output();
-
- #if ENABLED(SPINDLE_LASER_PWM)
- static void set_ocr(const uint8_t ocr);
- static inline void set_ocr_power(const cutter_power_t pwr) { power = pwr; set_ocr(pwr); }
+ #if ENABLED(MARLIN_DEV_MODE)
+ static inline void refresh_frequency() { set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); }
#endif
+ // Modifying this function should update everywhere
+ static inline bool enabled(const cutter_power_t opwr) { return opwr > 0; }
+ static inline bool enabled() { return enabled(power); }
+
+ static void apply_power(const uint8_t inpow);
+
+ FORCE_INLINE static void refresh() { apply_power(power); }
+ FORCE_INLINE static void set_power(const uint8_t upwr) { power = upwr; refresh(); }
+
+ #if ENABLED(SPINDLE_LASER_PWM)
+
+ static void set_ocr(const uint8_t ocr);
+ static inline void set_ocr_power(const uint8_t ocr) { power = ocr; set_ocr(ocr); }
+ static void ocr_off();
+ // Used to update output for power->OCR translation
+ static inline uint8_t upower_to_ocr(const cutter_power_t upwr) {
+ return (
+ #if CUTTER_UNIT_IS(PWM255)
+ uint8_t(upwr)
+ #elif CUTTER_UNIT_IS(PERCENT)
+ pct_to_ocr(upwr)
+ #else
+ uint8_t(pct_to_ocr(cpwr_to_pct(upwr)))
+ #endif
+ );
+ }
+
+ // Correct power to configured range
+ static inline cutter_power_t power_to_range(const cutter_power_t pwr) {
+ return power_to_range(pwr, (
+ #if CUTTER_UNIT_IS(PWM255)
+ 0
+ #elif CUTTER_UNIT_IS(PERCENT)
+ 1
+ #elif CUTTER_UNIT_IS(RPM)
+ 2
+ #else
+ #error "???"
+ #endif
+ ));
+ }
+ static inline cutter_power_t power_to_range(const cutter_power_t pwr, const uint8_t pwrUnit) {
+ if (pwr <= 0) return 0;
+ cutter_power_t upwr;
+ switch (pwrUnit) {
+ case 0: // PWM
+ upwr = cutter_power_t(
+ (pwr < pct_to_ocr(min_pct)) ? pct_to_ocr(min_pct) // Use minimum if set below
+ : (pwr > pct_to_ocr(max_pct)) ? pct_to_ocr(max_pct) // Use maximum if set above
+ : pwr
+ );
+ break;
+ case 1: // PERCENT
+ upwr = cutter_power_t(
+ (pwr < min_pct) ? min_pct // Use minimum if set below
+ : (pwr > max_pct) ? max_pct // Use maximum if set above
+ : pwr // PCT
+ );
+ break;
+ case 2: // RPM
+ upwr = cutter_power_t(
+ (pwr < SPEED_POWER_MIN) ? SPEED_POWER_MIN // Use minimum if set below
+ : (pwr > SPEED_POWER_MAX) ? SPEED_POWER_MAX // Use maximum if set above
+ : pwr // Calculate OCR value
+ );
+ break;
+ default: break;
+ }
+ return upwr;
+ }
+
+ #endif // SPINDLE_LASER_PWM
+
+ static inline void set_enabled(const bool enable) {
+ set_power(enable ? TERN(SPINDLE_LASER_PWM, (power ?: (unitPower ? upower_to_ocr(cpwr_to_upwr(SPEED_POWER_STARTUP)) : 0)), 255) : 0);
+ }
+
// Wait for spindle to spin up or spin down
- static inline void power_delay() {
- #if SPINDLE_LASER_POWERUP_DELAY || SPINDLE_LASER_POWERDOWN_DELAY
- safe_delay(enabled() ? SPINDLE_LASER_POWERUP_DELAY : SPINDLE_LASER_POWERDOWN_DELAY);
+ static inline void power_delay(const bool on) {
+ #if DISABLED(LASER_POWER_INLINE)
+ safe_delay(on ? SPINDLE_LASER_POWERUP_DELAY : SPINDLE_LASER_POWERDOWN_DELAY);
#endif
}
@@ -86,10 +190,93 @@ public:
static inline void set_direction(const bool) {}
#endif
- static inline void disable() { set_enabled(false); }
- static inline void enable_forward() { set_direction(false); set_enabled(true); }
- static inline void enable_reverse() { set_direction(true); set_enabled(true); }
+ static inline void disable() { isReady = false; set_enabled(false); }
+ #if HAS_LCD_MENU
+
+ static inline void enable_with_dir(const bool reverse) {
+ isReady = true;
+ const uint8_t ocr = TERN(SPINDLE_LASER_PWM, upower_to_ocr(menuPower), 255);
+ if (menuPower)
+ power = ocr;
+ else
+ menuPower = cpwr_to_upwr(SPEED_POWER_STARTUP);
+ unitPower = menuPower;
+ set_direction(reverse);
+ set_enabled(true);
+ }
+ FORCE_INLINE static void enable_forward() { enable_with_dir(false); }
+ FORCE_INLINE static void enable_reverse() { enable_with_dir(true); }
+
+ #if ENABLED(SPINDLE_LASER_PWM)
+ static inline void update_from_mpower() {
+ if (isReady) power = upower_to_ocr(menuPower);
+ unitPower = menuPower;
+ }
+ #endif
+
+ #endif
+
+ #if ENABLED(LASER_POWER_INLINE)
+ /**
+ * Inline power adds extra fields to the planner block
+ * to handle laser power and scale to movement speed.
+ */
+
+ // Force disengage planner power control
+ static inline void inline_disable() {
+ isReady = false;
+ unitPower = 0;
+ planner.laser_inline.status.isPlanned = false;
+ planner.laser_inline.status.isEnabled = false;
+ planner.laser_inline.power = 0;
+ }
+
+ // Inline modes of all other functions; all enable planner inline power control
+ static inline void set_inline_enabled(const bool enable) {
+ if (enable)
+ inline_power(cpwr_to_upwr(SPEED_POWER_STARTUP));
+ else {
+ isReady = false;
+ unitPower = menuPower = 0;
+ planner.laser_inline.status.isPlanned = false;
+ TERN(SPINDLE_LASER_PWM, inline_ocr_power, inline_power)(0);
+ }
+ }
+
+ // Set the power for subsequent movement blocks
+ static void inline_power(const cutter_power_t upwr) {
+ unitPower = menuPower = upwr;
+ #if ENABLED(SPINDLE_LASER_PWM)
+ #if ENABLED(SPEED_POWER_RELATIVE) && !CUTTER_UNIT_IS(RPM) // relative mode does not turn laser off at 0, except for RPM
+ planner.laser_inline.status.isEnabled = true;
+ planner.laser_inline.power = upower_to_ocr(upwr);
+ isReady = true;
+ #else
+ inline_ocr_power(upower_to_ocr(upwr));
+ #endif
+ #else
+ planner.laser_inline.status.isEnabled = enabled(upwr);
+ planner.laser_inline.power = upwr;
+ isReady = enabled(upwr);
+ #endif
+ }
+
+ static inline void inline_direction(const bool) { /* never */ }
+
+ #if ENABLED(SPINDLE_LASER_PWM)
+ static inline void inline_ocr_power(const uint8_t ocrpwr) {
+ isReady = ocrpwr > 0;
+ planner.laser_inline.status.isEnabled = ocrpwr > 0;
+ planner.laser_inline.power = ocrpwr;
+ }
+ #endif
+ #endif // LASER_POWER_INLINE
+
+ static inline void kill() {
+ TERN_(LASER_POWER_INLINE, inline_disable());
+ disable();
+ }
};
extern SpindleLaser cutter;
diff --git a/Marlin/src/feature/spindle_laser_types.h b/Marlin/src/feature/spindle_laser_types.h
new file mode 100644
index 000000000..181c4d73a
--- /dev/null
+++ b/Marlin/src/feature/spindle_laser_types.h
@@ -0,0 +1,53 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#pragma once
+
+/**
+ * feature/spindle_laser_types.h
+ * Support for Laser Power or Spindle Power & Direction
+ */
+
+#include "../inc/MarlinConfigPre.h"
+
+#if ENABLED(SPINDLE_FEATURE)
+ #define _MSG_CUTTER(M) MSG_SPINDLE_##M
+#else
+ #define _MSG_CUTTER(M) MSG_LASER_##M
+#endif
+#define MSG_CUTTER(M) _MSG_CUTTER(M)
+
+typedef IF<(SPEED_POWER_MAX > 255), uint16_t, uint8_t>::type cutter_cpower_t;
+
+#if CUTTER_UNIT_IS(RPM) && SPEED_POWER_MAX > 255
+ typedef uint16_t cutter_power_t;
+ #define CUTTER_MENU_POWER_TYPE uint16_5
+ #define cutter_power2str ui16tostr5rj
+#else
+ typedef uint8_t cutter_power_t;
+ #define CUTTER_MENU_POWER_TYPE uint8
+ #define cutter_power2str ui8tostr3rj
+#endif
+
+#if ENABLED(MARLIN_DEV_MODE)
+ typedef uint16_t cutter_frequency_t;
+ #define CUTTER_MENU_FREQUENCY_TYPE uint16_5
+#endif
diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp
index e5e69eed5..495d6a9f5 100644
--- a/Marlin/src/feature/tmc_util.cpp
+++ b/Marlin/src/feature/tmc_util.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -63,9 +63,9 @@
, is_stall:1
, is_stealth:1
, is_standstill:1
- #if HAS_STALLGUARD
- , sg_result_reasonable:1
- #endif
+ #if HAS_STALLGUARD
+ , sg_result_reasonable:1
+ #endif
#endif
;
#if ENABLED(TMC_DEBUG)
@@ -169,9 +169,7 @@
data.is_stealth = TEST(ds, STEALTH_bp);
data.is_standstill = TEST(ds, STST_bp);
#endif
- #if HAS_STALLGUARD
- data.sg_result_reasonable = false;
- #endif
+ TERN_(HAS_STALLGUARD, data.sg_result_reasonable = false);
#endif
return data;
}
@@ -213,9 +211,7 @@
SERIAL_PRINTLN(data.drv_status, HEX);
if (data.is_ot) SERIAL_ECHOLNPGM("overtemperature");
if (data.is_s2g) SERIAL_ECHOLNPGM("coil short circuit");
- #if ENABLED(TMC_DEBUG)
- tmc_report_all(true, true, true, true);
- #endif
+ TERN_(TMC_DEBUG, tmc_report_all(true, true, true, true));
kill(PSTR("Driver error"));
}
#endif
@@ -446,9 +442,7 @@
(void)monitor_tmc_driver(stepperE7, need_update_error_counters, need_debug_reporting);
#endif
- #if ENABLED(TMC_DEBUG)
- if (need_debug_reporting) SERIAL_EOL();
- #endif
+ if (TERN0(TMC_DEBUG, need_debug_reporting)) SERIAL_EOL();
}
}
@@ -486,6 +480,10 @@
TMC_GLOBAL_SCALER,
TMC_CS_ACTUAL,
TMC_PWM_SCALE,
+ TMC_PWM_SCALE_SUM,
+ TMC_PWM_SCALE_AUTO,
+ TMC_PWM_OFS_AUTO,
+ TMC_PWM_GRAD_AUTO,
TMC_VSENSE,
TMC_STEALTHCHOP,
TMC_MICROSTEPS,
@@ -498,7 +496,8 @@
TMC_TBL,
TMC_HEND,
TMC_HSTRT,
- TMC_SGT
+ TMC_SGT,
+ TMC_MSCNT
};
enum TMC_drv_status_enum : char {
TMC_DRV_CODES,
@@ -597,7 +596,10 @@
#if HAS_TMC220x
static void _tmc_status(TMC2208Stepper &st, const TMC_debug_enum i) {
switch (i) {
- case TMC_PWM_SCALE: SERIAL_PRINT(st.pwm_scale_sum(), DEC); break;
+ case TMC_PWM_SCALE_SUM: SERIAL_PRINT(st.pwm_scale_sum(), DEC); break;
+ case TMC_PWM_SCALE_AUTO: SERIAL_PRINT(st.pwm_scale_auto(), DEC); break;
+ case TMC_PWM_OFS_AUTO: SERIAL_PRINT(st.pwm_ofs_auto(), DEC); break;
+ case TMC_PWM_GRAD_AUTO: SERIAL_PRINT(st.pwm_grad_auto(), DEC); break;
case TMC_STEALTHCHOP: serialprint_truefalse(st.stealth()); break;
case TMC_S2VSA: if (st.s2vsa()) SERIAL_CHAR('*'); break;
case TMC_S2VSB: if (st.s2vsb()) SERIAL_CHAR('*'); break;
@@ -686,6 +688,7 @@
case TMC_TBL: SERIAL_PRINT(st.blank_time(), DEC); break;
case TMC_HEND: SERIAL_PRINT(st.hysteresis_end(), DEC); break;
case TMC_HSTRT: SERIAL_PRINT(st.hysteresis_start(), DEC); break;
+ case TMC_MSCNT: SERIAL_PRINT(st.get_microstep_counter(), DEC); break;
default: _tmc_status(st, i); break;
}
}
@@ -906,11 +909,20 @@
#if ENABLED(MONITOR_DRIVER_STATUS)
TMC_REPORT("triggered\n OTP\t", TMC_OTPW_TRIGGERED);
#endif
+
+ #if HAS_TMC220x
+ TMC_REPORT("pwm scale sum", TMC_PWM_SCALE_SUM);
+ TMC_REPORT("pwm scale auto", TMC_PWM_SCALE_AUTO);
+ TMC_REPORT("pwm offset auto", TMC_PWM_OFS_AUTO);
+ TMC_REPORT("pwm grad auto", TMC_PWM_GRAD_AUTO);
+ #endif
+
TMC_REPORT("off time", TMC_TOFF);
TMC_REPORT("blank time", TMC_TBL);
TMC_REPORT("hysteresis\n -end\t", TMC_HEND);
TMC_REPORT(" -start\t", TMC_HSTRT);
TMC_REPORT("Stallguard thrs", TMC_SGT);
+ TMC_REPORT("uStep count", TMC_MSCNT);
DRV_REPORT("DRVSTATUS", TMC_DRV_CODES);
#if HAS_TMCX1X0 || HAS_TMC220x
DRV_REPORT("sg_result", TMC_SG_RESULT);
@@ -1254,7 +1266,7 @@ void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z
#endif
}
- if (axis_connection) ui.set_status_P(GET_TEXT(MSG_ERROR_TMC));
+ if (axis_connection) LCD_MESSAGEPGM(MSG_ERROR_TMC);
}
#endif // HAS_TRINAMIC_CONFIG
diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h
index ccae8b660..2779ae4ef 100644
--- a/Marlin/src/feature/tmc_util.h
+++ b/Marlin/src/feature/tmc_util.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -35,6 +35,7 @@
#define CHOPPER_DEFAULT_36V { 5, 2, 4 }
#define CHOPPER_PRUSAMK3_24V { 3, -2, 6 }
#define CHOPPER_MARLIN_119 { 5, 2, 3 }
+#define CHOPPER_09STEP_24V { 3, -1, 5 }
#if ENABLED(MONITOR_DRIVER_STATUS) && !defined(MONITOR_DRIVER_STATUS_INTERVAL_MS)
#define MONITOR_DRIVER_STATUS_INTERVAL_MS 500u
@@ -69,15 +70,9 @@ class TMCStorage {
}
struct {
- #if HAS_STEALTHCHOP
- bool stealthChop_enabled = false;
- #endif
- #if ENABLED(HYBRID_THRESHOLD)
- uint8_t hybrid_thrs = 0;
- #endif
- #if USE_SENSORLESS
- int16_t homing_thrs = 0;
- #endif
+ TERN_(HAS_STEALTHCHOP, bool stealthChop_enabled = false);
+ TERN_(HYBRID_THRESHOLD, uint8_t hybrid_thrs = 0);
+ TERN_(USE_SENSORLESS, int16_t homing_thrs = 0);
} stored;
};
@@ -105,6 +100,7 @@ class TMCMarlin : public TMC, public TMCStorage {
this->val_mA = mA;
TMC::rms_current(mA, mult);
}
+ inline uint16_t get_microstep_counter() { return TMC::MSCNT(); }
#if HAS_STEALTHCHOP
inline void refresh_stepping_mode() { this->en_pwm_mode(this->stored.stealthChop_enabled); }
@@ -117,9 +113,7 @@ class TMCMarlin : public TMC, public TMCStorage {
}
void set_pwm_thrs(const uint32_t thrs) {
TMC::TPWMTHRS(_tmc_thrs(this->microsteps(), thrs, planner.settings.axis_steps_per_mm[AXIS_ID]));
- #if HAS_LCD_MENU
- this->stored.hybrid_thrs = thrs;
- #endif
+ TERN_(HAS_LCD_MENU, this->stored.hybrid_thrs = thrs);
}
#endif
@@ -128,9 +122,7 @@ class TMCMarlin : public TMC, public TMCStorage {
void homing_threshold(int16_t sgt_val) {
sgt_val = (int16_t)constrain(sgt_val, sgt_min, sgt_max);
TMC::sgt(sgt_val);
- #if HAS_LCD_MENU
- this->stored.homing_thrs = sgt_val;
- #endif
+ TERN_(HAS_LCD_MENU, this->stored.homing_thrs = sgt_val);
}
#if ENABLED(SPI_ENDSTOPS)
bool test_stall_status();
@@ -158,9 +150,13 @@ class TMCMarlin : public TMC220
TMCMarlin(Stream * SerialPort, const float RS, const uint8_t) :
TMC2208Stepper(SerialPort, RS)
{}
- TMCMarlin(const uint16_t RX, const uint16_t TX, const float RS, const uint8_t, const bool has_rx=true) :
- TMC2208Stepper(RX, TX, RS, has_rx)
+ TMCMarlin(Stream * SerialPort, const float RS, uint8_t addr, const uint16_t mul_pin1, const uint16_t mul_pin2) :
+ TMC2208Stepper(SerialPort, RS, addr, mul_pin1, mul_pin2)
+ {}
+ TMCMarlin(const uint16_t RX, const uint16_t TX, const float RS, const uint8_t) :
+ TMC2208Stepper(RX, TX, RS)
{}
+
uint16_t rms_current() { return TMC2208Stepper::rms_current(); }
inline void rms_current(const uint16_t mA) {
this->val_mA = mA;
@@ -170,6 +166,7 @@ class TMCMarlin : public TMC220
this->val_mA = mA;
TMC2208Stepper::rms_current(mA, mult);
}
+ inline uint16_t get_microstep_counter() { return TMC2208Stepper::MSCNT(); }
#if HAS_STEALTHCHOP
inline void refresh_stepping_mode() { en_spreadCycle(!this->stored.stealthChop_enabled); }
@@ -182,9 +179,7 @@ class TMCMarlin : public TMC220
}
void set_pwm_thrs(const uint32_t thrs) {
TMC2208Stepper::TPWMTHRS(_tmc_thrs(this->microsteps(), thrs, planner.settings.axis_steps_per_mm[AXIS_ID]));
- #if HAS_LCD_MENU
- this->stored.hybrid_thrs = thrs;
- #endif
+ TERN_(HAS_LCD_MENU, this->stored.hybrid_thrs = thrs);
}
#endif
@@ -203,7 +198,7 @@ class TMCMarlin : public TMC220
TMCMarlin(Stream * SerialPort, const float RS, const uint8_t addr) :
TMC2209Stepper(SerialPort, RS, addr)
{}
- TMCMarlin(const uint16_t RX, const uint16_t TX, const float RS, const uint8_t addr, const bool) :
+ TMCMarlin(const uint16_t RX, const uint16_t TX, const float RS, const uint8_t addr) :
TMC2209Stepper(RX, TX, RS, addr)
{}
uint8_t get_address() { return slave_address; }
@@ -216,6 +211,7 @@ class TMCMarlin : public TMC220
this->val_mA = mA;
TMC2209Stepper::rms_current(mA, mult);
}
+ inline uint16_t get_microstep_counter() { return TMC2209Stepper::MSCNT(); }
#if HAS_STEALTHCHOP
inline void refresh_stepping_mode() { en_spreadCycle(!this->stored.stealthChop_enabled); }
@@ -228,9 +224,7 @@ class TMCMarlin : public TMC220
}
void set_pwm_thrs(const uint32_t thrs) {
TMC2209Stepper::TPWMTHRS(_tmc_thrs(this->microsteps(), thrs, planner.settings.axis_steps_per_mm[AXIS_ID]));
- #if HAS_LCD_MENU
- this->stored.hybrid_thrs = thrs;
- #endif
+ TERN_(HAS_LCD_MENU, this->stored.hybrid_thrs = thrs);
}
#endif
#if USE_SENSORLESS
@@ -238,9 +232,7 @@ class TMCMarlin : public TMC220
void homing_threshold(int16_t sgt_val) {
sgt_val = (int16_t)constrain(sgt_val, sgt_min, sgt_max);
TMC2209Stepper::SGTHRS(sgt_val);
- #if HAS_LCD_MENU
- this->stored.homing_thrs = sgt_val;
- #endif
+ TERN_(HAS_LCD_MENU, this->stored.homing_thrs = sgt_val);
}
#endif
@@ -273,15 +265,14 @@ class TMCMarlin : public TMC266
this->val_mA = mA;
TMC2660Stepper::rms_current(mA);
}
+ inline uint16_t get_microstep_counter() { return TMC2660Stepper::mstep(); }
#if USE_SENSORLESS
inline int16_t homing_threshold() { return TMC2660Stepper::sgt(); }
void homing_threshold(int16_t sgt_val) {
sgt_val = (int16_t)constrain(sgt_val, sgt_min, sgt_max);
TMC2660Stepper::sgt(sgt_val);
- #if HAS_LCD_MENU
- this->stored.homing_thrs = sgt_val;
- #endif
+ TERN_(HAS_LCD_MENU, this->stored.homing_thrs = sgt_val);
}
#endif
@@ -363,9 +354,7 @@ void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z
struct slow_homing_t {
xy_ulong_t acceleration;
- #if HAS_CLASSIC_JERK
- xy_float_t jerk_xy;
- #endif
+ TERN_(HAS_CLASSIC_JERK, xy_float_t jerk_xy);
};
#endif
diff --git a/Marlin/src/feature/touch/xpt2046.cpp b/Marlin/src/feature/touch/xpt2046.cpp
index 26e25950d..235c17b50 100644
--- a/Marlin/src/feature/touch/xpt2046.cpp
+++ b/Marlin/src/feature/touch/xpt2046.cpp
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -23,6 +23,49 @@
#include "xpt2046.h"
#include "../../inc/MarlinConfig.h"
+#if ENABLED(FSMC_GRAPHICAL_TFT)
+ #include "../../lcd/dogm/ultralcd_DOGM.h" // for LCD_FULL_PIXEL_WIDTH, etc.
+#endif
+
+
+/*
+ * Draw and Touch processing
+ *
+ * LCD_PIXEL_WIDTH/HEIGHT (128x64) is the (emulated DOGM) Pixel Drawing resolution.
+ * TOUCH_SCREEN_WIDTH/HEIGHT (320x240) is the Touch Area resolution.
+ * LCD_FULL_PIXEL_WIDTH/HEIGHT (320x240 or 480x320) is the Actual (FSMC) Display resolution.
+ *
+ * - All native (u8g) drawing is done in LCD_PIXEL_* (128x64)
+ * - The DOGM pixels are is upscaled 2-3x (as needed) for display.
+ * - Touch coordinates use TOUCH_SCREEN_* resolution and are converted to
+ * click and scroll-wheel events (emulating of a common DOGM display).
+ *
+ * TOUCH_SCREEN resolution exists to fit our calibration values. The original touch code was made
+ * and originally calibrated for 320x240. If you decide to change the resolution of the touch code,
+ * new calibration values will be needed.
+ *
+ * The Marlin menus are drawn scaled in the upper region of the screen. The bottom region (in a
+ * fixed location in TOUCH_SCREEN* coordinate space) is used for 4 general-purpose buttons to
+ * navigate and select menu items. Both regions are touchable.
+ *
+ * The Marlin screen touchable area starts at LCD_PIXEL_OFFSET_X/Y (translated to SCREEN_START_LEFT/TOP)
+ * and spans LCD_PIXEL_WIDTH/HEIGHT (scaled to SCREEN_WIDTH/HEIGHT).
+ */
+// Touch screen resolution independent of display resolution
+#define TOUCH_SCREEN_HEIGHT 240
+#define TOUCH_SCREEN_WIDTH 320
+
+// Coordinates in terms of touch area
+#define BUTTON_AREA_TOP 175
+#define BUTTON_AREA_BOT 234
+
+#define SCREEN_START_TOP ((LCD_PIXEL_OFFSET_Y) * (TOUCH_SCREEN_HEIGHT) / (LCD_FULL_PIXEL_HEIGHT))
+#define SCREEN_START_LEFT ((LCD_PIXEL_OFFSET_X) * (TOUCH_SCREEN_WIDTH) / (LCD_FULL_PIXEL_WIDTH))
+#define SCREEN_HEIGHT ((LCD_PIXEL_HEIGHT * FSMC_UPSCALE) * (TOUCH_SCREEN_HEIGHT) / (LCD_FULL_PIXEL_HEIGHT))
+#define SCREEN_WIDTH ((LCD_PIXEL_WIDTH * FSMC_UPSCALE) * (TOUCH_SCREEN_WIDTH) / (LCD_FULL_PIXEL_WIDTH))
+
+#define TOUCHABLE_Y_HEIGHT SCREEN_HEIGHT
+#define TOUCHABLE_X_WIDTH SCREEN_WIDTH
#ifndef TOUCH_INT_PIN
#define TOUCH_INT_PIN -1
@@ -41,7 +84,6 @@
#endif
XPT2046 touch;
-extern int8_t encoderDiff;
void XPT2046::init() {
SET_INPUT(TOUCH_MISO_PIN);
@@ -61,30 +103,42 @@ void XPT2046::init() {
#include "../../lcd/ultralcd.h" // For EN_C bit mask
uint8_t XPT2046::read_buttons() {
- int16_t tsoffsets[4] = { 0 };
+ #ifdef HAS_SPI_LCD
+ int16_t tsoffsets[4] = { 0 };
- if (tsoffsets[0] + tsoffsets[1] == 0) {
- // Not yet set, so use defines as fallback...
- tsoffsets[0] = XPT2046_X_CALIBRATION;
- tsoffsets[1] = XPT2046_X_OFFSET;
- tsoffsets[2] = XPT2046_Y_CALIBRATION;
- tsoffsets[3] = XPT2046_Y_OFFSET;
- }
+ if (tsoffsets[0] + tsoffsets[1] == 0) {
+ // Not yet set, so use defines as fallback...
+ tsoffsets[0] = XPT2046_X_CALIBRATION;
+ tsoffsets[1] = XPT2046_X_OFFSET;
+ tsoffsets[2] = XPT2046_Y_CALIBRATION;
+ tsoffsets[3] = XPT2046_Y_OFFSET;
+ }
- // We rely on XPT2046 compatible mode to ADS7843, hence no Z1 and Z2 measurements possible.
+ // We rely on XPT2046 compatible mode to ADS7843, hence no Z1 and Z2 measurements possible.
- if (!isTouched()) return 0;
- const uint16_t x = uint16_t(((uint32_t(getInTouch(XPT2046_X))) * tsoffsets[0]) >> 16) + tsoffsets[1],
- y = uint16_t(((uint32_t(getInTouch(XPT2046_Y))) * tsoffsets[2]) >> 16) + tsoffsets[3];
- if (!isTouched()) return 0; // Fingers must still be on the TS for a valid read.
+ if (!isTouched()) return 0;
+ const uint16_t x = uint16_t(((uint32_t(getInTouch(XPT2046_X))) * tsoffsets[0]) >> 16) + tsoffsets[1],
+ y = uint16_t(((uint32_t(getInTouch(XPT2046_Y))) * tsoffsets[2]) >> 16) + tsoffsets[3];
+ if (!isTouched()) return 0; // Fingers must still be on the TS for a valid read.
- if (y < 175 || y > 234) return 0;
+ // Touch within the button area simulates an encoder button
+ if (y > BUTTON_AREA_TOP && y < BUTTON_AREA_BOT)
+ return WITHIN(x, 14, 77) ? EN_D
+ : WITHIN(x, 90, 153) ? EN_A
+ : WITHIN(x, 166, 229) ? EN_B
+ : WITHIN(x, 242, 305) ? EN_C
+ : 0;
- return WITHIN(x, 14, 77) ? EN_D
- : WITHIN(x, 90, 153) ? EN_A
- : WITHIN(x, 166, 229) ? EN_B
- : WITHIN(x, 242, 305) ? EN_C
- : 0;
+ if (x > TOUCH_SCREEN_WIDTH || !WITHIN(y, SCREEN_START_TOP, SCREEN_START_TOP + SCREEN_HEIGHT)) return 0;
+
+ // Column and row above BUTTON_AREA_TOP
+ int8_t col = (x - (SCREEN_START_LEFT)) * (LCD_WIDTH) / (TOUCHABLE_X_WIDTH),
+ row = (y - (SCREEN_START_TOP)) * (LCD_HEIGHT) / (TOUCHABLE_Y_HEIGHT);
+
+ // Send the touch to the UI (which will simulate the encoder wheel)
+ MarlinUI::screen_click(row, col, x, y);
+ #endif
+ return 0;
}
bool XPT2046::isTouched() {
diff --git a/Marlin/src/feature/touch/xpt2046.h b/Marlin/src/feature/touch/xpt2046.h
index 7f8eece1f..347881e0a 100644
--- a/Marlin/src/feature/touch/xpt2046.h
+++ b/Marlin/src/feature/touch/xpt2046.h
@@ -13,7 +13,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/feature/twibus.cpp b/Marlin/src/feature/twibus.cpp
index 9dbb1deb4..3cc20579a 100644
--- a/Marlin/src/feature/twibus.cpp
+++ b/Marlin/src/feature/twibus.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -104,8 +104,8 @@ bool TWIBus::request(const uint8_t bytes) {
debug(PSTR("request"), bytes);
// requestFrom() is a blocking function
- if (Wire.requestFrom(addr, bytes) == 0) {
- debug("request fail", addr);
+ if (Wire.requestFrom(I2C_ADDRESS(addr), bytes) == 0) {
+ debug("request fail", I2C_ADDRESS(addr));
return false;
}
diff --git a/Marlin/src/feature/twibus.h b/Marlin/src/feature/twibus.h
index 2c1b20da5..8bc8eb4e7 100644
--- a/Marlin/src/feature/twibus.h
+++ b/Marlin/src/feature/twibus.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -46,8 +46,8 @@ typedef void (*twiRequestFunc_t)();
* for the host to interpret.
*
* For more information see
- * - http://marlinfw.org/docs/gcode/M260.html
- * - http://marlinfw.org/docs/gcode/M261.html
+ * - https://marlinfw.org/docs/gcode/M260.html
+ * - https://marlinfw.org/docs/gcode/M261.html
*
*/
class TWIBus {
diff --git a/Marlin/src/feature/z_stepper_align.cpp b/Marlin/src/feature/z_stepper_align.cpp
index 6fccff7cc..87b1f6f25 100644
--- a/Marlin/src/feature/z_stepper_align.cpp
+++ b/Marlin/src/feature/z_stepper_align.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -56,10 +56,10 @@ void ZStepperAlign::reset_to_default() {
constexpr xyz_pos_t dpo = NOZZLE_TO_PROBE_OFFSET;
- #define LTEST(N) (xy_init[N].x >= _MAX(X_MIN_BED + MIN_PROBE_EDGE_LEFT, X_MIN_POS + dpo.x) - 0.00001f)
- #define RTEST(N) (xy_init[N].x <= _MIN(X_MAX_BED - MIN_PROBE_EDGE_RIGHT, X_MAX_POS + dpo.x) + 0.00001f)
- #define FTEST(N) (xy_init[N].y >= _MAX(Y_MIN_BED + MIN_PROBE_EDGE_FRONT, Y_MIN_POS + dpo.y) - 0.00001f)
- #define BTEST(N) (xy_init[N].y <= _MIN(Y_MAX_BED - MIN_PROBE_EDGE_BACK, Y_MAX_POS + dpo.y) + 0.00001f)
+ #define LTEST(N) (xy_init[N].x >= _MAX(X_MIN_BED + PROBING_MARGIN_LEFT, X_MIN_POS + dpo.x) - 0.00001f)
+ #define RTEST(N) (xy_init[N].x <= _MIN(X_MAX_BED - PROBING_MARGIN_RIGHT, X_MAX_POS + dpo.x) + 0.00001f)
+ #define FTEST(N) (xy_init[N].y >= _MAX(Y_MIN_BED + PROBING_MARGIN_FRONT, Y_MIN_POS + dpo.y) - 0.00001f)
+ #define BTEST(N) (xy_init[N].y <= _MIN(Y_MAX_BED - PROBING_MARGIN_BACK, Y_MAX_POS + dpo.y) + 0.00001f)
static_assert(LTEST(0) && RTEST(0), "The 1st Z_STEPPER_ALIGN_XY X is unreachable with the default probe X offset.");
static_assert(FTEST(0) && BTEST(0), "The 1st Z_STEPPER_ALIGN_XY Y is unreachable with the default probe Y offset.");
diff --git a/Marlin/src/feature/z_stepper_align.h b/Marlin/src/feature/z_stepper_align.h
index ade3d6b57..e1b235b52 100644
--- a/Marlin/src/feature/z_stepper_align.h
+++ b/Marlin/src/feature/z_stepper_align.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp
index 28fdf581f..438a61924 100644
--- a/Marlin/src/gcode/bedlevel/G26.cpp
+++ b/Marlin/src/gcode/bedlevel/G26.cpp
@@ -16,58 +16,10 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
-/**
- * Marlin Firmware -- G26 - Mesh Validation Tool
- */
-
-#include "../../inc/MarlinConfig.h"
-
-#if ENABLED(G26_MESH_VALIDATION)
-
-#define G26_OK false
-#define G26_ERR true
-
-#include "../../gcode/gcode.h"
-#include "../../feature/bedlevel/bedlevel.h"
-
-#include "../../MarlinCore.h"
-#include "../../module/planner.h"
-#include "../../module/stepper.h"
-#include "../../module/motion.h"
-#include "../../module/tool_change.h"
-#include "../../module/temperature.h"
-#include "../../lcd/ultralcd.h"
-
-#define EXTRUSION_MULTIPLIER 1.0
-#define PRIME_LENGTH 10.0
-#define OOZE_AMOUNT 0.3
-
-#define INTERSECTION_CIRCLE_RADIUS 5
-#define CROSSHAIRS_SIZE 3
-
-#ifndef G26_RETRACT_MULTIPLIER
- #define G26_RETRACT_MULTIPLIER 1.0 // x 1mm
-#endif
-
-#ifndef G26_XY_FEEDRATE
- #define G26_XY_FEEDRATE (PLANNER_XY_FEEDRATE() / 3.0)
-#endif
-
-#if CROSSHAIRS_SIZE >= INTERSECTION_CIRCLE_RADIUS
- #error "CROSSHAIRS_SIZE must be less than INTERSECTION_CIRCLE_RADIUS."
-#endif
-
-#define G26_OK false
-#define G26_ERR true
-
-#if ENABLED(ARC_SUPPORT)
- void plan_arc(const xyze_pos_t &cart, const ab_float_t &offset, const uint8_t clockwise);
-#endif
-
/**
* G26 Mesh Validation Tool
*
@@ -95,6 +47,8 @@
*
* H # Hotend Set the Nozzle Temperature. If not specified, a default of 205 C. will be assumed.
*
+ * I # Preset Heat the Nozzle and Bed based on a Material Preset (if material presets are defined).
+ *
* F # Filament Used to specify the diameter of the filament being used. If not specified
* 1.75mm filament is assumed. If you are not getting acceptable results by using the
* 'correct' numbers, you can scale this number up or down a little bit to change the amount
@@ -141,13 +95,54 @@
* Y # Y Coord. Specify the starting location of the drawing activity.
*/
-// External references
+#include "../../inc/MarlinConfig.h"
-// Private functions
+#if ENABLED(G26_MESH_VALIDATION)
+
+#define G26_OK false
+#define G26_ERR true
+
+#include "../../gcode/gcode.h"
+#include "../../feature/bedlevel/bedlevel.h"
+
+#include "../../MarlinCore.h"
+#include "../../module/planner.h"
+#include "../../module/stepper.h"
+#include "../../module/motion.h"
+#include "../../module/tool_change.h"
+#include "../../module/temperature.h"
+#include "../../lcd/ultralcd.h"
+
+#define EXTRUSION_MULTIPLIER 1.0
+#define PRIME_LENGTH 10.0
+#define OOZE_AMOUNT 0.3
+
+#define INTERSECTION_CIRCLE_RADIUS 5
+#define CROSSHAIRS_SIZE 3
+
+#ifndef G26_RETRACT_MULTIPLIER
+ #define G26_RETRACT_MULTIPLIER 1.0 // x 1mm
+#endif
+
+#ifndef G26_XY_FEEDRATE
+ #define G26_XY_FEEDRATE (PLANNER_XY_FEEDRATE() / 3.0)
+#endif
+
+#if CROSSHAIRS_SIZE >= INTERSECTION_CIRCLE_RADIUS
+ #error "CROSSHAIRS_SIZE must be less than INTERSECTION_CIRCLE_RADIUS."
+#endif
+
+#define G26_OK false
+#define G26_ERR true
+
+#if ENABLED(ARC_SUPPORT)
+ void plan_arc(const xyze_pos_t &cart, const ab_float_t &offset, const uint8_t clockwise);
+#endif
+
+constexpr float g26_e_axis_feedrate = 0.025;
static MeshFlags circle_flags, horizontal_mesh_line_flags, vertical_mesh_line_flags;
-float g26_e_axis_feedrate = 0.025,
- random_deviation = 0.0;
+float g26_random_deviation = 0.0;
static bool g26_retracted = false; // Track the retracted state of the nozzle so mismatched
// retracts/recovers won't result in a bad state.
@@ -172,9 +167,7 @@ int8_t g26_prime_flag;
bool user_canceled() {
if (!ui.button_pressed()) return false; // Return if the button isn't pressed
ui.set_status_P(GET_TEXT(MSG_G26_CANCELED), 99);
- #if HAS_LCD_MENU
- ui.quick_feedback();
- #endif
+ TERN_(HAS_LCD_MENU, ui.quick_feedback());
ui.wait_for_release();
return true;
}
@@ -202,7 +195,7 @@ mesh_index_pair find_closest_circle_to_print(const xy_pos_t &pos) {
f += (g26_xy_pos - m).magnitude() / 15.0f;
// Add the specified amount of Random Noise to our search
- if (random_deviation > 1.0) f += random(0.0, random_deviation);
+ if (g26_random_deviation > 1.0) f += random(0.0, g26_random_deviation);
if (f < closest) {
closest = f; // Found a closer un-printed location
@@ -308,9 +301,7 @@ inline bool look_for_lines_to_connect() {
GRID_LOOP(i, j) {
- #if HAS_LCD_MENU
- if (user_canceled()) return true;
- #endif
+ if (TERN0(HAS_LCD_MENU, user_canceled())) return true;
if (i < (GRID_MAX_POINTS_X)) { // Can't connect to anything farther to the right than GRID_MAX_POINTS_X.
// Already a half circle at the edge of the bed.
@@ -371,9 +362,7 @@ inline bool turn_on_heaters() {
#if HAS_SPI_LCD
ui.set_status_P(GET_TEXT(MSG_G26_HEATING_BED), 99);
ui.quick_feedback();
- #if HAS_LCD_MENU
- ui.capture();
- #endif
+ TERN_(HAS_LCD_MENU, ui.capture());
#endif
thermalManager.setTargetBed(g26_bed_temp);
@@ -397,11 +386,10 @@ inline bool turn_on_heaters() {
// Wait for the temperature to stabilize
if (!thermalManager.wait_for_hotend(active_extruder, true
- #if G26_CLICK_CAN_CANCEL
- , true
- #endif
- )
- ) return G26_ERR;
+ #if G26_CLICK_CAN_CANCEL
+ , true
+ #endif
+ )) return G26_ERR;
#if HAS_SPI_LCD
ui.reset_status();
@@ -522,15 +510,35 @@ void GcodeSuite::G26() {
bool g26_continue_with_closest = parser.boolval('C'),
g26_keep_heaters_on = parser.boolval('K');
+ // Accept 'I' if temperature presets are defined
+ const uint8_t preset_index = (0
+ #if PREHEAT_COUNT
+ + (parser.seenval('I') ? _MIN(parser.value_byte(), PREHEAT_COUNT - 1) + 1 : 0)
+ #endif
+ );
+
#if HAS_HEATED_BED
- if (parser.seenval('B')) {
- g26_bed_temp = parser.value_celsius();
- if (g26_bed_temp && !WITHIN(g26_bed_temp, 40, (BED_MAXTEMP - 10))) {
- SERIAL_ECHOLNPAIR("?Specified bed temperature not plausible (40-", int(BED_MAXTEMP - 10), "C).");
+
+ // Get a temperature from 'I' or 'B'
+ int16_t bedtemp = 0;
+
+ // Use the 'I' index if temperature presets are defined
+ #if PREHEAT_COUNT
+ if (preset_index) bedtemp = ui.material_preset[preset_index - 1].bed_temp;
+ #endif
+
+ // Look for 'B' Bed Temperature
+ if (parser.seenval('B')) bedtemp = parser.value_celsius();
+
+ if (bedtemp) {
+ if (!WITHIN(bedtemp, 40, BED_MAX_TARGET)) {
+ SERIAL_ECHOLNPAIR("?Specified bed temperature not plausible (40-", int(BED_MAX_TARGET), "C).");
return;
}
+ g26_bed_temp = bedtemp;
}
- #endif
+
+ #endif // HAS_HEATED_BED
if (parser.seenval('L')) {
g26_layer_height = parser.value_linear_units();
@@ -594,20 +602,34 @@ void GcodeSuite::G26() {
g26_extrusion_multiplier *= g26_filament_diameter * sq(g26_nozzle) / sq(0.3); // Scale up by nozzle size
- if (parser.seenval('H')) {
- g26_hotend_temp = parser.value_celsius();
- if (!WITHIN(g26_hotend_temp, 165, (HEATER_0_MAXTEMP - 15))) {
+ // Get a temperature from 'I' or 'H'
+ int16_t noztemp = 0;
+
+ // Accept 'I' if temperature presets are defined
+ #if PREHEAT_COUNT
+ if (preset_index) noztemp = ui.material_preset[preset_index - 1].hotend_temp;
+ #endif
+
+ // Look for 'H' Hotend Temperature
+ if (parser.seenval('H')) noztemp = parser.value_celsius();
+
+ // If any preset or temperature was specified
+ if (noztemp) {
+ if (!WITHIN(noztemp, 165, (HEATER_0_MAXTEMP) - (HOTEND_OVERSHOOT))) {
SERIAL_ECHOLNPGM("?Specified nozzle temperature not plausible.");
return;
}
+ g26_hotend_temp = noztemp;
}
+ // 'U' to Randomize and optionally set circle deviation
if (parser.seen('U')) {
randomSeed(millis());
// This setting will persist for the next G26
- random_deviation = parser.has_value() ? parser.value_float() : 50.0;
+ g26_random_deviation = parser.has_value() ? parser.value_float() : 50.0;
}
+ // Get repeat from 'R', otherwise do one full circuit
int16_t g26_repeats;
#if HAS_LCD_MENU
g26_repeats = parser.intval('R', GRID_MAX_POINTS + 1);
@@ -624,6 +646,7 @@ void GcodeSuite::G26() {
return;
}
+ // Set a position with 'X' and/or 'Y'. Default: current_position
g26_xy_pos.set(parser.seenval('X') ? RAW_X_POSITION(parser.value_linear_units()) : current_position.x,
parser.seenval('Y') ? RAW_Y_POSITION(parser.value_linear_units()) : current_position.y);
if (!position_is_reachable(g26_xy_pos)) {
@@ -636,8 +659,7 @@ void GcodeSuite::G26() {
*/
set_bed_leveling_enabled(!parser.seen('D'));
- if (current_position.z < Z_CLEARANCE_BETWEEN_PROBES)
- do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES);
+ do_z_clearance(Z_CLEARANCE_BETWEEN_PROBES);
#if DISABLED(NO_VOLUMETRICS)
bool volumetric_was_enabled = parser.volumetric_enabled;
@@ -672,9 +694,7 @@ void GcodeSuite::G26() {
move_to(destination, 0.0);
move_to(destination, g26_ooze_amount);
- #if HAS_LCD_MENU
- ui.capture();
- #endif
+ TERN_(HAS_LCD_MENU, ui.capture());
#if DISABLED(ARC_SUPPORT)
@@ -769,9 +789,7 @@ void GcodeSuite::G26() {
feedrate_mm_s = old_feedrate;
destination = current_position;
- #if HAS_LCD_MENU
- if (user_canceled()) goto LEAVE; // Check if the user wants to stop the Mesh Validation
- #endif
+ if (TERN0(HAS_LCD_MENU, user_canceled())) goto LEAVE; // Check if the user wants to stop the Mesh Validation
#else // !ARC_SUPPORT
@@ -795,9 +813,7 @@ void GcodeSuite::G26() {
for (int8_t ind = start_ind; ind <= end_ind; ind++) {
- #if HAS_LCD_MENU
- if (user_canceled()) goto LEAVE; // Check if the user wants to stop the Mesh Validation
- #endif
+ if (TERN0(HAS_LCD_MENU, user_canceled())) goto LEAVE; // Check if the user wants to stop the Mesh Validation
xyz_float_t p = { circle.x + _COS(ind ), circle.y + _SIN(ind ), g26_layer_height },
q = { circle.x + _COS(ind + 1), circle.y + _SIN(ind + 1), g26_layer_height };
@@ -840,14 +856,10 @@ void GcodeSuite::G26() {
planner.calculate_volumetric_multipliers();
#endif
- #if HAS_LCD_MENU
- ui.release(); // Give back control of the LCD
- #endif
+ TERN_(HAS_LCD_MENU, ui.release()); // Give back control of the LCD
if (!g26_keep_heaters_on) {
- #if HAS_HEATED_BED
- thermalManager.setTargetBed(0);
- #endif
+ TERN_(HAS_HEATED_BED, thermalManager.setTargetBed(0));
thermalManager.setTargetHotend(active_extruder, 0);
}
}
diff --git a/Marlin/src/gcode/bedlevel/G35.cpp b/Marlin/src/gcode/bedlevel/G35.cpp
new file mode 100755
index 000000000..786065b34
--- /dev/null
+++ b/Marlin/src/gcode/bedlevel/G35.cpp
@@ -0,0 +1,185 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(ASSISTED_TRAMMING)
+
+#include "../gcode.h"
+#include "../../module/planner.h"
+#include "../../module/probe.h"
+#include "../../feature/bedlevel/bedlevel.h"
+
+#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE)
+#include "../../core/debug_out.h"
+
+constexpr xy_pos_t screws_tilt_adjust_pos[] = TRAMMING_POINT_XY;
+
+static PGMSTR(point_name_1, TRAMMING_POINT_NAME_1);
+static PGMSTR(point_name_2, TRAMMING_POINT_NAME_2);
+static PGMSTR(point_name_3, TRAMMING_POINT_NAME_3);
+#ifdef TRAMMING_POINT_NAME_4
+ static PGMSTR(point_name_4, TRAMMING_POINT_NAME_4);
+ #ifdef TRAMMING_POINT_NAME_5
+ static PGMSTR(point_name_5, TRAMMING_POINT_NAME_5);
+ #endif
+#endif
+
+static PGM_P const tramming_point_name[] PROGMEM = {
+ point_name_1, point_name_2, point_name_3
+ #ifdef TRAMMING_POINT_NAME_4
+ , point_name_4
+ #ifdef TRAMMING_POINT_NAME_5
+ , point_name_5
+ #endif
+ #endif
+};
+
+#define G35_PROBE_COUNT COUNT(screws_tilt_adjust_pos)
+
+#if !WITHIN(TRAMMING_SCREW_THREAD, 30, 51) || TRAMMING_SCREW_THREAD % 10 > 1
+ #error "TRAMMING_SCREW_THREAD must be equal to 30, 31, 40, 41, 50, or 51."
+#endif
+
+static_assert(G35_PROBE_COUNT > 2, "TRAMMING_POINT_XY requires at least 3 XY positions.");
+
+/**
+ * G35: Read bed corners to help adjust bed screws
+ *
+ * S
+ *
+ * Screw thread: 30 - Clockwise M3
+ * 31 - Counter-Clockwise M3
+ * 40 - Clockwise M4
+ * 41 - Counter-Clockwise M4
+ * 50 - Clockwise M5
+ * 51 - Counter-Clockwise M5
+ **/
+void GcodeSuite::G35() {
+ DEBUG_SECTION(log_G35, "G35", DEBUGGING(LEVELING));
+
+ if (DEBUGGING(LEVELING)) log_machine_info();
+
+ float z_measured[G35_PROBE_COUNT] = { 0 };
+
+ const uint8_t screw_thread = parser.byteval('S', TRAMMING_SCREW_THREAD);
+ if (!WITHIN(screw_thread, 30, 51) || screw_thread % 10 > 1) {
+ SERIAL_ECHOLNPGM("?(S)crew thread must be 30, 31, 40, 41, 50, or 51.");
+ return;
+ }
+
+ // Wait for planner moves to finish!
+ planner.synchronize();
+
+ // Disable the leveling matrix before auto-aligning
+ #if HAS_LEVELING
+ TERN_(RESTORE_LEVELING_AFTER_G35, const bool leveling_was_active = planner.leveling_active);
+ set_bed_leveling_enabled(false);
+ #endif
+
+ #if ENABLED(CNC_WORKSPACE_PLANES)
+ workspace_plane = PLANE_XY;
+ #endif
+
+ // Always home with tool 0 active
+ #if HAS_MULTI_HOTEND
+ const uint8_t old_tool_index = active_extruder;
+ tool_change(0, true);
+ #endif
+
+ #if HAS_DUPLICATION_MODE
+ extruder_duplication_enabled = false;
+ #endif
+
+ // Home all before this procedure
+ home_all_axes();
+
+ bool err_break = false;
+
+ // Probe all positions
+ LOOP_L_N(i, G35_PROBE_COUNT) {
+
+ // In BLTOUCH HS mode, the probe travels in a deployed state.
+ // Users of G35 might have a badly misaligned bed, so raise Z by the
+ // length of the deployed pin (BLTOUCH stroke < 7mm)
+ current_position.z = (Z_CLEARANCE_BETWEEN_PROBES) + (7 * ENABLED(BLTOUCH_HS_MODE));
+
+ const float z_probed_height = probe.probe_at_point(screws_tilt_adjust_pos[i], PROBE_PT_RAISE, 0, true);
+
+ if (isnan(z_probed_height)) {
+ SERIAL_ECHOPAIR("G35 failed at point ", int(i), " (", tramming_point_name[i], ")");
+ SERIAL_ECHOLNPAIR_P(SP_X_STR, screws_tilt_adjust_pos[i].x, SP_Y_STR, screws_tilt_adjust_pos[i].y);
+ err_break = true;
+ break;
+ }
+
+ if (DEBUGGING(LEVELING)) {
+ DEBUG_ECHOPAIR("Probing point ", int(i), " (", tramming_point_name[i], ")");
+ SERIAL_ECHOLNPAIR_P(SP_X_STR, screws_tilt_adjust_pos[i].x, SP_Y_STR, screws_tilt_adjust_pos[i].y, SP_Z_STR, z_probed_height);
+ }
+
+ z_measured[i] = z_probed_height;
+ }
+
+ if (!err_break) {
+ const float threads_factor[] = { 0.5, 0.7, 0.8 };
+
+ // Calculate adjusts
+ LOOP_S_L_N(i, 1, G35_PROBE_COUNT) {
+ const float diff = z_measured[0] - z_measured[i],
+ adjust = abs(diff) < 0.001f ? 0 : diff / threads_factor[(screw_thread - 30) / 10];
+
+ const int full_turns = trunc(adjust);
+ const float decimal_part = adjust - float(full_turns);
+ const int minutes = trunc(decimal_part * 60.0f);
+
+ SERIAL_ECHOPAIR("Turn ", tramming_point_name[i],
+ " ", (screw_thread & 1) == (adjust > 0) ? "Counter-Clockwise" : "Clockwise",
+ " by ", abs(full_turns), " turns");
+ if (minutes) SERIAL_ECHOPAIR(" and ", abs(minutes), " minutes");
+ SERIAL_EOL();
+ }
+ }
+ else
+ SERIAL_ECHOLNPGM("G35 aborted.");
+
+ // Restore the active tool after homing
+ #if HAS_MULTI_HOTEND
+ tool_change(old_tool_index, DISABLED(PARKING_EXTRUDER)); // Fetch previous toolhead if not PARKING_EXTRUDER
+ #endif
+
+ #if BOTH(HAS_LEVELING, RESTORE_LEVELING_AFTER_G35)
+ set_bed_leveling_enabled(leveling_was_active);
+ #endif
+
+ // Stow the probe, as the last call to probe.probe_at_point(...) left
+ // the probe deployed if it was successful.
+ probe.stow();
+
+ // After this operation the Z position needs correction
+ set_axis_not_trusted(Z_AXIS);
+
+ // Home Z after the alignment procedure
+ process_subcommands_now_P(PSTR("G28Z"));
+}
+
+#endif // ASSISTED_TRAMMING
diff --git a/Marlin/src/gcode/bedlevel/G42.cpp b/Marlin/src/gcode/bedlevel/G42.cpp
index 139bd1bb6..a2896ed6c 100644
--- a/Marlin/src/gcode/bedlevel/G42.cpp
+++ b/Marlin/src/gcode/bedlevel/G42.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/bedlevel/M420.cpp b/Marlin/src/gcode/bedlevel/M420.cpp
index d042ace8d..d51543417 100644
--- a/Marlin/src/gcode/bedlevel/M420.cpp
+++ b/Marlin/src/gcode/bedlevel/M420.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -73,9 +73,7 @@ void GcodeSuite::M420() {
#endif
GRID_LOOP(x, y) {
Z_VALUES(x, y) = 0.001 * random(-200, 200);
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(x, y, Z_VALUES(x, y));
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, Z_VALUES(x, y)));
}
SERIAL_ECHOPGM("Simulated " STRINGIFY(GRID_MAX_POINTS_X) "x" STRINGIFY(GRID_MAX_POINTS_Y) " mesh ");
SERIAL_ECHOPAIR(" (", x_min);
@@ -86,12 +84,12 @@ void GcodeSuite::M420() {
}
#endif
+ xyz_pos_t oldpos = current_position;
+
// If disabling leveling do it right away
// (Don't disable for just M420 or M420 V)
if (seen_S && !to_enable) set_bed_leveling_enabled(false);
- xyz_pos_t oldpos = current_position;
-
#if ENABLED(AUTO_BED_LEVELING_UBL)
// L to load a mesh from the EEPROM
@@ -155,21 +153,18 @@ void GcodeSuite::M420() {
// Get the sum and average of all mesh values
float mesh_sum = 0;
- for (uint8_t x = GRID_MAX_POINTS_X; x--;)
- for (uint8_t y = GRID_MAX_POINTS_Y; y--;)
- mesh_sum += Z_VALUES(x, y);
+ GRID_LOOP(x, y) mesh_sum += Z_VALUES(x, y);
const float zmean = mesh_sum / float(GRID_MAX_POINTS);
#else
// Find the low and high mesh values
float lo_val = 100, hi_val = -100;
- for (uint8_t x = GRID_MAX_POINTS_X; x--;)
- for (uint8_t y = GRID_MAX_POINTS_Y; y--;) {
- const float z = Z_VALUES(x, y);
- NOMORE(lo_val, z);
- NOLESS(hi_val, z);
- }
+ GRID_LOOP(x, y) {
+ const float z = Z_VALUES(x, y);
+ NOMORE(lo_val, z);
+ NOLESS(hi_val, z);
+ }
// Take the mean of the lowest and highest
const float zmean = (lo_val + hi_val) / 2.0 + cval;
@@ -179,16 +174,11 @@ void GcodeSuite::M420() {
if (!NEAR_ZERO(zmean)) {
set_bed_leveling_enabled(false);
// Subtract the mean from all values
- for (uint8_t x = GRID_MAX_POINTS_X; x--;)
- for (uint8_t y = GRID_MAX_POINTS_Y; y--;) {
- Z_VALUES(x, y) -= zmean;
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(x, y, Z_VALUES(x, y));
- #endif
- }
- #if ENABLED(ABL_BILINEAR_SUBDIVISION)
- bed_level_virt_interpolate();
- #endif
+ GRID_LOOP(x, y) {
+ Z_VALUES(x, y) -= zmean;
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, Z_VALUES(x, y)));
+ }
+ TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate());
}
#endif
@@ -210,9 +200,7 @@ void GcodeSuite::M420() {
if (leveling_is_valid()) {
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
print_bilinear_leveling_grid();
- #if ENABLED(ABL_BILINEAR_SUBDIVISION)
- print_bilinear_leveling_grid_virt();
- #endif
+ TERN_(ABL_BILINEAR_SUBDIVISION, print_bilinear_leveling_grid_virt());
#elif ENABLED(MESH_BED_LEVELING)
SERIAL_ECHOLNPGM("Mesh Bed Level data:");
mbl.report_mesh();
diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp
index de6954598..f25fe32b0 100644
--- a/Marlin/src/gcode/bedlevel/abl/G29.cpp
+++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -60,7 +60,11 @@
#include "../../../lcd/extui/ui_api.h"
#endif
-#if HOTENDS > 1
+#if ENABLED(DWIN_CREALITY_LCD)
+ #include "../../../lcd/dwin/dwin.h"
+#endif
+
+#if HAS_MULTI_HOTEND
#include "../../../module/tool_change.h"
#endif
@@ -78,11 +82,7 @@
#endif
#endif
-#if ENABLED(G29_RETRY_AND_RECOVER)
- #define G29_RETURN(b) return b;
-#else
- #define G29_RETURN(b) return;
-#endif
+#define G29_RETURN(b) return TERN_(G29_RETRY_AND_RECOVER, b)
/**
* G29: Detailed Z probe, probes the bed at 3 or more points.
@@ -164,55 +164,34 @@
*/
G29_TYPE GcodeSuite::G29() {
- #if EITHER(DEBUG_LEVELING_FEATURE, PROBE_MANUALLY)
- const bool seenQ = parser.seen('Q');
- #else
- constexpr bool seenQ = false;
- #endif
+ reset_stepper_timeout();
+
+ const bool seenQ = EITHER(DEBUG_LEVELING_FEATURE, PROBE_MANUALLY) && parser.seen('Q');
// G29 Q is also available if debugging
#if ENABLED(DEBUG_LEVELING_FEATURE)
const uint8_t old_debug_flags = marlin_debug_flags;
if (seenQ) marlin_debug_flags |= MARLIN_DEBUG_LEVELING;
- if (DEBUGGING(LEVELING)) {
- DEBUG_POS(">>> G29", current_position);
- log_machine_info();
- }
+ DEBUG_SECTION(log_G29, "G29", DEBUGGING(LEVELING));
+ if (DEBUGGING(LEVELING)) log_machine_info();
marlin_debug_flags = old_debug_flags;
- #if DISABLED(PROBE_MANUALLY)
- if (seenQ) G29_RETURN(false);
- #endif
+ if (DISABLED(PROBE_MANUALLY) && seenQ) G29_RETURN(false);
#endif
- #if ENABLED(PROBE_MANUALLY)
- const bool seenA = parser.seen('A');
- #else
- constexpr bool seenA = false;
- #endif
-
- const bool no_action = seenA || seenQ,
- faux =
- #if ENABLED(DEBUG_LEVELING_FEATURE) && DISABLED(PROBE_MANUALLY)
- parser.boolval('C')
- #else
- no_action
- #endif
- ;
+ const bool seenA = TERN0(PROBE_MANUALLY, parser.seen('A')),
+ no_action = seenA || seenQ,
+ faux = ENABLED(DEBUG_LEVELING_FEATURE) && DISABLED(PROBE_MANUALLY) ? parser.boolval('C') : no_action;
// Don't allow auto-leveling without homing first
if (axis_unhomed_error()) G29_RETURN(false);
if (!no_action && planner.leveling_active && parser.boolval('O')) { // Auto-level only if needed
- if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> Auto-level not needed, skip\n<<< G29");
+ if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> Auto-level not needed, skip");
G29_RETURN(false);
}
// Define local vars 'static' for manual probing, 'auto' otherwise
- #if ENABLED(PROBE_MANUALLY)
- #define ABL_VAR static
- #else
- #define ABL_VAR
- #endif
+ #define ABL_VAR TERN_(PROBE_MANUALLY, static)
ABL_VAR int verbose_level;
ABL_VAR xy_pos_t probePos;
@@ -223,7 +202,7 @@ G29_TYPE GcodeSuite::G29() {
ABL_VAR int abl_probe_index;
#endif
- #if HAS_SOFTWARE_ENDSTOPS && ENABLED(PROBE_MANUALLY)
+ #if BOTH(HAS_SOFTWARE_ENDSTOPS, PROBE_MANUALLY)
ABL_VAR bool saved_soft_endstops_state = true;
#endif
@@ -245,7 +224,7 @@ G29_TYPE GcodeSuite::G29() {
#if ENABLED(AUTO_BED_LEVELING_LINEAR)
ABL_VAR int abl_points;
- #elif ENABLED(PROBE_MANUALLY) // Bilinear
+ #else
int constexpr abl_points = GRID_MAX_POINTS;
#endif
@@ -283,9 +262,7 @@ G29_TYPE GcodeSuite::G29() {
*/
if (!g29_in_progress) {
- #if HOTENDS > 1
- if (active_extruder != 0) tool_change(0);
- #endif
+ TERN_(HAS_MULTI_HOTEND, if (active_extruder) tool_change(0));
#if EITHER(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR)
abl_probe_index = -1;
@@ -322,12 +299,8 @@ G29_TYPE GcodeSuite::G29() {
if (WITHIN(i, 0, GRID_MAX_POINTS_X - 1) && WITHIN(j, 0, GRID_MAX_POINTS_Y)) {
set_bed_leveling_enabled(false);
z_values[i][j] = rz;
- #if ENABLED(ABL_BILINEAR_SUBDIVISION)
- bed_level_virt_interpolate();
- #endif
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(i, j, rz);
- #endif
+ TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate());
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(i, j, rz));
set_bed_leveling_enabled(abl_should_enable);
if (abl_should_enable) report_current_position();
}
@@ -352,11 +325,7 @@ G29_TYPE GcodeSuite::G29() {
G29_RETURN(false);
}
- dryrun = parser.boolval('D')
- #if ENABLED(PROBE_MANUALLY)
- || no_action
- #endif
- ;
+ dryrun = parser.boolval('D') || TERN0(PROBE_MANUALLY, no_action);
#if ENABLED(AUTO_BED_LEVELING_LINEAR)
@@ -436,26 +405,27 @@ G29_TYPE GcodeSuite::G29() {
planner.synchronize();
+ if (!faux) remember_feedrate_scaling_off();
+
// Disable auto bed leveling during G29.
// Be formal so G29 can be done successively without G28.
if (!no_action) set_bed_leveling_enabled(false);
+ // Deploy certain probes before starting probing
#if HAS_BED_PROBE
- // Deploy the probe. Probe will raise if needed.
- if (probe.deploy()) {
+ if (ENABLED(BLTOUCH))
+ do_z_clearance(Z_CLEARANCE_DEPLOY_PROBE);
+ else if (probe.deploy()) {
set_bed_leveling_enabled(abl_should_enable);
G29_RETURN(false);
}
#endif
- if (!faux) remember_feedrate_scaling_off();
-
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
- #if ENABLED(PROBE_MANUALLY)
- if (!no_action)
- #endif
- if (gridSpacing != bilinear_grid_spacing || probe_position_lf != bilinear_start) {
+ if (TERN1(PROBE_MANUALLY, !no_action)
+ && (gridSpacing != bilinear_grid_spacing || probe_position_lf != bilinear_start)
+ ) {
// Reset grid to 0.0 or "not probed". (Also disables ABL)
reset_bed_level();
@@ -492,14 +462,10 @@ G29_TYPE GcodeSuite::G29() {
// Abort current G29 procedure, go back to idle state
if (seenA && g29_in_progress) {
SERIAL_ECHOLNPGM("Manual G29 aborted");
- #if HAS_SOFTWARE_ENDSTOPS
- soft_endstops_enabled = saved_soft_endstops_state;
- #endif
+ TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = saved_soft_endstops_state);
set_bed_leveling_enabled(abl_should_enable);
g29_in_progress = false;
- #if ENABLED(LCD_BED_LEVELING)
- ui.wait_for_move = false;
- #endif
+ TERN_(LCD_BED_LEVELING, ui.wait_for_move = false);
}
// Query G29 status
@@ -517,9 +483,7 @@ G29_TYPE GcodeSuite::G29() {
if (abl_probe_index == 0) {
// For the initial G29 S2 save software endstop state
- #if HAS_SOFTWARE_ENDSTOPS
- saved_soft_endstops_state = soft_endstops_enabled;
- #endif
+ TERN_(HAS_SOFTWARE_ENDSTOPS, saved_soft_endstops_state = soft_endstops_enabled);
// Move close to the bed before the first point
do_blocking_move_to_z(0);
}
@@ -551,9 +515,7 @@ G29_TYPE GcodeSuite::G29() {
const float newz = measured_z + zoffset;
z_values[meshCount.x][meshCount.y] = newz;
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(meshCount, newz);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(meshCount, newz));
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR_P(PSTR("Save X"), meshCount.x, SP_Y_STR, meshCount.y, SP_Z_STR, measured_z + zoffset);
@@ -574,15 +536,12 @@ G29_TYPE GcodeSuite::G29() {
PR_INNER_VAR = abl_probe_index - (PR_OUTER_VAR * PR_INNER_END);
// Probe in reverse order for every other row/column
- bool zig = (PR_OUTER_VAR & 1); // != ((PR_OUTER_END) & 1);
-
+ const bool zig = (PR_OUTER_VAR & 1); // != ((PR_OUTER_END) & 1);
if (zig) PR_INNER_VAR = (PR_INNER_END - 1) - PR_INNER_VAR;
probePos = probe_position_lf + gridSpacing * meshCount.asFloat();
- #if ENABLED(AUTO_BED_LEVELING_LINEAR)
- indexIntoAB[meshCount.x][meshCount.y] = abl_probe_index;
- #endif
+ TERN_(AUTO_BED_LEVELING_LINEAR, indexIntoAB[meshCount.x][meshCount.y] = abl_probe_index);
// Keep looping till a reachable point is found
if (position_is_reachable(probePos)) break;
@@ -592,23 +551,16 @@ G29_TYPE GcodeSuite::G29() {
// Is there a next point to move to?
if (abl_probe_index < abl_points) {
_manual_goto_xy(probePos); // Can be used here too!
- #if HAS_SOFTWARE_ENDSTOPS
- // Disable software endstops to allow manual adjustment
- // If G29 is not completed, they will not be re-enabled
- soft_endstops_enabled = false;
- #endif
+ // Disable software endstops to allow manual adjustment
+ // If G29 is not completed, they will not be re-enabled
+ TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = false);
G29_RETURN(false);
}
else {
-
// Leveling done! Fall through to G29 finishing code below
-
SERIAL_ECHOLNPGM("Grid probing done.");
-
// Re-enable software endstops, if needed
- #if HAS_SOFTWARE_ENDSTOPS
- soft_endstops_enabled = saved_soft_endstops_state;
- #endif
+ TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = saved_soft_endstops_state);
}
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
@@ -617,11 +569,9 @@ G29_TYPE GcodeSuite::G29() {
if (abl_probe_index < abl_points) {
probePos = points[abl_probe_index];
_manual_goto_xy(probePos);
- #if HAS_SOFTWARE_ENDSTOPS
- // Disable software endstops to allow manual adjustment
- // If G29 is not completed, they will not be re-enabled
- soft_endstops_enabled = false;
- #endif
+ // Disable software endstops to allow manual adjustment
+ // If G29 is not completed, they will not be re-enabled
+ TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = false);
G29_RETURN(false);
}
else {
@@ -629,9 +579,7 @@ G29_TYPE GcodeSuite::G29() {
SERIAL_ECHOLNPGM("3-point probing done.");
// Re-enable software endstops, if needed
- #if HAS_SOFTWARE_ENDSTOPS
- soft_endstops_enabled = saved_soft_endstops_state;
- #endif
+ TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = saved_soft_endstops_state);
if (!dryrun) {
vector_3 planeNormal = vector_3::cross(points[0] - points[1], points[2] - points[1]).get_normal();
@@ -688,19 +636,13 @@ G29_TYPE GcodeSuite::G29() {
probePos = probe_position_lf + gridSpacing * meshCount.asFloat();
- #if ENABLED(AUTO_BED_LEVELING_LINEAR)
- indexIntoAB[meshCount.x][meshCount.y] = ++abl_probe_index; // 0...
- #endif
+ TERN_(AUTO_BED_LEVELING_LINEAR, indexIntoAB[meshCount.x][meshCount.y] = ++abl_probe_index); // 0...
- #if IS_KINEMATIC
- // Avoid probing outside the round or hexagonal area
- if (!probe.can_reach(probePos)) continue;
- #endif
+ // Avoid probing outside the round or hexagonal area
+ if (TERN0(IS_KINEMATIC, !probe.can_reach(probePos))) continue;
- if (verbose_level) SERIAL_ECHOLNPAIR("Probing mesh point ", int(pt_index), "/", int(GRID_MAX_POINTS), ".");
- #if HAS_DISPLAY
- ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), int(pt_index), int(GRID_MAX_POINTS));
- #endif
+ if (verbose_level) SERIAL_ECHOLNPAIR("Probing mesh point ", int(pt_index), "/", abl_points, ".");
+ TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), int(pt_index), int(abl_points)));
measured_z = faux ? 0.001f * random(-100, 101) : probe.probe_at_point(probePos, raise_after, verbose_level);
@@ -712,9 +654,7 @@ G29_TYPE GcodeSuite::G29() {
#if ENABLED(PROBE_TEMP_COMPENSATION)
temp_comp.compensate_measurement(TSI_BED, thermalManager.degBed(), measured_z);
temp_comp.compensate_measurement(TSI_PROBE, thermalManager.degProbe(), measured_z);
- #if ENABLED(USE_TEMP_EXT_COMPENSATION)
- temp_comp.compensate_measurement(TSI_EXT, thermalManager.degHotend(), measured_z);
- #endif
+ TERN_(USE_TEMP_EXT_COMPENSATION, temp_comp.compensate_measurement(TSI_EXT, thermalManager.degHotend(), measured_z));
#endif
#if ENABLED(AUTO_BED_LEVELING_LINEAR)
@@ -730,14 +670,12 @@ G29_TYPE GcodeSuite::G29() {
#elif ENABLED(AUTO_BED_LEVELING_BILINEAR)
z_values[meshCount.x][meshCount.y] = measured_z + zoffset;
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(meshCount, z_values[meshCount.x][meshCount.y]);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(meshCount, z_values[meshCount.x][meshCount.y]));
#endif
abl_should_enable = false;
- idle();
+ idle_no_sleep();
} // inner
} // outer
@@ -747,10 +685,8 @@ G29_TYPE GcodeSuite::G29() {
// Probe at 3 arbitrary points
LOOP_L_N(i, 3) {
- if (verbose_level) SERIAL_ECHOLNPAIR("Probing point ", int(i), "/3.");
- #if HAS_DISPLAY
- ui.status_printf_P(0, PSTR(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_MESH), int(i));
- #endif
+ if (verbose_level) SERIAL_ECHOLNPAIR("Probing point ", int(i + 1), "/3.");
+ TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_MESH), int(i + 1)));
// Retain the last probe position
probePos = points[i];
@@ -773,9 +709,7 @@ G29_TYPE GcodeSuite::G29() {
#endif // AUTO_BED_LEVELING_3POINT
- #if HAS_DISPLAY
- ui.reset_status();
- #endif
+ TERN_(HAS_DISPLAY, ui.reset_status());
// Stow the probe. No raise for FIX_MOUNTED_PROBE.
if (probe.stow()) {
@@ -799,9 +733,7 @@ G29_TYPE GcodeSuite::G29() {
#if ENABLED(PROBE_MANUALLY)
g29_in_progress = false;
- #if ENABLED(LCD_BED_LEVELING)
- ui.wait_for_move = false;
- #endif
+ TERN_(LCD_BED_LEVELING, ui.wait_for_move = false);
#endif
// Calculate leveling, print reports, correct the position
@@ -813,9 +745,7 @@ G29_TYPE GcodeSuite::G29() {
refresh_bed_level();
- #if ENABLED(ABL_BILINEAR_SUBDIVISION)
- print_bilinear_leveling_grid_virt();
- #endif
+ TERN_(ABL_BILINEAR_SUBDIVISION, print_bilinear_leveling_grid_virt());
#elif ENABLED(AUTO_BED_LEVELING_LINEAR)
@@ -934,11 +864,7 @@ G29_TYPE GcodeSuite::G29() {
// Unapply the offset because it is going to be immediately applied
// and cause compensation movement in Z
- #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
- const float fade_scaling_factor = planner.fade_scaling_factor_for_z(current_position.z);
- #else
- constexpr float fade_scaling_factor = 1.0f;
- #endif
+ const float fade_scaling_factor = TERN(ENABLE_LEVELING_FADE_HEIGHT, planner.fade_scaling_factor_for_z(current_position.z), 1);
current_position.z -= fade_scaling_factor * bilinear_z_offset(current_position);
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(" corrected Z:", current_position.z);
@@ -956,7 +882,7 @@ G29_TYPE GcodeSuite::G29() {
// Sync the planner from the current_position
if (planner.leveling_active) sync_plan_position();
- #if HAS_BED_PROBE && defined(Z_AFTER_PROBING)
+ #if HAS_BED_PROBE
probe.move_z_after_probing();
#endif
@@ -966,9 +892,11 @@ G29_TYPE GcodeSuite::G29() {
process_subcommands_now_P(PSTR(Z_PROBE_END_SCRIPT));
#endif
- report_current_position();
+ #if ENABLED(DWIN_CREALITY_LCD)
+ DWIN_CompletedLeveling();
+ #endif
- if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("<<< G29");
+ report_current_position();
G29_RETURN(isnan(measured_z));
}
diff --git a/Marlin/src/gcode/bedlevel/abl/M421.cpp b/Marlin/src/gcode/bedlevel/abl/M421.cpp
index 3cd2673d6..182dc3251 100644
--- a/Marlin/src/gcode/bedlevel/abl/M421.cpp
+++ b/Marlin/src/gcode/bedlevel/abl/M421.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -36,32 +36,39 @@
#endif
/**
- * M421: Set a single Mesh Bed Leveling Z coordinate
+ * M421: Set one or more Mesh Bed Leveling Z coordinates
*
* Usage:
* M421 I J Z
* M421 I J Q
+ *
+ * - If I is omitted, set the entire row
+ * - If J is omitted, set the entire column
+ * - If both I and J are omitted, set all
*/
void GcodeSuite::M421() {
int8_t ix = parser.intval('I', -1), iy = parser.intval('J', -1);
- const bool hasI = ix >= 0,
- hasJ = iy >= 0,
- hasZ = parser.seen('Z'),
- hasQ = !hasZ && parser.seen('Q');
+ const bool hasZ = parser.seenval('Z'),
+ hasQ = !hasZ && parser.seenval('Q');
- if (!hasI || !hasJ || !(hasZ || hasQ))
- SERIAL_ERROR_MSG(STR_ERR_M421_PARAMETERS);
- else if (!WITHIN(ix, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(iy, 0, GRID_MAX_POINTS_Y - 1))
- SERIAL_ERROR_MSG(STR_ERR_MESH_XY);
- else {
- z_values[ix][iy] = parser.value_linear_units() + (hasQ ? z_values[ix][iy] : 0);
- #if ENABLED(ABL_BILINEAR_SUBDIVISION)
- bed_level_virt_interpolate();
- #endif
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(ix, iy, z_values[ix][iy]);
- #endif
+ if (hasZ || hasQ) {
+ if (WITHIN(ix, -1, GRID_MAX_POINTS_X - 1) && WITHIN(iy, -1, GRID_MAX_POINTS_Y - 1)) {
+ const float zval = parser.value_linear_units();
+ uint8_t sx = ix >= 0 ? ix : 0, ex = ix >= 0 ? ix : GRID_MAX_POINTS_X - 1,
+ sy = iy >= 0 ? iy : 0, ey = iy >= 0 ? iy : GRID_MAX_POINTS_Y - 1;
+ LOOP_S_LE_N(x, sx, ex) {
+ LOOP_S_LE_N(y, sy, ey) {
+ z_values[x][y] = zval + (hasQ ? z_values[x][y] : 0);
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y]));
+ }
+ }
+ TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate());
+ }
+ else
+ SERIAL_ERROR_MSG(STR_ERR_MESH_XY);
}
+ else
+ SERIAL_ERROR_MSG(STR_ERR_M421_PARAMETERS);
}
#endif // AUTO_BED_LEVELING_BILINEAR
diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp
index 6c8fafe23..68ac459eb 100644
--- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp
+++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -62,9 +62,7 @@ inline void echo_not_entered(const char c) { SERIAL_CHAR(c); SERIAL_ECHOLNPGM("
void GcodeSuite::G29() {
static int mbl_probe_index = -1;
- #if HAS_SOFTWARE_ENDSTOPS
- static bool saved_soft_endstops_state;
- #endif
+ TERN_(HAS_SOFTWARE_ENDSTOPS, static bool saved_soft_endstops_state);
MeshLevelingState state = (MeshLevelingState)parser.byteval('S', (int8_t)MeshReport);
if (!WITHIN(state, 0, 5)) {
@@ -111,9 +109,7 @@ void GcodeSuite::G29() {
else {
// Save Z for the previous mesh position
mbl.set_zigzag_z(mbl_probe_index - 1, current_position.z);
- #if HAS_SOFTWARE_ENDSTOPS
- soft_endstops_enabled = saved_soft_endstops_state;
- #endif
+ TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = saved_soft_endstops_state);
}
// If there's another point to sample, move there with optional lift.
if (mbl_probe_index < GRID_MAX_POINTS) {
@@ -147,9 +143,7 @@ void GcodeSuite::G29() {
planner.synchronize();
#endif
- #if ENABLED(LCD_BED_LEVELING)
- ui.wait_for_move = false;
- #endif
+ TERN_(LCD_BED_LEVELING, ui.wait_for_move = false);
}
break;
@@ -178,9 +172,7 @@ void GcodeSuite::G29() {
if (parser.seenval('Z')) {
mbl.z_values[ix][iy] = parser.value_linear_units();
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(ix, iy, mbl.z_values[ix][iy]);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, mbl.z_values[ix][iy]));
}
else
return echo_not_entered('Z');
diff --git a/Marlin/src/gcode/bedlevel/mbl/M421.cpp b/Marlin/src/gcode/bedlevel/mbl/M421.cpp
index 3997e5ad5..1368ab0be 100644
--- a/Marlin/src/gcode/bedlevel/mbl/M421.cpp
+++ b/Marlin/src/gcode/bedlevel/mbl/M421.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/bedlevel/ubl/G29.cpp b/Marlin/src/gcode/bedlevel/ubl/G29.cpp
index 7b42e6ddd..2ef3ab4ce 100644
--- a/Marlin/src/gcode/bedlevel/ubl/G29.cpp
+++ b/Marlin/src/gcode/bedlevel/ubl/G29.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/bedlevel/ubl/M421.cpp b/Marlin/src/gcode/bedlevel/ubl/M421.cpp
index bd65c21ad..600c1fc8b 100644
--- a/Marlin/src/gcode/bedlevel/ubl/M421.cpp
+++ b/Marlin/src/gcode/bedlevel/ubl/M421.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -63,9 +63,7 @@ void GcodeSuite::M421() {
else {
float &zval = ubl.z_values[ij.x][ij.y];
zval = hasN ? NAN : parser.value_linear_units() + (hasQ ? zval : 0);
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onMeshUpdate(ij.x, ij.y, zval);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ij.x, ij.y, zval));
}
}
diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp
index fafce9a89..1fbb3dd35 100644
--- a/Marlin/src/gcode/calibrate/G28.cpp
+++ b/Marlin/src/gcode/calibrate/G28.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -27,7 +27,7 @@
#include "../../module/stepper.h"
#include "../../module/endstops.h"
-#if HOTENDS > 1
+#if HAS_MULTI_HOTEND
#include "../../module/tool_change.h"
#endif
@@ -46,11 +46,18 @@
#endif
#include "../../lcd/ultralcd.h"
+#if ENABLED(DWIN_CREALITY_LCD)
+ #include "../../lcd/dwin/dwin.h"
+#endif
#if HAS_L64XX // set L6470 absolute position registers to counts
#include "../../libs/L64XX/L64XX_Marlin.h"
#endif
+#if ENABLED(LASER_MOVE_G28_OFF)
+ #include "../../feature/spindle_laser.h"
+#endif
+
#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE)
#include "../../core/debug_out.h"
@@ -108,15 +115,10 @@
#if ENABLED(Z_SAFE_HOMING)
inline void home_z_safely() {
+ DEBUG_SECTION(log_G28, "home_z_safely", DEBUGGING(LEVELING));
- // Disallow Z homing if X or Y are unknown
- if (!TEST(axis_known_position, X_AXIS) || !TEST(axis_known_position, Y_AXIS)) {
- LCD_MESSAGEPGM(MSG_ERR_Z_HOMING);
- SERIAL_ECHO_MSG(STR_ERR_Z_HOMING_SER);
- return;
- }
-
- if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("home_z_safely >>>");
+ // Disallow Z homing if X or Y homing is needed
+ if (axis_unhomed_error(_BV(X_AXIS) | _BV(Y_AXIS))) return;
sync_plan_position();
@@ -126,22 +128,16 @@
*/
destination.set(safe_homing_xy, current_position.z);
- #if HOMING_Z_WITH_PROBE
- destination -= probe.offset_xy;
- #endif
+ TERN_(HOMING_Z_WITH_PROBE, destination -= probe.offset_xy);
if (position_is_reachable(destination)) {
if (DEBUGGING(LEVELING)) DEBUG_POS("home_z_safely", destination);
// This causes the carriage on Dual X to unpark
- #if ENABLED(DUAL_X_CARRIAGE)
- active_extruder_parked = false;
- #endif
+ TERN_(DUAL_X_CARRIAGE, active_extruder_parked = false);
- #if ENABLED(SENSORLESS_HOMING)
- safe_delay(500); // Short delay needed to settle
- #endif
+ TERN_(SENSORLESS_HOMING, safe_delay(500)); // Short delay needed to settle
do_blocking_move_to_xy(destination);
homeaxis(Z_AXIS);
@@ -150,8 +146,6 @@
LCD_MESSAGEPGM(MSG_ZPROBE_OUT);
SERIAL_ECHO_MSG(STR_ZPROBE_OUT_SER);
}
-
- if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("<<< home_z_safely");
}
#endif // Z_SAFE_HOMING
@@ -175,9 +169,7 @@
void end_slow_homing(const slow_homing_t &slow_homing) {
planner.settings.max_acceleration_mm_per_s2[X_AXIS] = slow_homing.acceleration.x;
planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = slow_homing.acceleration.y;
- #if HAS_CLASSIC_JERK
- planner.max_jerk = slow_homing.jerk_xy;
- #endif
+ TERN_(HAS_CLASSIC_JERK, planner.max_jerk = slow_homing.jerk_xy);
planner.reset_acceleration_rates();
}
@@ -203,10 +195,12 @@
*
*/
void GcodeSuite::G28() {
- if (DEBUGGING(LEVELING)) {
- DEBUG_ECHOLNPGM(">>> G28");
- log_machine_info();
- }
+ DEBUG_SECTION(log_G28, "G28", DEBUGGING(LEVELING));
+ if (DEBUGGING(LEVELING)) log_machine_info();
+
+ TERN_(LASER_MOVE_G28_OFF, cutter.set_inline_enabled(false)); // turn off laser
+
+ TERN_(DWIN_CREALITY_LCD, HMI_flag.home_flag = true);
#if ENABLED(DUAL_X_CARRIAGE)
bool IDEX_saved_duplication_state = extruder_duplication_enabled;
@@ -219,14 +213,13 @@ void GcodeSuite::G28() {
sync_plan_position();
SERIAL_ECHOLNPGM("Simulated Homing");
report_current_position();
- if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("<<< G28");
return;
}
#endif
// Home (O)nly if position is unknown
if (!homing_needed() && parser.boolval('O')) {
- if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> homing not needed, skip\n<<< G28");
+ if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> homing not needed, skip");
return;
}
@@ -237,22 +230,21 @@ void GcodeSuite::G28() {
#if HAS_LEVELING
// Cancel the active G29 session
- #if ENABLED(PROBE_MANUALLY)
- g29_in_progress = false;
- #endif
+ TERN_(PROBE_MANUALLY, g29_in_progress = false);
- #if ENABLED(RESTORE_LEVELING_AFTER_G28)
- const bool leveling_was_active = planner.leveling_active;
- #endif
+ TERN_(RESTORE_LEVELING_AFTER_G28, const bool leveling_was_active = planner.leveling_active);
set_bed_leveling_enabled(false);
#endif
- #if ENABLED(CNC_WORKSPACE_PLANES)
- workspace_plane = PLANE_XY;
- #endif
+ TERN_(CNC_WORKSPACE_PLANES, workspace_plane = PLANE_XY);
+
+ // Count this command as movement / activity
+ reset_stepper_timeout();
#define HAS_CURRENT_HOME(N) (defined(N##_CURRENT_HOME) && N##_CURRENT_HOME != N##_CURRENT)
- #define HAS_HOMING_CURRENT (HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(X2) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Y2))
+ #if HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(X2) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Y2)
+ #define HAS_HOMING_CURRENT 1
+ #endif
#if HAS_HOMING_CURRENT
auto debug_current = [](PGM_P const s, const int16_t a, const int16_t b){
@@ -280,21 +272,17 @@ void GcodeSuite::G28() {
#endif
#endif
- #if ENABLED(IMPROVE_HOMING_RELIABILITY)
- slow_homing_t slow_homing = begin_slow_homing();
- #endif
+ TERN_(IMPROVE_HOMING_RELIABILITY, slow_homing_t slow_homing = begin_slow_homing());
// Always home with tool 0 active
- #if HOTENDS > 1
+ #if HAS_MULTI_HOTEND
#if DISABLED(DELTA) || ENABLED(DELTA_HOME_TO_SAFE_ZONE)
const uint8_t old_tool_index = active_extruder;
#endif
tool_change(0, true);
#endif
- #if HAS_DUPLICATION_MODE
- extruder_duplication_enabled = false;
- #endif
+ TERN_(HAS_DUPLICATION_MODE, extruder_duplication_enabled = false);
remember_feedrate_scaling_off();
@@ -306,18 +294,17 @@ void GcodeSuite::G28() {
home_delta();
- #if ENABLED(IMPROVE_HOMING_RELIABILITY)
- end_slow_homing(slow_homing);
- #endif
+ TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(slow_homing));
#else // NOT DELTA
- const bool homeX = parser.seen('X'), homeY = parser.seen('Y'), homeZ = parser.seen('Z'),
+ const bool homeZ = parser.seen('Z'),
+ needX = homeZ && TERN0(Z_SAFE_HOMING, axes_need_homing(_BV(X_AXIS))),
+ needY = homeZ && TERN0(Z_SAFE_HOMING, axes_need_homing(_BV(Y_AXIS))),
+ homeX = needX || parser.seen('X'), homeY = needY || parser.seen('Y'),
home_all = homeX == homeY && homeX == homeZ, // All or None
doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ;
- destination = current_position;
-
#if Z_HOME_DIR > 0 // If homing away from BED do Z first
if (doZ) homeaxis(Z_AXIS);
@@ -325,17 +312,14 @@ void GcodeSuite::G28() {
#endif
const float z_homing_height =
- (DISABLED(UNKNOWN_Z_NO_RAISE) || TEST(axis_known_position, Z_AXIS))
- ? (parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT)
- : 0;
+ ENABLED(UNKNOWN_Z_NO_RAISE) && TEST(axis_known_position, Z_AXIS)
+ ? 0
+ : (parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT);
- if (z_homing_height && (doX || doY)) {
+ if (z_homing_height && (doX || doY || (ENABLED(Z_SAFE_HOMING) && doZ))) {
// Raise Z before homing any other axes and z is not already high enough (never lower z)
- destination.z = z_homing_height + (TEST(axis_known_position, Z_AXIS) ? 0.0f : current_position.z);
- if (destination.z > current_position.z) {
- if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Raise Z (before homing) to ", destination.z);
- do_blocking_move_to_z(destination.z);
- }
+ if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Raise Z (before homing) by ", z_homing_height);
+ do_z_clearance(z_homing_height, TEST(axis_known_position, Z_AXIS), DISABLED(UNKNOWN_Z_NO_RAISE));
}
#if ENABLED(QUICK_HOME)
@@ -380,32 +364,17 @@ void GcodeSuite::G28() {
if (DISABLED(HOME_Y_BEFORE_X) && doY)
homeaxis(Y_AXIS);
- #if ENABLED(IMPROVE_HOMING_RELIABILITY)
- end_slow_homing(slow_homing);
- #endif
+ TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(slow_homing));
// Home Z last if homing towards the bed
#if Z_HOME_DIR < 0
if (doZ) {
- #if ENABLED(BLTOUCH)
- bltouch.init();
- #endif
- #if ENABLED(Z_SAFE_HOMING)
- home_z_safely();
- #else
- homeaxis(Z_AXIS);
- #endif
+ TERN_(BLTOUCH, bltouch.init());
- #if HOMING_Z_WITH_PROBE && defined(Z_AFTER_PROBING)
- #if Z_AFTER_HOMING > Z_AFTER_PROBING
- do_blocking_move_to_z(Z_AFTER_HOMING);
- #else
- probe.move_z_after_probing();
- #endif
- #elif defined(Z_AFTER_HOMING)
- do_blocking_move_to_z(Z_AFTER_HOMING);
- #endif
+ TERN(Z_SAFE_HOMING, home_z_safely(), homeaxis(Z_AXIS));
+
+ probe.move_z_after_homing();
} // doZ
@@ -425,9 +394,7 @@ void GcodeSuite::G28() {
if (dxc_is_duplicating()) {
- #if ENABLED(IMPROVE_HOMING_RELIABILITY)
- slow_homing = begin_slow_homing();
- #endif
+ TERN_(IMPROVE_HOMING_RELIABILITY, slow_homing = begin_slow_homing());
// Always home the 2nd (right) extruder first
active_extruder = 1;
@@ -448,9 +415,7 @@ void GcodeSuite::G28() {
dual_x_carriage_mode = IDEX_saved_mode;
stepper.set_directions();
- #if ENABLED(IMPROVE_HOMING_RELIABILITY)
- end_slow_homing(slow_homing);
- #endif
+ TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(slow_homing));
}
#endif // DUAL_X_CARRIAGE
@@ -458,23 +423,19 @@ void GcodeSuite::G28() {
endstops.not_homing();
// Clear endstop state for polled stallGuard endstops
- #if ENABLED(SPI_ENDSTOPS)
- endstops.clear_endstop_state();
- #endif
+ TERN_(SPI_ENDSTOPS, endstops.clear_endstop_state());
#if BOTH(DELTA, DELTA_HOME_TO_SAFE_ZONE)
// move to a height where we can use the full xy-area
do_blocking_move_to_z(delta_clip_start_height);
#endif
- #if ENABLED(RESTORE_LEVELING_AFTER_G28)
- set_bed_leveling_enabled(leveling_was_active);
- #endif
+ TERN_(RESTORE_LEVELING_AFTER_G28, set_bed_leveling_enabled(leveling_was_active));
restore_feedrate_and_scaling();
// Restore the active tool after homing
- #if HOTENDS > 1 && (DISABLED(DELTA) || ENABLED(DELTA_HOME_TO_SAFE_ZONE))
+ #if HAS_MULTI_HOTEND && (DISABLED(DELTA) || ENABLED(DELTA_HOME_TO_SAFE_ZONE))
tool_change(old_tool_index, NONE(PARKING_EXTRUDER, DUAL_X_CARRIAGE)); // Do move if one of these
#endif
@@ -496,13 +457,13 @@ void GcodeSuite::G28() {
ui.refresh();
+ TERN_(DWIN_CREALITY_LCD, DWIN_CompletedHoming());
+
report_current_position();
if (ENABLED(NANODLP_Z_SYNC) && (doZ || ENABLED(NANODLP_ALL_AXIS)))
SERIAL_ECHOLNPGM(STR_Z_MOVE_COMP);
- if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("<<< G28");
-
#if HAS_L64XX
// Set L6470 absolute position registers to counts
// constexpr *might* move this to PROGMEM.
diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp
index ac2cdf7d4..53af04d52 100644
--- a/Marlin/src/gcode/calibrate/G33.cpp
+++ b/Marlin/src/gcode/calibrate/G33.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -35,7 +35,7 @@
#include "../../module/probe.h"
#endif
-#if HOTENDS > 1
+#if HAS_MULTI_HOTEND
#include "../../module/tool_change.h"
#endif
@@ -63,12 +63,7 @@ enum CalEnum : char { // the 7 main calibration points -
#define LOOP_CAL_RAD(VAR) LOOP_CAL_PT(VAR, __A, _7P_STEP)
#define LOOP_CAL_ACT(VAR, _4P, _OP) LOOP_CAL_PT(VAR, _OP ? _AB : __A, _4P ? _4P_STEP : _7P_STEP)
-#if HOTENDS > 1
- const uint8_t old_tool_index = active_extruder;
- #define AC_CLEANUP() ac_cleanup(old_tool_index)
-#else
- #define AC_CLEANUP() ac_cleanup()
-#endif
+TERN_(HAS_MULTI_HOTEND, const uint8_t old_tool_index = active_extruder);
float lcd_probe_pt(const xy_pos_t &xy);
@@ -79,9 +74,7 @@ void ac_home() {
}
void ac_setup(const bool reset_bed) {
- #if HOTENDS > 1
- tool_change(0, true);
- #endif
+ TERN_(HAS_MULTI_HOTEND, tool_change(0, true));
planner.synchronize();
remember_feedrate_scaling_off();
@@ -91,21 +84,11 @@ void ac_setup(const bool reset_bed) {
#endif
}
-void ac_cleanup(
- #if HOTENDS > 1
- const uint8_t old_tool_index
- #endif
-) {
- #if ENABLED(DELTA_HOME_TO_SAFE_ZONE)
- do_blocking_move_to_z(delta_clip_start_height);
- #endif
- #if HAS_BED_PROBE
- probe.stow();
- #endif
+void ac_cleanup(TERN_(HAS_MULTI_HOTEND, const uint8_t old_tool_index)) {
+ TERN_(DELTA_HOME_TO_SAFE_ZONE, do_blocking_move_to_z(delta_clip_start_height));
+ TERN_(HAS_BED_PROBE, probe.stow());
restore_feedrate_and_scaling();
- #if HOTENDS > 1
- tool_change(old_tool_index, true);
- #endif
+ TERN_(HAS_MULTI_HOTEND, tool_change(old_tool_index, true));
}
void print_signed_float(PGM_P const prefix, const float &f) {
@@ -465,7 +448,7 @@ void GcodeSuite::G33() {
}
// Report settings
- PGM_P checkingac = PSTR("Checking... AC");
+ PGM_P const checkingac = PSTR("Checking... AC");
serialprintPGM(checkingac);
if (verbose_level == 0) SERIAL_ECHOPGM(" (DRY-RUN)");
SERIAL_EOL();
@@ -488,7 +471,7 @@ void GcodeSuite::G33() {
zero_std_dev_old = zero_std_dev;
if (!probe_calibration_points(z_at_pt, probe_points, towers_set, stow_after_each)) {
SERIAL_ECHOLNPGM("Correct delta settings with M665 and M666");
- return AC_CLEANUP();
+ return ac_cleanup(TERN_(HAS_MULTI_HOTEND, old_tool_index));
}
zero_std_dev = std_dev_points(z_at_pt, _0p_calibration, _1p_calibration, _4p_calibration, _4p_opposite_points);
@@ -641,7 +624,7 @@ void GcodeSuite::G33() {
}
}
else { // dry run
- PGM_P enddryrun = PSTR("End DRY-RUN");
+ PGM_P const enddryrun = PSTR("End DRY-RUN");
serialprintPGM(enddryrun);
SERIAL_ECHO_SP(35);
SERIAL_ECHOLNPAIR_F("std dev:", zero_std_dev, 3);
@@ -659,7 +642,7 @@ void GcodeSuite::G33() {
}
while (((zero_std_dev < test_precision && iterations < 31) || iterations <= force_iterations) && zero_std_dev > calibration_precision);
- AC_CLEANUP();
+ ac_cleanup(TERN_(HAS_MULTI_HOTEND, old_tool_index));
}
#endif // DELTA_AUTO_CALIBRATION
diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp
index d1b828d07..3360dc050 100644
--- a/Marlin/src/gcode/calibrate/G34_M422.cpp
+++ b/Marlin/src/gcode/calibrate/G34_M422.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -32,7 +32,7 @@
#include "../../module/motion.h"
#include "../../module/probe.h"
-#if HOTENDS > 1
+#if HAS_MULTI_HOTEND
#include "../../module/tool_change.h"
#endif
@@ -47,17 +47,6 @@
#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE)
#include "../../core/debug_out.h"
-inline void set_all_z_lock(const bool lock) {
- stepper.set_z_lock(lock);
- stepper.set_z2_lock(lock);
- #if NUM_Z_STEPPER_DRIVERS >= 3
- stepper.set_z3_lock(lock);
- #if NUM_Z_STEPPER_DRIVERS >= 4
- stepper.set_z4_lock(lock);
- #endif
- #endif
-}
-
/**
* G34: Z-Stepper automatic alignment
*
@@ -67,10 +56,8 @@ inline void set_all_z_lock(const bool lock) {
* R points based on current probe offsets
*/
void GcodeSuite::G34() {
- if (DEBUGGING(LEVELING)) {
- DEBUG_ECHOLNPGM(">>> G34");
- log_machine_info();
- }
+ DEBUG_SECTION(log_G34, "G34", DEBUGGING(LEVELING));
+ if (DEBUGGING(LEVELING)) log_machine_info();
do { // break out on error
@@ -113,34 +100,24 @@ void GcodeSuite::G34() {
// Disable the leveling matrix before auto-aligning
#if HAS_LEVELING
- #if ENABLED(RESTORE_LEVELING_AFTER_G34)
- const bool leveling_was_active = planner.leveling_active;
- #endif
+ TERN_(RESTORE_LEVELING_AFTER_G34, const bool leveling_was_active = planner.leveling_active);
set_bed_leveling_enabled(false);
#endif
- #if ENABLED(CNC_WORKSPACE_PLANES)
- workspace_plane = PLANE_XY;
- #endif
+ TERN_(CNC_WORKSPACE_PLANES, workspace_plane = PLANE_XY);
// Always home with tool 0 active
- #if HOTENDS > 1
+ #if HAS_MULTI_HOTEND
const uint8_t old_tool_index = active_extruder;
tool_change(0, true);
#endif
- #if HAS_DUPLICATION_MODE
- extruder_duplication_enabled = false;
- #endif
+ TERN_(HAS_DUPLICATION_MODE, extruder_duplication_enabled = false);
- #if BOTH(BLTOUCH, BLTOUCH_HS_MODE)
- // In BLTOUCH HS mode, the probe travels in a deployed state.
- // Users of G34 might have a badly misaligned bed, so raise Z by the
- // length of the deployed pin (BLTOUCH stroke < 7mm)
- #define Z_BASIC_CLEARANCE Z_CLEARANCE_BETWEEN_PROBES + 7.0f
- #else
- #define Z_BASIC_CLEARANCE Z_CLEARANCE_BETWEEN_PROBES
- #endif
+ // In BLTOUCH HS mode, the probe travels in a deployed state.
+ // Users of G34 might have a badly misaligned bed, so raise Z by the
+ // length of the deployed pin (BLTOUCH stroke < 7mm)
+ #define Z_BASIC_CLEARANCE Z_CLEARANCE_BETWEEN_PROBES + 7.0f * BOTH(BLTOUCH, BLTOUCH_HS_MODE)
// Compute a worst-case clearance height to probe from. After the first
// iteration this will be re-calculated based on the actual bed position
@@ -315,11 +292,14 @@ void GcodeSuite::G34() {
// Check for less accuracy compared to last move
if (last_z_align_move[zstepper] < z_align_abs * 0.7f) {
SERIAL_ECHOLNPGM("Decreasing accuracy detected.");
+ if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(zstepper + 1), " last_z_align_move = ", last_z_align_move[zstepper]);
+ if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(zstepper + 1), " z_align_abs = ", z_align_abs);
adjustment_reverse = !adjustment_reverse;
}
- // Remember the alignment for the next iteration
- last_z_align_move[zstepper] = z_align_abs;
+ // Remember the alignment for the next iteration, but only if steppers move,
+ // otherwise it would be just zero (in case this stepper was at z_measured_min already)
+ if (z_align_abs > 0) last_z_align_move[zstepper] = z_align_abs;
#endif
// Stop early if all measured points achieve accuracy target
@@ -328,23 +308,15 @@ void GcodeSuite::G34() {
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(zstepper + 1), " corrected by ", z_align_move);
// Lock all steppers except one
- set_all_z_lock(true);
- switch (zstepper) {
- case 0: stepper.set_z_lock(false); break;
- case 1: stepper.set_z2_lock(false); break;
- #if NUM_Z_STEPPER_DRIVERS >= 3
- case 2: stepper.set_z3_lock(false); break;
- #endif
- #if NUM_Z_STEPPER_DRIVERS == 4
- case 3: stepper.set_z4_lock(false); break;
- #endif
- }
+ stepper.set_all_z_lock(true, zstepper);
#if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS)
// Decreasing accuracy was detected so move was inverted.
// Will match reversed Z steppers on dual steppers. Triple will need more work to map.
- if (adjustment_reverse)
+ if (adjustment_reverse) {
z_align_move = -z_align_move;
+ if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(zstepper + 1), " correction reversed to ", z_align_move);
+ }
#endif
// Do a move to correct part of the misalignment for the current stepper
@@ -352,7 +324,7 @@ void GcodeSuite::G34() {
} // for (zstepper)
// Back to normal stepper operations
- set_all_z_lock(false);
+ stepper.set_all_z_lock(false);
stepper.set_separate_multi_axis(false);
if (err_break) break;
@@ -386,17 +358,13 @@ void GcodeSuite::G34() {
#endif
// Restore the active tool after homing
- #if HOTENDS > 1
- tool_change(old_tool_index, DISABLED(PARKING_EXTRUDER)); // Fetch previous tool for parking extruder
- #endif
+ TERN_(HAS_MULTI_HOTEND, tool_change(old_tool_index, DISABLED(PARKING_EXTRUDER))); // Fetch previous tool for parking extruder
- #if HAS_LEVELING && ENABLED(RESTORE_LEVELING_AFTER_G34)
+ #if BOTH(HAS_LEVELING, RESTORE_LEVELING_AFTER_G34)
set_bed_leveling_enabled(leveling_was_active);
#endif
}while(0);
-
- if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("<<< G34");
}
/**
diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp
index 42c56fe51..0ef23d28f 100644
--- a/Marlin/src/gcode/calibrate/G425.cpp
+++ b/Marlin/src/gcode/calibrate/G425.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -51,7 +51,6 @@
#undef CALIBRATION_MEASURE_AT_TOP_EDGES
#endif
-
/**
* G425 backs away from the calibration object by various distances
* depending on the confidence level:
@@ -93,8 +92,6 @@ struct measurements_t {
xy_float_t nozzle_outer_dimension = nod;
};
-#define TEMPORARY_SOFT_ENDSTOP_STATE(enable) REMEMBER(tes, soft_endstops_enabled, enable);
-
#if ENABLED(BACKLASH_GCODE)
#define TEMPORARY_BACKLASH_CORRECTION(value) REMEMBER(tbst, backlash.correction, value)
#else
@@ -127,7 +124,7 @@ inline void park_above_object(measurements_t &m, const float uncertainty) {
calibration_move();
}
-#if HOTENDS > 1
+#if HAS_MULTI_HOTEND
inline void set_nozzle(measurements_t &m, const uint8_t extruder) {
if (extruder != active_extruder) {
park_above_object(m, CALIBRATION_MEASUREMENT_UNKNOWN);
@@ -256,7 +253,7 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t
#endif
}
- if (AXIS_CAN_CALIBRATE(X) && axis == X_AXIS || AXIS_CAN_CALIBRATE(Y) && axis == Y_AXIS) {
+ if ((AXIS_CAN_CALIBRATE(X) && axis == X_AXIS) || (AXIS_CAN_CALIBRATE(Y) && axis == Y_AXIS)) {
// Move to safe distance to the side of the calibration object
current_position[axis] = m.obj_center[axis] + (-dir) * (dimensions[axis] / 2 + m.nozzle_outer_dimension[axis] / 2 + uncertainty);
calibration_move();
@@ -286,37 +283,19 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
probe_side(m, uncertainty, TOP);
#endif
- #if ENABLED(CALIBRATION_MEASURE_RIGHT)
- probe_side(m, uncertainty, RIGHT, probe_top_at_edge);
- #endif
-
- #if ENABLED(CALIBRATION_MEASURE_FRONT)
- probe_side(m, uncertainty, FRONT, probe_top_at_edge);
- #endif
-
- #if ENABLED(CALIBRATION_MEASURE_LEFT)
- probe_side(m, uncertainty, LEFT, probe_top_at_edge);
- #endif
- #if ENABLED(CALIBRATION_MEASURE_BACK)
- probe_side(m, uncertainty, BACK, probe_top_at_edge);
- #endif
+ TERN_(CALIBRATION_MEASURE_RIGHT, probe_side(m, uncertainty, RIGHT, probe_top_at_edge));
+ TERN_(CALIBRATION_MEASURE_FRONT, probe_side(m, uncertainty, FRONT, probe_top_at_edge));
+ TERN_(CALIBRATION_MEASURE_LEFT, probe_side(m, uncertainty, LEFT, probe_top_at_edge));
+ TERN_(CALIBRATION_MEASURE_BACK, probe_side(m, uncertainty, BACK, probe_top_at_edge));
// Compute the measured center of the calibration object.
- #if HAS_X_CENTER
- m.obj_center.x = (m.obj_side[LEFT] + m.obj_side[RIGHT]) / 2;
- #endif
- #if HAS_Y_CENTER
- m.obj_center.y = (m.obj_side[FRONT] + m.obj_side[BACK]) / 2;
- #endif
+ TERN_(HAS_X_CENTER, m.obj_center.x = (m.obj_side[LEFT] + m.obj_side[RIGHT]) / 2);
+ TERN_(HAS_Y_CENTER, m.obj_center.y = (m.obj_side[FRONT] + m.obj_side[BACK]) / 2);
// Compute the outside diameter of the nozzle at the height
// at which it makes contact with the calibration object
- #if HAS_X_CENTER
- m.nozzle_outer_dimension.x = m.obj_side[RIGHT] - m.obj_side[LEFT] - dimensions.x;
- #endif
- #if HAS_Y_CENTER
- m.nozzle_outer_dimension.y = m.obj_side[BACK] - m.obj_side[FRONT] - dimensions.y;
- #endif
+ TERN_(HAS_X_CENTER, m.nozzle_outer_dimension.x = m.obj_side[RIGHT] - m.obj_side[LEFT] - dimensions.x);
+ TERN_(HAS_Y_CENTER, m.nozzle_outer_dimension.y = m.obj_side[BACK] - m.obj_side[FRONT] - dimensions.y);
park_above_object(m, uncertainty);
@@ -506,7 +485,7 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const
TEMPORARY_BACKLASH_CORRECTION(all_on);
TEMPORARY_BACKLASH_SMOOTHING(0.0f);
- #if HOTENDS > 1
+ #if HAS_MULTI_HOTEND
set_nozzle(m, extruder);
#else
UNUSED(extruder);
@@ -545,13 +524,9 @@ inline void calibrate_all_toolheads(measurements_t &m, const float uncertainty)
HOTEND_LOOP() calibrate_toolhead(m, uncertainty, e);
- #if HAS_HOTEND_OFFSET
- normalize_hotend_offsets();
- #endif
+ TERN_(HAS_HOTEND_OFFSET, normalize_hotend_offsets());
- #if HOTENDS > 1
- set_nozzle(m, 0);
- #endif
+ TERN_(HAS_MULTI_HOTEND, set_nozzle(m, 0));
}
/**
@@ -568,9 +543,7 @@ inline void calibrate_all_toolheads(measurements_t &m, const float uncertainty)
inline void calibrate_all() {
measurements_t m;
- #if HAS_HOTEND_OFFSET
- reset_hotend_offsets();
- #endif
+ TERN_(HAS_HOTEND_OFFSET, reset_hotend_offsets());
TEMPORARY_BACKLASH_CORRECTION(all_on);
TEMPORARY_BACKLASH_SMOOTHING(0.0f);
@@ -578,12 +551,10 @@ inline void calibrate_all() {
// Do a fast and rough calibration of the toolheads
calibrate_all_toolheads(m, CALIBRATION_MEASUREMENT_UNKNOWN);
- #if ENABLED(BACKLASH_GCODE)
- calibrate_backlash(m, CALIBRATION_MEASUREMENT_UNCERTAIN);
- #endif
+ TERN_(BACKLASH_GCODE, calibrate_backlash(m, CALIBRATION_MEASUREMENT_UNCERTAIN));
// Cycle the toolheads so the servos settle into their "natural" positions
- #if HOTENDS > 1
+ #if HAS_MULTI_HOTEND
HOTEND_LOOP() set_nozzle(m, e);
#endif
@@ -605,6 +576,11 @@ inline void calibrate_all() {
* no args - Perform entire calibration sequence (backlash + position on all toolheads)
*/
void GcodeSuite::G425() {
+
+ #ifdef CALIBRATION_SCRIPT_PRE
+ GcodeSuite::process_subcommands_now_P(PSTR(CALIBRATION_SCRIPT_PRE));
+ #endif
+
TEMPORARY_SOFT_ENDSTOP_STATE(false);
TEMPORARY_BED_LEVELING_STATE(false);
@@ -635,6 +611,10 @@ void GcodeSuite::G425() {
#endif
else
calibrate_all();
+
+ #ifdef CALIBRATION_SCRIPT_POST
+ GcodeSuite::process_subcommands_now_P(PSTR(CALIBRATION_SCRIPT_POST));
+ #endif
}
#endif // CALIBRATION_GCODE
diff --git a/Marlin/src/gcode/calibrate/G76_M871.cpp b/Marlin/src/gcode/calibrate/G76_M871.cpp
index c878f83a1..f2f53d213 100644
--- a/Marlin/src/gcode/calibrate/G76_M871.cpp
+++ b/Marlin/src/gcode/calibrate/G76_M871.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -103,13 +103,19 @@ void GcodeSuite::G76() {
return false;
};
- auto g76_probe = [](const xy_pos_t &xypos) {
- do_blocking_move_to_z(5.0); // Raise nozzle before probing
- const float measured_z = probe.probe_at_point(xypos, PROBE_PT_NONE, 0, false); // verbose=0, probe_relative=false
+ auto g76_probe = [](const TempSensorID sid, uint16_t &targ, const xy_pos_t &nozpos) {
+ do_z_clearance(5.0); // Raise nozzle before probing
+ const float measured_z = probe.probe_at_point(nozpos, PROBE_PT_STOW, 0, false); // verbose=0, probe_relative=false
if (isnan(measured_z))
SERIAL_ECHOLNPGM("!Received NAN. Aborting.");
- else
+ else {
SERIAL_ECHOLNPAIR_F("Measured: ", measured_z);
+ if (targ == cali_info_init[sid].start_temp)
+ temp_comp.prepare_new_calibration(measured_z);
+ else
+ temp_comp.push_back_new_measurement(sid, measured_z);
+ targ += cali_info_init[sid].temp_res;
+ }
return measured_z;
};
@@ -125,8 +131,9 @@ void GcodeSuite::G76() {
// Synchronize with planner
planner.synchronize();
- const xyz_pos_t parkpos = { temp_comp.park_point_x, temp_comp.park_point_y, temp_comp.park_point_z };
- const xy_pos_t ppos = { temp_comp.measure_point_x, temp_comp.measure_point_y };
+ const xyz_pos_t parkpos = temp_comp.park_point,
+ probe_pos_xyz = xyz_pos_t(temp_comp.measure_point) + xyz_pos_t({ 0.0f, 0.0f, PTC_PROBE_HEATING_OFFSET }),
+ noz_pos_xyz = probe_pos_xyz - xy_pos_t(probe.offset_xy); // Nozzle position based on probe position
if (do_bed_cal || do_probe_cal) {
// Ensure park position is reachable
@@ -135,7 +142,7 @@ void GcodeSuite::G76() {
SERIAL_ECHOLNPGM("!Park");
else {
// Ensure probe position is reachable
- reachable = probe.can_reach(ppos);
+ reachable = probe.can_reach(probe_pos_xyz);
if (!reachable) SERIAL_ECHOLNPGM("!Probe");
}
@@ -149,8 +156,6 @@ void GcodeSuite::G76() {
remember_feedrate_scaling_off();
- // Nozzle position based on probe position
- const xy_pos_t noz_pos = ppos - probe.offset_xy;
/******************************************
* Calibrate bed temperature offsets
@@ -159,9 +164,13 @@ void GcodeSuite::G76() {
// Report temperatures every second and handle heating timeouts
millis_t next_temp_report = millis() + 1000;
+ auto report_targets = [&](const uint16_t tb, const uint16_t tp) {
+ SERIAL_ECHOLNPAIR("Target Bed:", tb, " Probe:", tp);
+ };
+
if (do_bed_cal) {
- uint16_t target_bed = temp_comp.cali_info_init[TSI_BED].start_temp,
+ uint16_t target_bed = cali_info_init[TSI_BED].start_temp,
target_probe = temp_comp.bed_calib_probe_temp;
SERIAL_ECHOLNPGM("Waiting for cooling.");
@@ -169,40 +178,30 @@ void GcodeSuite::G76() {
report_temps(next_temp_report);
// Disable leveling so it won't mess with us
- #if HAS_LEVELING
- set_bed_leveling_enabled(false);
- #endif
+ TERN_(HAS_LEVELING, set_bed_leveling_enabled(false));
for (;;) {
thermalManager.setTargetBed(target_bed);
- SERIAL_ECHOLNPAIR("Target Bed:", target_bed, " Probe:", target_probe);
+ report_targets(target_bed, target_probe);
// Park nozzle
do_blocking_move_to(parkpos);
// Wait for heatbed to reach target temp and probe to cool below target temp
- if (wait_for_temps(target_bed, target_probe, next_temp_report, millis() + 900UL * 1000UL)) {
+ if (wait_for_temps(target_bed, target_probe, next_temp_report, millis() + MIN_TO_MS(15))) {
SERIAL_ECHOLNPGM("!Bed heating timeout.");
break;
}
// Move the nozzle to the probing point and wait for the probe to reach target temp
- do_blocking_move_to_xy(noz_pos);
+ do_blocking_move_to(noz_pos_xyz);
SERIAL_ECHOLNPGM("Waiting for probe heating.");
while (thermalManager.degProbe() < target_probe)
report_temps(next_temp_report);
- const float measured_z = g76_probe(noz_pos);
- if (isnan(measured_z)) break;
-
- if (target_bed == temp_comp.cali_info_init[TSI_BED].start_temp)
- temp_comp.prepare_new_calibration(measured_z);
- else
- temp_comp.push_back_new_measurement(TSI_BED, measured_z);
-
- target_bed += temp_comp.cali_info_init[TSI_BED].temp_res;
- if (target_bed > temp_comp.max_bed_temp) break;
+ const float measured_z = g76_probe(TSI_BED, target_bed, noz_pos_xyz);
+ if (isnan(measured_z) || target_bed > BED_MAX_TARGET) break;
}
SERIAL_ECHOLNPAIR("Retrieved measurements: ", temp_comp.get_index());
@@ -213,9 +212,7 @@ void GcodeSuite::G76() {
// Cleanup
thermalManager.setTargetBed(0);
- #if HAS_LEVELING
- set_bed_leveling_enabled(true);
- #endif
+ TERN_(HAS_LEVELING, set_bed_leveling_enabled(true));
} // do_bed_cal
/********************************************
@@ -231,20 +228,20 @@ void GcodeSuite::G76() {
const uint16_t target_bed = temp_comp.probe_calib_bed_temp;
thermalManager.setTargetBed(target_bed);
- uint16_t target_probe = temp_comp.cali_info_init[TSI_PROBE].start_temp;
+ uint16_t target_probe = cali_info_init[TSI_PROBE].start_temp;
+
+ report_targets(target_bed, target_probe);
// Wait for heatbed to reach target temp and probe to cool below target temp
wait_for_temps(target_bed, target_probe, next_temp_report);
// Disable leveling so it won't mess with us
- #if HAS_LEVELING
- set_bed_leveling_enabled(false);
- #endif
+ TERN_(HAS_LEVELING, set_bed_leveling_enabled(false));
bool timeout = false;
for (;;) {
// Move probe to probing point and wait for it to reach target temperature
- do_blocking_move_to_xy(noz_pos);
+ do_blocking_move_to(noz_pos_xyz);
SERIAL_ECHOLNPAIR("Waiting for probe heating. Bed:", target_bed, " Probe:", target_probe);
const millis_t probe_timeout_ms = millis() + 900UL * 1000UL;
@@ -257,16 +254,8 @@ void GcodeSuite::G76() {
}
if (timeout) break;
- const float measured_z = g76_probe(noz_pos);
- if (isnan(measured_z)) break;
-
- if (target_probe == temp_comp.cali_info_init[TSI_PROBE].start_temp)
- temp_comp.prepare_new_calibration(measured_z);
- else
- temp_comp.push_back_new_measurement(TSI_PROBE, measured_z);
-
- target_probe += temp_comp.cali_info_init[TSI_PROBE].temp_res;
- if (target_probe > temp_comp.cali_info_init[TSI_PROBE].end_temp) break;
+ const float measured_z = g76_probe(TSI_PROBE, target_probe, noz_pos_xyz);
+ if (isnan(measured_z) || target_probe > cali_info_init[TSI_PROBE].end_temp) break;
}
SERIAL_ECHOLNPAIR("Retrieved measurements: ", temp_comp.get_index());
@@ -278,9 +267,7 @@ void GcodeSuite::G76() {
// Cleanup
thermalManager.setTargetBed(0);
- #if HAS_LEVELING
- set_bed_leveling_enabled(true);
- #endif
+ TERN_(HAS_LEVELING, set_bed_leveling_enabled(true));
SERIAL_ECHOLNPGM("Final compensation values:");
temp_comp.print_offsets();
diff --git a/Marlin/src/gcode/calibrate/M100.cpp b/Marlin/src/gcode/calibrate/M100.cpp
index 6b8a0de52..ea054125b 100644
--- a/Marlin/src/gcode/calibrate/M100.cpp
+++ b/Marlin/src/gcode/calibrate/M100.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -116,13 +116,18 @@
// Utility functions
//
-// Location of a variable on its stack frame. Returns a value above
-// the stack (once the function returns to the caller).
-char* top_of_stack() {
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wreturn-local-addr"
+
+// Location of a variable in its stack frame.
+// The returned address will be above the stack (after it returns).
+char *top_of_stack() {
char x;
return &x + 1; // x is pulled on return;
}
+#pragma GCC diagnostic pop
+
// Count the number of test bytes at the specified location.
inline int32_t count_test_bytes(const char * const start_free_memory) {
for (uint32_t i = 0; i < 32000; i++)
diff --git a/Marlin/src/gcode/calibrate/M12.cpp b/Marlin/src/gcode/calibrate/M12.cpp
index 26f15bb89..da2445437 100644
--- a/Marlin/src/gcode/calibrate/M12.cpp
+++ b/Marlin/src/gcode/calibrate/M12.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#include "../../inc/MarlinConfigPre.h"
@@ -28,9 +28,12 @@
#include "../../feature/closedloop.h"
void GcodeSuite::M12() {
+
planner.synchronize();
+
if (parser.seenval('S'))
- set_closedloop(parser.value_int()); // Force a CLC set
+ closedloop.set(parser.value_int()); // Force a CLC set
+
}
#endif
diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp
index 980152a4b..3e54186a5 100644
--- a/Marlin/src/gcode/calibrate/M425.cpp
+++ b/Marlin/src/gcode/calibrate/M425.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -46,8 +46,17 @@
void GcodeSuite::M425() {
bool noArgs = true;
+ auto axis_can_calibrate = [](const uint8_t a) {
+ switch (a) {
+ default:
+ case X_AXIS: return AXIS_CAN_CALIBRATE(X);
+ case Y_AXIS: return AXIS_CAN_CALIBRATE(Y);
+ case Z_AXIS: return AXIS_CAN_CALIBRATE(Z);
+ }
+ };
+
LOOP_XYZ(a) {
- if (CAN_CALIBRATE(a) && parser.seen(XYZ_CHAR(a))) {
+ if (AXIS_CAN_CALIBRATE(a) && parser.seen(XYZ_CHAR(a))) {
planner.synchronize();
backlash.distance_mm[a] = parser.has_value() ? parser.value_linear_units() : backlash.get_measurement(AxisEnum(a));
noArgs = false;
@@ -74,7 +83,7 @@ void GcodeSuite::M425() {
SERIAL_ECHOLNPGM("active:");
SERIAL_ECHOLNPAIR(" Correction Amount/Fade-out: F", backlash.get_correction(), " (F1.0 = full, F0.0 = none)");
SERIAL_ECHOPGM(" Backlash Distance (mm): ");
- LOOP_XYZ(a) if (CAN_CALIBRATE(a)) {
+ LOOP_XYZ(a) if (axis_can_calibrate(a)) {
SERIAL_CHAR(' ', XYZ_CHAR(a));
SERIAL_ECHO(backlash.distance_mm[a]);
SERIAL_EOL();
@@ -87,7 +96,7 @@ void GcodeSuite::M425() {
#if ENABLED(MEASURE_BACKLASH_WHEN_PROBING)
SERIAL_ECHOPGM(" Average measured backlash (mm):");
if (backlash.has_any_measurement()) {
- LOOP_XYZ(a) if (CAN_CALIBRATE(a) && backlash.has_measurement(AxisEnum(a))) {
+ LOOP_XYZ(a) if (axis_can_calibrate(a) && backlash.has_measurement(AxisEnum(a))) {
SERIAL_CHAR(' ', XYZ_CHAR(a));
SERIAL_ECHO(backlash.get_measurement(AxisEnum(a)));
}
diff --git a/Marlin/src/gcode/calibrate/M48.cpp b/Marlin/src/gcode/calibrate/M48.cpp
index c1e8b0e9f..47c72eece 100644
--- a/Marlin/src/gcode/calibrate/M48.cpp
+++ b/Marlin/src/gcode/calibrate/M48.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -263,9 +263,7 @@ void GcodeSuite::M48() {
restore_feedrate_and_scaling();
// Re-enable bed level correction if it had been on
- #if HAS_LEVELING
- set_bed_leveling_enabled(was_enabled);
- #endif
+ TERN_(HAS_LEVELING, set_bed_leveling_enabled(was_enabled));
report_current_position();
}
diff --git a/Marlin/src/gcode/calibrate/M665.cpp b/Marlin/src/gcode/calibrate/M665.cpp
index 0436736b4..557204cc1 100644
--- a/Marlin/src/gcode/calibrate/M665.cpp
+++ b/Marlin/src/gcode/calibrate/M665.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -38,8 +38,11 @@
* R = delta radius
* S = segments per second
* X = Alpha (Tower 1) angle trim
- * Y = Beta (Tower 2) angle trim
+ * Y = Beta (Tower 2) angle trim
* Z = Gamma (Tower 3) angle trim
+ * A = Alpha (Tower 1) digonal rod trim
+ * B = Beta (Tower 2) digonal rod trim
+ * C = Gamma (Tower 3) digonal rod trim
*/
void GcodeSuite::M665() {
if (parser.seen('H')) delta_height = parser.value_linear_units();
@@ -49,6 +52,9 @@
if (parser.seen('X')) delta_tower_angle_trim.a = parser.value_float();
if (parser.seen('Y')) delta_tower_angle_trim.b = parser.value_float();
if (parser.seen('Z')) delta_tower_angle_trim.c = parser.value_float();
+ if (parser.seen('A')) delta_diagonal_rod_trim.a = parser.value_float();
+ if (parser.seen('B')) delta_diagonal_rod_trim.b = parser.value_float();
+ if (parser.seen('C')) delta_diagonal_rod_trim.c = parser.value_float();
recalc_delta_settings();
}
diff --git a/Marlin/src/gcode/calibrate/M666.cpp b/Marlin/src/gcode/calibrate/M666.cpp
index 721cbcfaa..e915aa8ff 100644
--- a/Marlin/src/gcode/calibrate/M666.cpp
+++ b/Marlin/src/gcode/calibrate/M666.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -38,7 +38,7 @@
* M666: Set delta endstop adjustment
*/
void GcodeSuite::M666() {
- if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM(">>> M666");
+ DEBUG_SECTION(log_M666, "M666", DEBUGGING(LEVELING));
LOOP_XYZ(i) {
if (parser.seen(XYZ_CHAR(i))) {
const float v = parser.value_linear_units();
@@ -46,7 +46,6 @@
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("delta_endstop_adj[", XYZ_CHAR(i), "] = ", delta_endstop_adj[i]);
}
}
- if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("<<< M666");
}
#elif HAS_EXTRA_ENDSTOPS
diff --git a/Marlin/src/gcode/calibrate/M852.cpp b/Marlin/src/gcode/calibrate/M852.cpp
index 865b03def..b60f41748 100644
--- a/Marlin/src/gcode/calibrate/M852.cpp
+++ b/Marlin/src/gcode/calibrate/M852.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp
index b9192198b..cb17fc45a 100644
--- a/Marlin/src/gcode/config/M200-M205.cpp
+++ b/Marlin/src/gcode/config/M200-M205.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -30,21 +30,42 @@
* M200: Set filament diameter and set E axis units to cubic units
*
* T - Optional extruder number. Current extruder if omitted.
- * D - Diameter of the filament. Use "D0" to switch back to linear units on the E axis.
+ * D - Set filament diameter and enable. D0 disables volumetric.
+ * S - Turn volumetric ON or OFF.
+ * L - Volumetric extruder limit (in mm^3/sec). L0 disables the limit.
*/
void GcodeSuite::M200() {
const int8_t target_extruder = get_target_extruder_from_command();
if (target_extruder < 0) return;
- if (parser.seen('D')) {
- // setting any extruder filament size disables volumetric on the assumption that
- // slicers either generate in extruder values as cubic mm or as as filament feeds
- // for all extruders
+ bool vol_enable = parser.volumetric_enabled,
+ can_enable = true;
+
+ if (parser.seenval('D')) {
const float dval = parser.value_linear_units();
- if ( (parser.volumetric_enabled = (dval != 0)) )
+ if (dval) { // Set filament size for volumetric calculation
planner.set_filament_size(target_extruder, dval);
+ vol_enable = true; // Dn = enable for compatibility
+ }
+ else
+ can_enable = false; // D0 = disable for compatibility
}
+
+ // Enable or disable with S1 / S0
+ parser.volumetric_enabled = can_enable && parser.boolval('S', vol_enable);
+
+ #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT)
+ if (parser.seenval('L')) {
+ // Set volumetric limit (in mm^3/sec)
+ const float lval = parser.value_float();
+ if (WITHIN(lval, 0, 20))
+ planner.set_volumetric_extruder_limit(target_extruder, lval);
+ else
+ SERIAL_ECHOLNPGM("?L value out of range (0-20).");
+ }
+ #endif
+
planner.calculate_volumetric_multipliers();
}
@@ -60,6 +81,11 @@ void GcodeSuite::M201() {
const int8_t target_extruder = get_target_extruder_from_command();
if (target_extruder < 0) return;
+ #ifdef XY_FREQUENCY_LIMIT
+ if (parser.seenval('F')) planner.set_frequency_limit(parser.value_byte());
+ if (parser.seenval('G')) planner.xy_freq_min_speed_factor = constrain(parser.value_float(), 1, 100) / 100;
+ #endif
+
LOOP_XYZE(i) {
if (parser.seen(axis_codes[i])) {
const uint8_t a = (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i);
@@ -121,7 +147,7 @@ void GcodeSuite::M204() {
* J = Junction Deviation (mm) (If not using CLASSIC_JERK)
*/
void GcodeSuite::M205() {
- #if DISABLED(CLASSIC_JERK)
+ #if HAS_JUNCTION_DEVIATION
#define J_PARAM "J"
#else
#define J_PARAM
@@ -137,14 +163,12 @@ void GcodeSuite::M205() {
if (parser.seen('B')) planner.settings.min_segment_time_us = parser.value_ulong();
if (parser.seen('S')) planner.settings.min_feedrate_mm_s = parser.value_linear_units();
if (parser.seen('T')) planner.settings.min_travel_feedrate_mm_s = parser.value_linear_units();
- #if DISABLED(CLASSIC_JERK)
+ #if HAS_JUNCTION_DEVIATION
if (parser.seen('J')) {
const float junc_dev = parser.value_linear_units();
if (WITHIN(junc_dev, 0.01f, 0.3f)) {
planner.junction_deviation_mm = junc_dev;
- #if ENABLED(LIN_ADVANCE)
- planner.recalculate_max_e_jerk();
- #endif
+ TERN_(LIN_ADVANCE, planner.recalculate_max_e_jerk());
}
else
SERIAL_ERROR_MSG("?J out of range (0.01 to 0.3)");
diff --git a/Marlin/src/gcode/config/M217.cpp b/Marlin/src/gcode/config/M217.cpp
index 44e69c429..0d049ede1 100644
--- a/Marlin/src/gcode/config/M217.cpp
+++ b/Marlin/src/gcode/config/M217.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -27,6 +27,10 @@
#include "../gcode.h"
#include "../../module/tool_change.h"
+#if ENABLED(TOOLCHANGE_MIGRATION_FEATURE)
+ #include "../../module/motion.h"
+#endif
+
#include "../../MarlinCore.h" // for SP_X_STR, etc.
extern const char SP_X_STR[], SP_Y_STR[], SP_Z_STR[];
@@ -36,15 +40,29 @@ void M217_report(const bool eeprom=false) {
#if ENABLED(TOOLCHANGE_FILAMENT_SWAP)
serialprintPGM(eeprom ? PSTR(" M217") : PSTR("Toolchange:"));
SERIAL_ECHOPAIR(" S", LINEAR_UNIT(toolchange_settings.swap_length));
- SERIAL_ECHOPAIR_P(SP_E_STR, LINEAR_UNIT(toolchange_settings.extra_prime));
- SERIAL_ECHOPAIR_P(SP_P_STR, LINEAR_UNIT(toolchange_settings.prime_speed));
- SERIAL_ECHOPAIR(" R", LINEAR_UNIT(toolchange_settings.retract_speed));
+ SERIAL_ECHOPAIR_P(SP_B_STR, LINEAR_UNIT(toolchange_settings.extra_resume),
+ SP_E_STR, LINEAR_UNIT(toolchange_settings.extra_prime),
+ SP_P_STR, LINEAR_UNIT(toolchange_settings.prime_speed));
+ SERIAL_ECHOPAIR(" R", LINEAR_UNIT(toolchange_settings.retract_speed),
+ " U", LINEAR_UNIT(toolchange_settings.unretract_speed),
+ " F", toolchange_settings.fan_speed,
+ " G", toolchange_settings.fan_time);
+
+ #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE)
+ SERIAL_ECHOPAIR(" A", int(migration.automode));
+ SERIAL_ECHOPAIR(" L", LINEAR_UNIT(migration.last));
+ #endif
#if ENABLED(TOOLCHANGE_PARK)
+ SERIAL_ECHOPAIR(" W", LINEAR_UNIT(toolchange_settings.enable_park));
SERIAL_ECHOPAIR_P(SP_X_STR, LINEAR_UNIT(toolchange_settings.change_point.x));
SERIAL_ECHOPAIR_P(SP_Y_STR, LINEAR_UNIT(toolchange_settings.change_point.y));
#endif
+ #if ENABLED(TOOLCHANGE_FS_PRIME_FIRST_USED)
+ SERIAL_ECHOPAIR(" V", LINEAR_UNIT(enable_first_prime));
+ #endif
+
#else
UNUSED(eeprom);
@@ -58,48 +76,98 @@ void M217_report(const bool eeprom=false) {
/**
* M217 - Set SINGLENOZZLE toolchange parameters
*
+ * // Tool change command
+ * Q Prime active tool and exit
+ *
+ * // Tool change settings
* S[linear] Swap length
- * E[linear] Purge length
+ * B[linear] Extra Swap length
+ * E[linear] Prime length
* P[linear/m] Prime speed
* R[linear/m] Retract speed
+ * U[linear/m] UnRetract speed
+ * V[linear] 0/1 Enable auto prime first extruder used
+ * W[linear] 0/1 Enable park & Z Raise
* X[linear] Park X (Requires TOOLCHANGE_PARK)
* Y[linear] Park Y (Requires TOOLCHANGE_PARK)
* Z[linear] Z Raise
+ * F[linear] Fan Speed 0-255
+ * G[linear/s] Fan time
+ *
+ * Tool migration settings
+ * A[0|1] Enable auto-migration on runout
+ * L[index] Last extruder to use for auto-migration
+ *
+ * Tool migration command
+ * T[index] Migrate to next extruder or the given extruder
*/
void GcodeSuite::M217() {
- #define SPR_PARAM
- #define XY_PARAM
-
#if ENABLED(TOOLCHANGE_FILAMENT_SWAP)
- #undef SPR_PARAM
- #define SPR_PARAM "SPRE"
+ static constexpr float max_extrude = TERN(PREVENT_LENGTHY_EXTRUDE, EXTRUDE_MAXLENGTH, 500);
- static constexpr float max_extrude =
- #if ENABLED(PREVENT_LENGTHY_EXTRUDE)
- EXTRUDE_MAXLENGTH
- #else
- 500
- #endif
- ;
+ if (parser.seen('Q')) { tool_change_prime(); return; }
if (parser.seenval('S')) { const float v = parser.value_linear_units(); toolchange_settings.swap_length = constrain(v, 0, max_extrude); }
+ if (parser.seenval('B')) { const float v = parser.value_linear_units(); toolchange_settings.extra_resume = constrain(v, -10, 10); }
if (parser.seenval('E')) { const float v = parser.value_linear_units(); toolchange_settings.extra_prime = constrain(v, 0, max_extrude); }
if (parser.seenval('P')) { const int16_t v = parser.value_linear_units(); toolchange_settings.prime_speed = constrain(v, 10, 5400); }
if (parser.seenval('R')) { const int16_t v = parser.value_linear_units(); toolchange_settings.retract_speed = constrain(v, 10, 5400); }
+ if (parser.seenval('U')) { const int16_t v = parser.value_linear_units(); toolchange_settings.unretract_speed = constrain(v, 10, 5400); }
+ #if TOOLCHANGE_FS_FAN >= 0 && HAS_FAN
+ if (parser.seenval('F')) { const int16_t v = parser.value_linear_units(); toolchange_settings.fan_speed = constrain(v, 0, 255); }
+ if (parser.seenval('G')) { const int16_t v = parser.value_linear_units(); toolchange_settings.fan_time = constrain(v, 1, 30); }
+ #endif
+ #endif
+
+ #if ENABLED(TOOLCHANGE_FS_PRIME_FIRST_USED)
+ if (parser.seenval('V')) { enable_first_prime = parser.value_linear_units(); }
#endif
#if ENABLED(TOOLCHANGE_PARK)
- #undef XY_PARAM
- #define XY_PARAM "XY"
- if (parser.seenval('X')) { toolchange_settings.change_point.x = parser.value_linear_units(); }
- if (parser.seenval('Y')) { toolchange_settings.change_point.y = parser.value_linear_units(); }
+ if (parser.seenval('W')) { toolchange_settings.enable_park = parser.value_linear_units(); }
+ if (parser.seenval('X')) { const int16_t v = parser.value_linear_units(); toolchange_settings.change_point.x = constrain(v, X_MIN_POS, X_MAX_POS); }
+ if (parser.seenval('Y')) { const int16_t v = parser.value_linear_units(); toolchange_settings.change_point.y = constrain(v, Y_MIN_POS, Y_MAX_POS); }
#endif
if (parser.seenval('Z')) { toolchange_settings.z_raise = parser.value_linear_units(); }
- if (!parser.seen(SPR_PARAM XY_PARAM "Z")) M217_report();
+ #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE)
+ migration.target = 0; // 0 = disabled
+
+ if (parser.seenval('L')) { // Last
+ const int16_t lval = parser.value_int();
+ if (WITHIN(lval, 0, EXTRUDERS - 1)) {
+ migration.last = lval;
+ migration.automode = (active_extruder < migration.last);
+ }
+ }
+
+ if (parser.seen('A')) // Auto on/off
+ migration.automode = parser.value_bool();
+
+ if (parser.seen('T')) { // Migrate now
+ if (parser.has_value()) {
+ const int16_t tval = parser.value_int();
+ if (WITHIN(tval, 0, EXTRUDERS - 1) && tval != active_extruder) {
+ migration.target = tval + 1;
+ extruder_migration();
+ migration.target = 0; // disable
+ return;
+ }
+ else
+ migration.target = 0; // disable
+ }
+ else {
+ extruder_migration();
+ return;
+ }
+ }
+
+ #endif
+
+ M217_report();
}
#endif // EXTRUDERS > 1
diff --git a/Marlin/src/gcode/config/M218.cpp b/Marlin/src/gcode/config/M218.cpp
index 5c7d5eac7..7701320e9 100644
--- a/Marlin/src/gcode/config/M218.cpp
+++ b/Marlin/src/gcode/config/M218.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/config/M220.cpp b/Marlin/src/gcode/config/M220.cpp
index f24c11e23..1bec6a778 100644
--- a/Marlin/src/gcode/config/M220.cpp
+++ b/Marlin/src/gcode/config/M220.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/config/M221.cpp b/Marlin/src/gcode/config/M221.cpp
index 8522b544f..7ba22d190 100644
--- a/Marlin/src/gcode/config/M221.cpp
+++ b/Marlin/src/gcode/config/M221.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -33,10 +33,8 @@ void GcodeSuite::M221() {
const int8_t target_extruder = get_target_extruder_from_command();
if (target_extruder < 0) return;
- if (parser.seenval('S')) {
- planner.flow_percentage[target_extruder] = parser.value_int();
- planner.refresh_e_factor(target_extruder);
- }
+ if (parser.seenval('S'))
+ planner.set_flow(target_extruder, parser.value_int());
else {
SERIAL_ECHO_START();
SERIAL_CHAR('E', '0' + target_extruder);
diff --git a/Marlin/src/gcode/config/M281.cpp b/Marlin/src/gcode/config/M281.cpp
index e925cd5b1..018ca1c09 100644
--- a/Marlin/src/gcode/config/M281.cpp
+++ b/Marlin/src/gcode/config/M281.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#include "../../inc/MarlinConfig.h"
@@ -26,6 +26,13 @@
#include "../gcode.h"
#include "../../module/servo.h"
+/**
+ * M281 - Edit / Report Servo Angles
+ *
+ * P - Servo to update
+ * L - Deploy Angle
+ * U - Stowed Angle
+ */
void GcodeSuite::M281() {
if (!parser.seenval('P')) return;
const int servo_index = parser.value_int();
diff --git a/Marlin/src/gcode/config/M301.cpp b/Marlin/src/gcode/config/M301.cpp
index 54d32c865..7b3f57608 100644
--- a/Marlin/src/gcode/config/M301.cpp
+++ b/Marlin/src/gcode/config/M301.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -30,6 +30,8 @@
/**
* M301: Set PID parameters P I D (and optionally C, L)
*
+ * E[extruder] Default: 0
+ *
* P[float] Kp term
* I[float] Ki term (unscaled)
* D[float] Kd term (unscaled)
@@ -65,6 +67,7 @@ void GcodeSuite::M301() {
#endif
thermalManager.updatePID();
+
SERIAL_ECHO_START();
#if ENABLED(PID_PARAMS_PER_HOTEND)
SERIAL_ECHOPAIR(" e:", e); // specify extruder in serial output
diff --git a/Marlin/src/gcode/config/M302.cpp b/Marlin/src/gcode/config/M302.cpp
index aa178ea20..14fbd9f57 100644
--- a/Marlin/src/gcode/config/M302.cpp
+++ b/Marlin/src/gcode/config/M302.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/config/M304.cpp b/Marlin/src/gcode/config/M304.cpp
index 2a8514942..10739be3f 100644
--- a/Marlin/src/gcode/config/M304.cpp
+++ b/Marlin/src/gcode/config/M304.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/config/M305.cpp b/Marlin/src/gcode/config/M305.cpp
index d45e18f1b..3e7206aee 100644
--- a/Marlin/src/gcode/config/M305.cpp
+++ b/Marlin/src/gcode/config/M305.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp
index baf5efb13..1e7374542 100644
--- a/Marlin/src/gcode/config/M43.cpp
+++ b/Marlin/src/gcode/config/M43.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -340,12 +340,8 @@ void GcodeSuite::M43() {
#if HAS_RESUME_CONTINUE
KEEPALIVE_STATE(PAUSED_FOR_USER);
wait_for_user = true;
- #if ENABLED(HOST_PROMPT_SUPPORT)
- host_prompt_do(PROMPT_USER_CONTINUE, PSTR("M43 Wait Called"), CONTINUE_STR);
- #endif
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onUserConfirmRequired_P(PSTR("M43 Wait Called"));
- #endif
+ TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("M43 Wait Called"), CONTINUE_STR));
+ TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("M43 Wait Called")));
#endif
for (;;) {
@@ -366,9 +362,7 @@ void GcodeSuite::M43() {
}
}
- #if HAS_RESUME_CONTINUE
- if (!wait_for_user) break;
- #endif
+ if (TERN0(HAS_RESUME_CONTINUE, !wait_for_user)) break;
safe_delay(200);
}
diff --git a/Marlin/src/gcode/config/M540.cpp b/Marlin/src/gcode/config/M540.cpp
index a8ec628d5..54d52f3a3 100644
--- a/Marlin/src/gcode/config/M540.cpp
+++ b/Marlin/src/gcode/config/M540.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/config/M575.cpp b/Marlin/src/gcode/config/M575.cpp
index 947af14e3..4144c366d 100644
--- a/Marlin/src/gcode/config/M575.cpp
+++ b/Marlin/src/gcode/config/M575.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -42,7 +42,7 @@ void GcodeSuite::M575() {
if (set0) {
SERIAL_ECHO_START();
SERIAL_ECHOLNPAIR(" Serial "
- #if NUM_SERIAL > 1
+ #if HAS_MULTI_SERIAL
, '0',
#else
"0"
@@ -50,7 +50,7 @@ void GcodeSuite::M575() {
" baud rate set to ", baud
);
}
- #if NUM_SERIAL > 1
+ #if HAS_MULTI_SERIAL
const bool set1 = (port == -99 || port == 1);
if (set1) {
SERIAL_ECHO_START();
@@ -62,7 +62,7 @@ void GcodeSuite::M575() {
if (set0) { MYSERIAL0.end(); MYSERIAL0.begin(baud); }
- #if NUM_SERIAL > 1
+ #if HAS_MULTI_SERIAL
if (set1) { MYSERIAL1.end(); MYSERIAL1.begin(baud); }
#endif
diff --git a/Marlin/src/gcode/config/M672.cpp b/Marlin/src/gcode/config/M672.cpp
index cc160bde6..58dc27177 100644
--- a/Marlin/src/gcode/config/M672.cpp
+++ b/Marlin/src/gcode/config/M672.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -51,8 +51,8 @@
* Marlin: M672 R
*/
-#define M672_PROGBYTE 105 // magic byte to start programming custom sensitivity
-#define M672_ERASEBYTE 131 // magic byte to clear custom sensitivity
+#define M672_PROGBYTE 105 // magic byte to start programming custom sensitivity
+#define M672_ERASEBYTE 131 // magic byte to clear custom sensitivity
//
// Smart Effector byte send protocol:
diff --git a/Marlin/src/gcode/config/M92.cpp b/Marlin/src/gcode/config/M92.cpp
index bc86ff4d3..0a7d52b63 100644
--- a/Marlin/src/gcode/config/M92.cpp
+++ b/Marlin/src/gcode/config/M92.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -105,7 +105,7 @@ void GcodeSuite::M92() {
if (wanted) {
const float best = uint16_t(wanted / z_full_step_mm) * z_full_step_mm;
SERIAL_ECHOPAIR(", best:[", best);
- if (best != wanted) { SERIAL_CHAR(','); SERIAL_ECHO(best + z_full_step_mm); }
+ if (best != wanted) { SERIAL_CHAR(','); SERIAL_DECIMAL(best + z_full_step_mm); }
SERIAL_CHAR(']');
}
SERIAL_ECHOLNPGM(" }");
diff --git a/Marlin/src/gcode/control/M108_M112_M410.cpp b/Marlin/src/gcode/control/M108_M112_M410.cpp
index cb4220507..df145d5d1 100644
--- a/Marlin/src/gcode/control/M108_M112_M410.cpp
+++ b/Marlin/src/gcode/control/M108_M112_M410.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -31,9 +31,7 @@
* M108: Stop the waiting for heaters in M109, M190, M303. Does not affect the target temperature.
*/
void GcodeSuite::M108() {
- #if HAS_RESUME_CONTINUE
- wait_for_user = false;
- #endif
+ TERN_(HAS_RESUME_CONTINUE, wait_for_user = false);
wait_for_heatup = false;
}
diff --git a/Marlin/src/gcode/control/M111.cpp b/Marlin/src/gcode/control/M111.cpp
index 20ed44fb2..e31c3e2fb 100644
--- a/Marlin/src/gcode/control/M111.cpp
+++ b/Marlin/src/gcode/control/M111.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -28,21 +28,18 @@
void GcodeSuite::M111() {
if (parser.seen('S')) marlin_debug_flags = parser.byteval('S');
- static const char str_debug_1[] PROGMEM = STR_DEBUG_ECHO,
- str_debug_2[] PROGMEM = STR_DEBUG_INFO,
- str_debug_4[] PROGMEM = STR_DEBUG_ERRORS,
- str_debug_8[] PROGMEM = STR_DEBUG_DRYRUN,
- str_debug_16[] PROGMEM = STR_DEBUG_COMMUNICATION
- #if ENABLED(DEBUG_LEVELING_FEATURE)
- , str_debug_lvl[] PROGMEM = STR_DEBUG_LEVELING
- #endif
- ;
+ static PGMSTR(str_debug_1, STR_DEBUG_ECHO);
+ static PGMSTR(str_debug_2, STR_DEBUG_INFO);
+ static PGMSTR(str_debug_4, STR_DEBUG_ERRORS);
+ static PGMSTR(str_debug_8, STR_DEBUG_DRYRUN);
+ static PGMSTR(str_debug_16, STR_DEBUG_COMMUNICATION);
+ #if ENABLED(DEBUG_LEVELING_FEATURE)
+ static PGMSTR(str_debug_lvl, STR_DEBUG_LEVELING);
+ #endif
static PGM_P const debug_strings[] PROGMEM = {
- str_debug_1, str_debug_2, str_debug_4, str_debug_8, str_debug_16
- #if ENABLED(DEBUG_LEVELING_FEATURE)
- , str_debug_lvl
- #endif
+ str_debug_1, str_debug_2, str_debug_4, str_debug_8, str_debug_16,
+ TERN_(DEBUG_LEVELING_FEATURE, str_debug_lvl)
};
SERIAL_ECHO_START();
diff --git a/Marlin/src/gcode/control/M120_M121.cpp b/Marlin/src/gcode/control/M120_M121.cpp
index b25834cbd..570f2e935 100644
--- a/Marlin/src/gcode/control/M120_M121.cpp
+++ b/Marlin/src/gcode/control/M120_M121.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/control/M17_M18_M84.cpp b/Marlin/src/gcode/control/M17_M18_M84.cpp
index d69654a95..499feef71 100644
--- a/Marlin/src/gcode/control/M17_M18_M84.cpp
+++ b/Marlin/src/gcode/control/M17_M18_M84.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -25,7 +25,7 @@
#include "../../lcd/ultralcd.h"
#include "../../module/stepper.h"
-#if BOTH(AUTO_BED_LEVELING_UBL, ULTRA_LCD)
+#if ENABLED(AUTO_BED_LEVELING_UBL)
#include "../../feature/bedlevel/bedlevel.h"
#endif
@@ -37,9 +37,7 @@ void GcodeSuite::M17() {
if (parser.seen('X')) ENABLE_AXIS_X();
if (parser.seen('Y')) ENABLE_AXIS_Y();
if (parser.seen('Z')) ENABLE_AXIS_Z();
- #if HAS_E_STEPPER_ENABLE
- if (parser.seen('E')) enable_e_steppers();
- #endif
+ if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen('E'))) enable_e_steppers();
}
else {
LCD_MESSAGEPGM(MSG_NO_MOVE);
@@ -52,6 +50,7 @@ void GcodeSuite::M17() {
*/
void GcodeSuite::M18_M84() {
if (parser.seenval('S')) {
+ reset_stepper_timeout();
stepper_inactive_time = parser.value_millis_from_seconds();
}
else {
@@ -60,18 +59,11 @@ void GcodeSuite::M18_M84() {
if (parser.seen('X')) DISABLE_AXIS_X();
if (parser.seen('Y')) DISABLE_AXIS_Y();
if (parser.seen('Z')) DISABLE_AXIS_Z();
- #if HAS_E_STEPPER_ENABLE
- if (parser.seen('E')) disable_e_steppers();
- #endif
+ if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen('E'))) disable_e_steppers();
}
else
planner.finish_and_disable();
- #if HAS_LCD_MENU && ENABLED(AUTO_BED_LEVELING_UBL)
- if (ubl.lcd_map_control) {
- ubl.lcd_map_control = false;
- ui.defer_status_screen(false);
- }
- #endif
+ TERN_(AUTO_BED_LEVELING_UBL, ubl.steppers_were_disabled());
}
}
diff --git a/Marlin/src/gcode/control/M211.cpp b/Marlin/src/gcode/control/M211.cpp
index 3b0a928b8..ffad722f3 100644
--- a/Marlin/src/gcode/control/M211.cpp
+++ b/Marlin/src/gcode/control/M211.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/control/M226.cpp b/Marlin/src/gcode/control/M226.cpp
index 0dfbfd625..52e0e57a8 100644
--- a/Marlin/src/gcode/control/M226.cpp
+++ b/Marlin/src/gcode/control/M226.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/control/M280.cpp b/Marlin/src/gcode/control/M280.cpp
index 21a6c9890..6ccbb7bec 100644
--- a/Marlin/src/gcode/control/M280.cpp
+++ b/Marlin/src/gcode/control/M280.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/control/M3-M5.cpp b/Marlin/src/gcode/control/M3-M5.cpp
index 56e1e0e4e..1326c3066 100644
--- a/Marlin/src/gcode/control/M3-M5.cpp
+++ b/Marlin/src/gcode/control/M3-M5.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -30,20 +30,16 @@
/**
* Laser:
- *
* M3 - Laser ON/Power (Ramped power)
* M4 - Laser ON/Power (Continuous power)
*
- * S - Set power. S0 will turn the laser off.
- * O - Set power and OCR
- *
* Spindle:
- *
* M3 - Spindle ON (Clockwise)
* M4 - Spindle ON (Counter-clockwise)
*
- * S - Set power. S0 will turn the spindle off.
- * O - Set power and OCR
+ * Parameters:
+ * S - Set power. S0 will turn the spindle/laser off, except in relative mode.
+ * O - Set power and OCR (oscillator count register)
*
* If no PWM pin is defined then M3/M4 just turns it on.
*
@@ -70,31 +66,69 @@
* PWM duty cycle goes from 0 (off) to 255 (always on).
*/
void GcodeSuite::M3_M4(const bool is_M4) {
+ auto get_s_power = [] {
+ if (parser.seenval('S')) {
+ const float spwr = parser.value_float();
+ cutter.unitPower = TERN(SPINDLE_LASER_PWM,
+ cutter.power_to_range(cutter_power_t(round(spwr))),
+ spwr > 0 ? 255 : 0);
+ }
+ else
+ cutter.unitPower = cutter.cpwr_to_upwr(SPEED_POWER_STARTUP);
+ return cutter.unitPower;
+ };
- #if ENABLED(SPINDLE_FEATURE)
- planner.synchronize(); // Wait for movement to complete before changing power
+ #if ENABLED(LASER_POWER_INLINE)
+ if (parser.seen('I') == DISABLED(LASER_POWER_INLINE_INVERT)) {
+ // Laser power in inline mode
+ cutter.inline_direction(is_M4); // Should always be unused
+ #if ENABLED(SPINDLE_LASER_PWM)
+ if (parser.seen('O')) {
+ cutter.unitPower = cutter.power_to_range(parser.value_byte(), 0);
+ cutter.inline_ocr_power(cutter.unitPower); // The OCR is a value from 0 to 255 (uint8_t)
+ }
+ else
+ cutter.inline_power(cutter.upower_to_ocr(get_s_power()));
+ #else
+ cutter.set_inline_enabled(true);
+ #endif
+ return;
+ }
+ // Non-inline, standard case
+ cutter.inline_disable(); // Prevent future blocks re-setting the power
#endif
+ planner.synchronize(); // Wait for previous movement commands (G0/G0/G2/G3) to complete before changing power
cutter.set_direction(is_M4);
#if ENABLED(SPINDLE_LASER_PWM)
- if (parser.seenval('O'))
- cutter.set_ocr_power(parser.value_byte()); // The OCR is a value from 0 to 255 (uint8_t)
+ if (parser.seenval('O')) {
+ cutter.unitPower = cutter.power_to_range(parser.value_byte(), 0);
+ cutter.set_ocr_power(cutter.unitPower); // The OCR is a value from 0 to 255 (uint8_t)
+ }
else
- cutter.set_power(parser.intval('S', 255));
+ cutter.set_power(cutter.upower_to_ocr(get_s_power()));
#else
cutter.set_enabled(true);
#endif
+ cutter.menuPower = cutter.unitPower;
}
/**
- * M5 - Cutter OFF
+ * M5 - Cutter OFF (when moves are complete)
*/
void GcodeSuite::M5() {
- #if ENABLED(SPINDLE_FEATURE)
- planner.synchronize();
+ #if ENABLED(LASER_POWER_INLINE)
+ if (parser.seen('I') == DISABLED(LASER_POWER_INLINE_INVERT)) {
+ cutter.set_inline_enabled(false); // Laser power in inline mode
+ return;
+ }
+ // Non-inline, standard case
+ cutter.inline_disable(); // Prevent future blocks re-setting the power
#endif
+ planner.synchronize();
cutter.set_enabled(false);
+ cutter.menuPower = cutter.unitPower;
}
#endif // HAS_CUTTER
diff --git a/Marlin/src/gcode/control/M350_M351.cpp b/Marlin/src/gcode/control/M350_M351.cpp
index 54b29a21d..463bd2ad5 100644
--- a/Marlin/src/gcode/control/M350_M351.cpp
+++ b/Marlin/src/gcode/control/M350_M351.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/control/M380_M381.cpp b/Marlin/src/gcode/control/M380_M381.cpp
index 756021a59..3f5b25246 100644
--- a/Marlin/src/gcode/control/M380_M381.cpp
+++ b/Marlin/src/gcode/control/M380_M381.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/control/M400.cpp b/Marlin/src/gcode/control/M400.cpp
index 392629980..9a5ad4e9d 100644
--- a/Marlin/src/gcode/control/M400.cpp
+++ b/Marlin/src/gcode/control/M400.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/control/M42.cpp b/Marlin/src/gcode/control/M42.cpp
index 74625b031..c88113db4 100644
--- a/Marlin/src/gcode/control/M42.cpp
+++ b/Marlin/src/gcode/control/M42.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -24,7 +24,7 @@
#include "../../MarlinCore.h" // for pin_is_protected
#include "../../inc/MarlinConfig.h"
-#if FAN_COUNT > 0
+#if HAS_FAN
#include "../../module/temperature.h"
#endif
@@ -56,15 +56,14 @@ void GcodeSuite::M42() {
#ifdef INPUT_PULLDOWN
case 3: pinMode(pin, INPUT_PULLDOWN); break;
#endif
- default: SERIAL_ECHOLNPGM("Invalid Pin Mode");
+ default: SERIAL_ECHOLNPGM("Invalid Pin Mode"); return;
}
- return;
}
if (!parser.seenval('S')) return;
const byte pin_status = parser.value_byte();
- #if FAN_COUNT > 0
+ #if HAS_FAN
switch (pin) {
#if HAS_FAN0
case FAN0_PIN: thermalManager.fan_speed[0] = pin_status; return;
diff --git a/Marlin/src/gcode/control/M605.cpp b/Marlin/src/gcode/control/M605.cpp
index ab5efbbb4..5dc36428b 100644
--- a/Marlin/src/gcode/control/M605.cpp
+++ b/Marlin/src/gcode/control/M605.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -92,8 +92,10 @@
case DXC_AUTO_PARK_MODE:
break;
case DXC_DUPLICATION_MODE:
- if (parser.seen('X')) duplicate_extruder_x_offset = _MAX(parser.value_linear_units(), X2_MIN_POS - x_home_pos(0));
+ // Set the X offset, but no less than the safety gap
+ if (parser.seen('X')) duplicate_extruder_x_offset = _MAX(parser.value_linear_units(), (X2_MIN_POS) - (X1_MIN_POS));
if (parser.seen('R')) duplicate_extruder_temp_offset = parser.value_celsius_diff();
+ // Always switch back to tool 0
if (active_extruder != 0) tool_change(0);
break;
default:
diff --git a/Marlin/src/gcode/control/M7-M9.cpp b/Marlin/src/gcode/control/M7-M9.cpp
index 1fc8a93e2..a33e43288 100644
--- a/Marlin/src/gcode/control/M7-M9.cpp
+++ b/Marlin/src/gcode/control/M7-M9.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/control/M80_M81.cpp b/Marlin/src/gcode/control/M80_M81.cpp
index e8d9aa2fd..0dede7ea6 100644
--- a/Marlin/src/gcode/control/M80_M81.cpp
+++ b/Marlin/src/gcode/control/M80_M81.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -72,16 +72,15 @@
#endif
#if DISABLED(AUTO_POWER_CONTROL)
- delay(PSU_POWERUP_DELAY); // Wait for power to settle
+ safe_delay(PSU_POWERUP_DELAY);
restore_stepper_drivers();
+ TERN_(HAS_TRINAMIC_CONFIG, safe_delay(PSU_POWERUP_DELAY));
#endif
- #if HAS_LCD_MENU
- ui.reset_status();
- #endif
+ TERN_(HAS_LCD_MENU, ui.reset_status());
}
-#endif // ENABLED(PSU_CONTROL)
+#endif // PSU_CONTROL
/**
* M81: Turn off Power, including Power Supply, if there is one.
@@ -93,7 +92,7 @@ void GcodeSuite::M81() {
print_job_timer.stop();
planner.finish_and_disable();
- #if FAN_COUNT > 0
+ #if HAS_FAN
thermalManager.zero_fan_speeds();
#if ENABLED(PROBING_FANS_OFF)
thermalManager.fans_paused = false;
diff --git a/Marlin/src/gcode/control/M85.cpp b/Marlin/src/gcode/control/M85.cpp
index 1cdf49f60..9c8c02c59 100644
--- a/Marlin/src/gcode/control/M85.cpp
+++ b/Marlin/src/gcode/control/M85.cpp
@@ -16,12 +16,11 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#include "../gcode.h"
-#include "../../MarlinCore.h" // for max_inactive_time
/**
* M85: Set inactivity shutdown timer with parameter S. To disable set zero (default)
diff --git a/Marlin/src/gcode/control/M997.cpp b/Marlin/src/gcode/control/M997.cpp
index 1d9b12204..6c28d42f4 100644
--- a/Marlin/src/gcode/control/M997.cpp
+++ b/Marlin/src/gcode/control/M997.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/control/M999.cpp b/Marlin/src/gcode/control/M999.cpp
index 79cd5e185..53d74322a 100644
--- a/Marlin/src/gcode/control/M999.cpp
+++ b/Marlin/src/gcode/control/M999.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/control/T.cpp b/Marlin/src/gcode/control/T.cpp
index e6b3bb5d6..46cdfebf1 100644
--- a/Marlin/src/gcode/control/T.cpp
+++ b/Marlin/src/gcode/control/T.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -48,10 +48,11 @@
*/
void GcodeSuite::T(const uint8_t tool_index) {
- if (DEBUGGING(LEVELING)) {
- DEBUG_ECHOLNPAIR(">>> T(", tool_index, ")");
- DEBUG_POS("BEFORE", current_position);
- }
+ DEBUG_SECTION(log_T, "T", DEBUGGING(LEVELING));
+ if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("...(", tool_index, ")");
+
+ // Count this command as movement / activity
+ reset_stepper_timeout();
#if ENABLED(PRUSA_MMU2)
if (parser.string_arg) {
@@ -72,9 +73,4 @@ void GcodeSuite::T(const uint8_t tool_index) {
);
#endif
-
- if (DEBUGGING(LEVELING)) {
- DEBUG_POS("AFTER", current_position);
- DEBUG_ECHOLNPGM("<<< T()");
- }
}
diff --git a/Marlin/src/gcode/eeprom/M500-M504.cpp b/Marlin/src/gcode/eeprom/M500-M504.cpp
index 17f9ff71f..5aee68ba9 100644
--- a/Marlin/src/gcode/eeprom/M500-M504.cpp
+++ b/Marlin/src/gcode/eeprom/M500-M504.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -58,11 +58,47 @@ void GcodeSuite::M502() {
#endif // !DISABLE_M503
#if ENABLED(EEPROM_SETTINGS)
+
+ #if ENABLED(MARLIN_DEV_MODE)
+ #include "../../libs/hex_print_routines.h"
+ #endif
+
/**
* M504: Validate EEPROM Contents
*/
void GcodeSuite::M504() {
+ #if ENABLED(MARLIN_DEV_MODE)
+ const bool dowrite = parser.seenval('W');
+ if (dowrite || parser.seenval('R')) {
+ uint8_t val = 0;
+ int addr = parser.value_ushort();
+ if (dowrite) {
+ val = parser.byteval('V');
+ persistentStore.write_data(addr, &val);
+ SERIAL_ECHOLNPAIR("Wrote address ", addr, " with ", int(val));
+ }
+ else {
+ if (parser.seenval('T')) {
+ const int endaddr = parser.value_ushort();
+ while (addr <= endaddr) {
+ persistentStore.read_data(addr, &val);
+ SERIAL_ECHOLNPAIR("0x", hex_word(addr), ":", hex_byte(val));
+ addr++;
+ safe_delay(10);
+ }
+ SERIAL_EOL();
+ }
+ else {
+ persistentStore.read_data(addr, &val);
+ SERIAL_ECHOLNPAIR("Read address ", addr, " and got ", int(val));
+ }
+ }
+ return;
+ }
+ #endif
+
if (settings.validate())
SERIAL_ECHO_MSG("EEPROM OK");
}
+
#endif
diff --git a/Marlin/src/gcode/feature/L6470/M122.cpp b/Marlin/src/gcode/feature/L6470/M122.cpp
index ec5f9aea2..d2b7f7399 100644
--- a/Marlin/src/gcode/feature/L6470/M122.cpp
+++ b/Marlin/src/gcode/feature/L6470/M122.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/feature/L6470/M906.cpp b/Marlin/src/gcode/feature/L6470/M906.cpp
index 497fa7562..cd7fc3dcb 100644
--- a/Marlin/src/gcode/feature/L6470/M906.cpp
+++ b/Marlin/src/gcode/feature/L6470/M906.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/feature/L6470/M916-918.cpp b/Marlin/src/gcode/feature/L6470/M916-918.cpp
index a3eaf7b26..29efc06dd 100644
--- a/Marlin/src/gcode/feature/L6470/M916-918.cpp
+++ b/Marlin/src/gcode/feature/L6470/M916-918.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/feature/advance/M900.cpp b/Marlin/src/gcode/feature/advance/M900.cpp
index b3985401c..5c7155d7c 100644
--- a/Marlin/src/gcode/feature/advance/M900.cpp
+++ b/Marlin/src/gcode/feature/advance/M900.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -134,7 +134,7 @@ void GcodeSuite::M900() {
SERIAL_ECHOPGM("Advance K");
LOOP_L_N(i, EXTRUDERS) {
SERIAL_CHAR(' ', '0' + i, ':');
- SERIAL_ECHO(planner.extruder_advance_K[i]);
+ SERIAL_DECIMAL(planner.extruder_advance_K[i]);
}
SERIAL_EOL();
#endif
diff --git a/Marlin/src/gcode/feature/baricuda/M126-M129.cpp b/Marlin/src/gcode/feature/baricuda/M126-M129.cpp
index d96ee03af..edeba0d27 100644
--- a/Marlin/src/gcode/feature/baricuda/M126-M129.cpp
+++ b/Marlin/src/gcode/feature/baricuda/M126-M129.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/feature/camera/M240.cpp b/Marlin/src/gcode/feature/camera/M240.cpp
index 33ef9bf1a..9664ce152 100644
--- a/Marlin/src/gcode/feature/camera/M240.cpp
+++ b/Marlin/src/gcode/feature/camera/M240.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -100,9 +100,9 @@
* M240: Trigger a camera by...
*
* - CHDK : Emulate a Canon RC-1 with a configurable ON duration.
- * http://captain-slow.dk/2014/03/09/3d-printing-timelapses/
+ * https://captain-slow.dk/2014/03/09/3d-printing-timelapses/
* - PHOTOGRAPH_PIN : Pulse a digital pin 16 times.
- * See http://www.doc-diy.net/photo/rc-1_hacked/
+ * See https://www.doc-diy.net/photo/rc-1_hacked/
* - PHOTO_SWITCH_POSITION : Bump a physical switch with the X-carriage using a
* configured position, delay, and retract length.
*
diff --git a/Marlin/src/gcode/feature/cancel/M486.cpp b/Marlin/src/gcode/feature/cancel/M486.cpp
index 19216b2cb..1f14ae0fd 100644
--- a/Marlin/src/gcode/feature/cancel/M486.cpp
+++ b/Marlin/src/gcode/feature/cancel/M486.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/feature/caselight/M355.cpp b/Marlin/src/gcode/feature/caselight/M355.cpp
index ff793451b..4d2acd189 100644
--- a/Marlin/src/gcode/feature/caselight/M355.cpp
+++ b/Marlin/src/gcode/feature/caselight/M355.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/feature/clean/G12.cpp b/Marlin/src/gcode/feature/clean/G12.cpp
index 6d13a010b..fc99cc5c1 100644
--- a/Marlin/src/gcode/feature/clean/G12.cpp
+++ b/Marlin/src/gcode/feature/clean/G12.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -37,22 +37,32 @@
/**
* G12: Clean the nozzle
+ *
+ * E : 0=Never or 1=Always apply the "software endstop" limits
+ * P0 S : Stroke cleaning with S strokes
+ * P1 Sn T : Zigzag cleaning with S repeats and T zigzags
+ * P2 Sn R : Circle cleaning with S repeats and R radius
*/
void GcodeSuite::G12() {
// Don't allow nozzle cleaning without homing first
if (axis_unhomed_error()) return;
+ #ifdef WIPE_SEQUENCE_COMMANDS
+ if (!parser.seen_any()) {
+ gcode.process_subcommands_now_P(PSTR(WIPE_SEQUENCE_COMMANDS));
+ return;
+ }
+ #endif
+
const uint8_t pattern = parser.ushortval('P', 0),
strokes = parser.ushortval('S', NOZZLE_CLEAN_STROKES),
objects = parser.ushortval('T', NOZZLE_CLEAN_TRIANGLES);
- const float radius = parser.floatval('R', NOZZLE_CLEAN_CIRCLE_RADIUS);
+ const float radius = parser.linearval('R', NOZZLE_CLEAN_CIRCLE_RADIUS);
const bool seenxyz = parser.seen("XYZ");
const uint8_t cleans = (!seenxyz || parser.boolval('X') ? _BV(X_AXIS) : 0)
| (!seenxyz || parser.boolval('Y') ? _BV(Y_AXIS) : 0)
- #if DISABLED(NOZZLE_CLEAN_NO_Z)
- | (!seenxyz || parser.boolval('Z') ? _BV(Z_AXIS) : 0)
- #endif
+ | TERN(NOZZLE_CLEAN_NO_Z, 0, (!seenxyz || parser.boolval('Z') ? _BV(Z_AXIS) : 0))
;
#if HAS_LEVELING
@@ -60,6 +70,8 @@ void GcodeSuite::G12() {
TEMPORARY_BED_LEVELING_STATE(!TEST(cleans, Z_AXIS) && planner.leveling_active);
#endif
+ TEMPORARY_SOFT_ENDSTOP_STATE(parser.boolval('E'));
+
nozzle.clean(pattern, strokes, radius, objects, cleans);
}
diff --git a/Marlin/src/gcode/feature/controllerfan/M710.cpp b/Marlin/src/gcode/feature/controllerfan/M710.cpp
index e00fa77d6..67d4ad8ab 100644
--- a/Marlin/src/gcode/feature/controllerfan/M710.cpp
+++ b/Marlin/src/gcode/feature/controllerfan/M710.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -29,11 +29,11 @@
void M710_report(const bool forReplay) {
if (!forReplay) { SERIAL_ECHOLNPGM("; Controller Fan"); SERIAL_ECHO_START(); }
- SERIAL_ECHOLNPAIR("M710 "
- "S", int(controllerFan.settings.active_speed),
- "I", int(controllerFan.settings.idle_speed),
- "A", int(controllerFan.settings.auto_mode),
- "D", controllerFan.settings.duration,
+ SERIAL_ECHOLNPAIR(" M710"
+ " S", int(controllerFan.settings.active_speed),
+ " I", int(controllerFan.settings.idle_speed),
+ " A", int(controllerFan.settings.auto_mode),
+ " D", controllerFan.settings.duration,
" ; (", (int(controllerFan.settings.active_speed) * 100) / 255, "%"
" ", (int(controllerFan.settings.idle_speed) * 100) / 255, "%)"
);
diff --git a/Marlin/src/gcode/feature/digipot/M907-M910.cpp b/Marlin/src/gcode/feature/digipot/M907-M910.cpp
index fe8e37ebd..54599a045 100644
--- a/Marlin/src/gcode/feature/digipot/M907-M910.cpp
+++ b/Marlin/src/gcode/feature/digipot/M907-M910.cpp
@@ -16,13 +16,13 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#include "../../../inc/MarlinConfig.h"
-#if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || EITHER(DIGIPOT_I2C, DAC_STEPPER_CURRENT)
+#if ANY(HAS_DIGIPOTSS, HAS_MOTOR_CURRENT_PWM, HAS_I2C_DIGIPOT, DAC_STEPPER_CURRENT)
#include "../../gcode.h"
@@ -30,7 +30,7 @@
#include "../../../module/stepper.h"
#endif
-#if ENABLED(DIGIPOT_I2C)
+#if HAS_I2C_DIGIPOT
#include "../../../feature/digipot/digipot.h"
#endif
@@ -62,7 +62,7 @@ void GcodeSuite::M907() {
#endif
- #if ENABLED(DIGIPOT_I2C)
+ #if HAS_I2C_DIGIPOT
// this one uses actual amps in floating point
LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) digipot_i2c_set_current(i, parser.value_float());
// Additional extruders use B,C,D for channels 4,5,6.
@@ -80,18 +80,14 @@ void GcodeSuite::M907() {
#endif
}
-#if HAS_DIGIPOTSS || ENABLED(DAC_STEPPER_CURRENT)
+#if EITHER(HAS_DIGIPOTSS, DAC_STEPPER_CURRENT)
/**
* M908: Control digital trimpot directly (M908 P S)
*/
void GcodeSuite::M908() {
- #if HAS_DIGIPOTSS
- stepper.digitalPotWrite(parser.intval('P'), parser.intval('S'));
- #endif
- #if ENABLED(DAC_STEPPER_CURRENT)
- dac_current_raw(parser.byteval('P', -1), parser.ushortval('S', 0));
- #endif
+ TERN_(HAS_DIGIPOTSS, stepper.digitalPotWrite(parser.intval('P'), parser.intval('S')));
+ TERN_(DAC_STEPPER_CURRENT, dac_current_raw(parser.byteval('P', -1), parser.ushortval('S', 0)));
}
#endif // HAS_DIGIPOTSS || DAC_STEPPER_CURRENT
@@ -103,4 +99,4 @@ void GcodeSuite::M907() {
#endif // DAC_STEPPER_CURRENT
-#endif // HAS_DIGIPOTSS || DAC_STEPPER_CURRENT || HAS_MOTOR_CURRENT_PWM || DIGIPOT_I2C
+#endif // HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || HAS_I2C_DIGIPOT || DAC_STEPPER_CURRENT
diff --git a/Marlin/src/gcode/feature/filwidth/M404-M407.cpp b/Marlin/src/gcode/feature/filwidth/M404-M407.cpp
index 41e6e90aa..516289fe2 100644
--- a/Marlin/src/gcode/feature/filwidth/M404-M407.cpp
+++ b/Marlin/src/gcode/feature/filwidth/M404-M407.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/feature/fwretract/G10_G11.cpp b/Marlin/src/gcode/feature/fwretract/G10_G11.cpp
index 75e5b6a58..05f015036 100644
--- a/Marlin/src/gcode/feature/fwretract/G10_G11.cpp
+++ b/Marlin/src/gcode/feature/fwretract/G10_G11.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/feature/fwretract/M207-M209.cpp b/Marlin/src/gcode/feature/fwretract/M207-M209.cpp
index 6c48774c3..538f16cde 100644
--- a/Marlin/src/gcode/feature/fwretract/M207-M209.cpp
+++ b/Marlin/src/gcode/feature/fwretract/M207-M209.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/feature/i2c/M260_M261.cpp b/Marlin/src/gcode/feature/i2c/M260_M261.cpp
index ea04d2a29..13c2cd1d1 100644
--- a/Marlin/src/gcode/feature/i2c/M260_M261.cpp
+++ b/Marlin/src/gcode/feature/i2c/M260_M261.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -31,7 +31,7 @@
/**
* M260: Send data to a I2C slave device
*
- * This is a PoC, the formating and arguments for the GCODE will
+ * This is a PoC, the formatting and arguments for the GCODE will
* change to be more compatible, the current proposal is:
*
* M260 A ; Sets the I2C slave address the data will be sent to
diff --git a/Marlin/src/gcode/feature/leds/M150.cpp b/Marlin/src/gcode/feature/leds/M150.cpp
index 656b7e5f9..88f02951a 100644
--- a/Marlin/src/gcode/feature/leds/M150.cpp
+++ b/Marlin/src/gcode/feature/leds/M150.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -34,6 +34,9 @@
* Always sets all 3 or 4 components. If a component is left out, set to 0.
* If brightness is left out, no value changed
*
+ * With NEOPIXEL_LED:
+ * I Set the Neopixel index to affect. Default: All
+ *
* Examples:
*
* M150 R255 ; Turn LED red
@@ -43,8 +46,12 @@
* M150 W ; Turn LED white using a white LED
* M150 P127 ; Set LED 50% brightness
* M150 P ; Set LED full brightness
+ * M150 I1 R ; Set NEOPIXEL index 1 to red
*/
void GcodeSuite::M150() {
+ #if ENABLED(NEOPIXEL_LED)
+ neo.set_neo_index(parser.intval('I', -1));
+ #endif
leds.set_color(MakeLEDColor(
parser.seen('R') ? (parser.has_value() ? parser.value_byte() : 255) : 0,
parser.seen('U') ? (parser.has_value() ? parser.value_byte() : 255) : 0,
diff --git a/Marlin/src/gcode/feature/leds/M7219.cpp b/Marlin/src/gcode/feature/leds/M7219.cpp
index acbd55957..a6ee71174 100644
--- a/Marlin/src/gcode/feature/leds/M7219.cpp
+++ b/Marlin/src/gcode/feature/leds/M7219.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/feature/macro/M810-M819.cpp b/Marlin/src/gcode/feature/macro/M810-M819.cpp
index c106de298..7b9e1a13f 100644
--- a/Marlin/src/gcode/feature/macro/M810-M819.cpp
+++ b/Marlin/src/gcode/feature/macro/M810-M819.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/feature/mixing/M163-M165.cpp b/Marlin/src/gcode/feature/mixing/M163-M165.cpp
index 61be64ede..a4cb64e7d 100644
--- a/Marlin/src/gcode/feature/mixing/M163-M165.cpp
+++ b/Marlin/src/gcode/feature/mixing/M163-M165.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/feature/mixing/M166.cpp b/Marlin/src/gcode/feature/mixing/M166.cpp
index b4618c811..5f2c4f042 100644
--- a/Marlin/src/gcode/feature/mixing/M166.cpp
+++ b/Marlin/src/gcode/feature/mixing/M166.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/feature/pause/G27.cpp b/Marlin/src/gcode/feature/pause/G27.cpp
index 7f2f0d48b..ea6aadf17 100644
--- a/Marlin/src/gcode/feature/pause/G27.cpp
+++ b/Marlin/src/gcode/feature/pause/G27.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/feature/pause/G60.cpp b/Marlin/src/gcode/feature/pause/G60.cpp
index 45a8734ca..6f695b99a 100644
--- a/Marlin/src/gcode/feature/pause/G60.cpp
+++ b/Marlin/src/gcode/feature/pause/G60.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -24,7 +24,6 @@
#if SAVED_POSITIONS
-#include "../../../core/language.h"
#include "../../gcode.h"
#include "../../../module/motion.h"
diff --git a/Marlin/src/gcode/feature/pause/G61.cpp b/Marlin/src/gcode/feature/pause/G61.cpp
index 60e6bcf04..d8049f02b 100644
--- a/Marlin/src/gcode/feature/pause/G61.cpp
+++ b/Marlin/src/gcode/feature/pause/G61.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -24,7 +24,6 @@
#if SAVED_POSITIONS
-#include "../../../core/language.h"
#include "../../../module/planner.h"
#include "../../gcode.h"
#include "../../../module/motion.h"
diff --git a/Marlin/src/gcode/feature/pause/M125.cpp b/Marlin/src/gcode/feature/pause/M125.cpp
index 206815a20..db78e870d 100644
--- a/Marlin/src/gcode/feature/pause/M125.cpp
+++ b/Marlin/src/gcode/feature/pause/M125.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -56,11 +56,7 @@
*/
void GcodeSuite::M125() {
// Initial retract before move to filament change position
- const float retract = -ABS(parser.seen('L') ? parser.value_axis_units(E_AXIS) : 0
- #ifdef PAUSE_PARK_RETRACT_LENGTH
- + (PAUSE_PARK_RETRACT_LENGTH)
- #endif
- );
+ const float retract = -ABS(parser.seen('L') ? parser.value_axis_units(E_AXIS) : (PAUSE_PARK_RETRACT_LENGTH));
xyz_pos_t park_point = NOZZLE_PARK_POINT;
@@ -75,26 +71,17 @@ void GcodeSuite::M125() {
park_point += hotend_offset[active_extruder];
#endif
- #if ENABLED(SDSUPPORT)
- const bool sd_printing = IS_SD_PRINTING();
- #else
- constexpr bool sd_printing = false;
- #endif
+ const bool sd_printing = TERN0(SDSUPPORT, IS_SD_PRINTING());
- #if HAS_LCD_MENU
- lcd_pause_show_message(PAUSE_MESSAGE_PAUSING, PAUSE_MODE_PAUSE_PRINT);
- const bool show_lcd = parser.seenval('P');
- #else
- constexpr bool show_lcd = false;
- #endif
+ TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT));
+
+ const bool show_lcd = TERN0(HAS_LCD_MENU, parser.seenval('P'));
if (pause_print(retract, park_point, 0, show_lcd)) {
- #if ENABLED(POWER_LOSS_RECOVERY)
- if (recovery.enabled) recovery.save(true);
- #endif
- if (!sd_printing || show_lcd) {
+ TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true));
+ if (ENABLED(EXTENSIBLE_UI) || !sd_printing || show_lcd) {
wait_for_confirmation(false, 0);
- resume_print(0, 0, PAUSE_PARK_RETRACT_LENGTH, 0);
+ resume_print(0, 0, -retract, 0);
}
}
}
diff --git a/Marlin/src/gcode/feature/pause/M600.cpp b/Marlin/src/gcode/feature/pause/M600.cpp
index fc7702796..673c7387e 100644
--- a/Marlin/src/gcode/feature/pause/M600.cpp
+++ b/Marlin/src/gcode/feature/pause/M600.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -56,6 +56,7 @@
* L[distance] - Extrude distance for insertion (manual reload)
* B[count] - Number of times to beep, -1 for indefinite (if equipped with a buzzer)
* T[toolhead] - Select extruder for filament change
+ * R[temp] - Resume temperature (in current units)
*
* Default values are used for omitted arguments.
*/
@@ -83,7 +84,7 @@ void GcodeSuite::M600() {
// In this case, for duplicating modes set DXC_ext to the extruder that ran out.
#if HAS_FILAMENT_SENSOR && NUM_RUNOUT_SENSORS > 1
if (dxc_is_duplicating())
- DXC_ext = (READ(FIL_RUNOUT2_PIN) == FIL_RUNOUT_INVERTING) ? 1 : 0;
+ DXC_ext = (READ(FIL_RUNOUT2_PIN) == FIL_RUNOUT_STATE) ? 1 : 0;
#else
DXC_ext = active_extruder;
#endif
@@ -96,27 +97,19 @@ void GcodeSuite::M600() {
#endif
#if ENABLED(HOME_BEFORE_FILAMENT_CHANGE)
- // Don't allow filament change without homing first
- if (axes_need_homing()) home_all_axes();
+ // If needed, home before parking for filament change
+ if (!all_axes_known()) home_all_axes();
#endif
#if EXTRUDERS > 1
// Change toolhead if specified
const uint8_t active_extruder_before_filament_change = active_extruder;
- if (
- active_extruder != target_extruder
- #if ENABLED(DUAL_X_CARRIAGE)
- && dual_x_carriage_mode != DXC_DUPLICATION_MODE && dual_x_carriage_mode != DXC_MIRRORED_MODE
- #endif
- ) tool_change(target_extruder, false);
+ if (active_extruder != target_extruder && TERN1(DUAL_X_CARRIAGE, !dxc_is_duplicating()))
+ tool_change(target_extruder, false);
#endif
// Initial retract before move to filament change position
- const float retract = -ABS(parser.seen('E') ? parser.value_axis_units(E_AXIS) : 0
- #ifdef PAUSE_PARK_RETRACT_LENGTH
- + (PAUSE_PARK_RETRACT_LENGTH)
- #endif
- );
+ const float retract = -ABS(parser.seen('E') ? parser.value_axis_units(E_AXIS) : (PAUSE_PARK_RETRACT_LENGTH));
xyz_pos_t park_point NOZZLE_PARK_POINT;
@@ -149,11 +142,9 @@ void GcodeSuite::M600() {
: fc_settings[active_extruder].load_length);
#endif
- const int beep_count = parser.intval('B',
+ const int beep_count = parser.intval('B', -1
#ifdef FILAMENT_CHANGE_ALERT_BEEPS
- FILAMENT_CHANGE_ALERT_BEEPS
- #else
- -1
+ + 1 + FILAMENT_CHANGE_ALERT_BEEPS
#endif
);
@@ -163,7 +154,8 @@ void GcodeSuite::M600() {
resume_print(slow_load_length, fast_load_length, 0, beep_count DXC_PASS);
#else
wait_for_confirmation(true, beep_count DXC_PASS);
- resume_print(slow_load_length, fast_load_length, ADVANCED_PAUSE_PURGE_LENGTH, beep_count DXC_PASS);
+ resume_print(slow_load_length, fast_load_length, ADVANCED_PAUSE_PURGE_LENGTH,
+ beep_count, (parser.seenval('R') ? parser.value_celsius() : 0) DXC_PASS);
#endif
}
@@ -173,9 +165,7 @@ void GcodeSuite::M600() {
tool_change(active_extruder_before_filament_change, false);
#endif
- #if ENABLED(MIXING_EXTRUDER)
- mixer.T(old_mixing_tool); // Restore original mixing tool
- #endif
+ TERN_(MIXING_EXTRUDER, mixer.T(old_mixing_tool)); // Restore original mixing tool
}
#endif // ADVANCED_PAUSE_FEATURE
diff --git a/Marlin/src/gcode/feature/pause/M603.cpp b/Marlin/src/gcode/feature/pause/M603.cpp
index 620b8f4f2..a62b5cd46 100644
--- a/Marlin/src/gcode/feature/pause/M603.cpp
+++ b/Marlin/src/gcode/feature/pause/M603.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/feature/pause/M701_M702.cpp b/Marlin/src/gcode/feature/pause/M701_M702.cpp
index aa3c3c4c3..7449787d7 100644
--- a/Marlin/src/gcode/feature/pause/M701_M702.cpp
+++ b/Marlin/src/gcode/feature/pause/M701_M702.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -84,9 +84,7 @@ void GcodeSuite::M701() {
if (parser.seenval('Z')) park_point.z = parser.linearval('Z');
// Show initial "wait for load" message
- #if HAS_LCD_MENU
- lcd_pause_show_message(PAUSE_MESSAGE_LOAD, PAUSE_MODE_LOAD_FILAMENT, target_extruder);
- #endif
+ TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_LOAD, PAUSE_MODE_LOAD_FILAMENT, target_extruder));
#if EXTRUDERS > 1 && DISABLED(PRUSA_MMU2)
// Change toolhead if specified
@@ -129,14 +127,10 @@ void GcodeSuite::M701() {
tool_change(active_extruder_before_filament_change, false);
#endif
- #if ENABLED(MIXING_EXTRUDER)
- mixer.T(old_mixing_tool); // Restore original mixing tool
- #endif
+ TERN_(MIXING_EXTRUDER, mixer.T(old_mixing_tool)); // Restore original mixing tool
// Show status screen
- #if HAS_LCD_MENU
- lcd_pause_show_message(PAUSE_MESSAGE_STATUS);
- #endif
+ TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_STATUS));
}
/**
@@ -163,16 +157,18 @@ void GcodeSuite::M702() {
#if ENABLED(FILAMENT_UNLOAD_ALL_EXTRUDERS)
float mix_multiplier = 1.0;
- if (!parser.seenval('T')) {
+ const bool seenT = parser.seenval('T');
+ if (!seenT) {
mixer.T(MIXER_AUTORETRACT_TOOL);
mix_multiplier = MIXING_STEPPERS;
}
- else
+ #else
+ constexpr bool seenT = true;
#endif
- {
+
+ if (seenT) {
const int8_t target_e_stepper = get_target_e_stepper_from_command();
if (target_e_stepper < 0) return;
-
mixer.T(MIXER_DIRECT_SET_TOOL);
MIXER_STEPPER_LOOP(i) mixer.set_collector(i, (i == (uint8_t)target_e_stepper) ? 1.0 : 0.0);
mixer.normalize();
@@ -188,9 +184,7 @@ void GcodeSuite::M702() {
if (parser.seenval('Z')) park_point.z = parser.linearval('Z');
// Show initial "wait for unload" message
- #if HAS_LCD_MENU
- lcd_pause_show_message(PAUSE_MESSAGE_UNLOAD, PAUSE_MODE_UNLOAD_FILAMENT, target_extruder);
- #endif
+ TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_UNLOAD, PAUSE_MODE_UNLOAD_FILAMENT, target_extruder));
#if EXTRUDERS > 1 && DISABLED(PRUSA_MMU2)
// Change toolhead if specified
@@ -239,14 +233,10 @@ void GcodeSuite::M702() {
tool_change(active_extruder_before_filament_change, false);
#endif
- #if ENABLED(MIXING_EXTRUDER)
- mixer.T(old_mixing_tool); // Restore original mixing tool
- #endif
+ TERN_(MIXING_EXTRUDER, mixer.T(old_mixing_tool)); // Restore original mixing tool
// Show status screen
- #if HAS_LCD_MENU
- lcd_pause_show_message(PAUSE_MESSAGE_STATUS);
- #endif
+ TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_STATUS));
}
#endif // ADVANCED_PAUSE_FEATURE
diff --git a/Marlin/src/gcode/feature/power_monitor/M430.cpp b/Marlin/src/gcode/feature/power_monitor/M430.cpp
new file mode 100644
index 000000000..a669f0a76
--- /dev/null
+++ b/Marlin/src/gcode/feature/power_monitor/M430.cpp
@@ -0,0 +1,70 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (C) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+
+#include "../../../inc/MarlinConfig.h"
+
+#if HAS_POWER_MONITOR
+
+#include "../../../feature/power_monitor.h"
+#include "../../../MarlinCore.h"
+#include "../../gcode.h"
+
+/**
+ * M430: Enable/disable current LCD display
+ * With no parameters report the system current draw (in Amps)
+ *
+ * I[bool] - Set Display of current on the LCD
+ * V[bool] - Set Display of voltage on the LCD
+ * W[bool] - Set Display of power on the LCD
+ */
+void GcodeSuite::M430() {
+ bool do_report = true;
+ #if HAS_SPI_LCD
+ #if ENABLED(POWER_MONITOR_CURRENT)
+ if (parser.seen('I')) { power_monitor.set_current_display(parser.value_bool()); do_report = false; }
+ #endif
+ #if HAS_POWER_MONITOR_VREF
+ if (parser.seen('V')) { power_monitor.set_voltage_display(parser.value_bool()); do_report = false; }
+ #endif
+ #if HAS_POWER_MONITOR_WATTS
+ if (parser.seen('W')) { power_monitor.set_power_display(parser.value_bool()); do_report = false; }
+ #endif
+ #endif
+ if (do_report) {
+ SERIAL_ECHOLNPAIR(
+ #if ENABLED(POWER_MONITOR_CURRENT)
+ "Current: ", power_monitor.getAmps(), "A"
+ #if HAS_POWER_MONITOR_VREF
+ " "
+ #endif
+ #endif
+ #if HAS_POWER_MONITOR_VREF
+ "Voltage: ", power_monitor.getVolts(), "V"
+ #endif
+ #if HAS_POWER_MONITOR_WATTS
+ " Power: ", power_monitor.getPower(), "W"
+ #endif
+ );
+ }
+}
+
+#endif // HAS_POWER_MONITOR
diff --git a/Marlin/src/gcode/feature/powerloss/M1000.cpp b/Marlin/src/gcode/feature/powerloss/M1000.cpp
index 8d8cdc755..58e810e5d 100644
--- a/Marlin/src/gcode/feature/powerloss/M1000.cpp
+++ b/Marlin/src/gcode/feature/powerloss/M1000.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -41,7 +41,7 @@ inline void plr_error(PGM_P const prefix) {
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
DEBUG_ECHO_START();
serialprintPGM(prefix);
- DEBUG_ECHOLNPGM(" Power-Loss Recovery Data");
+ DEBUG_ECHOLNPGM(" Job Recovery Data");
#else
UNUSED(prefix);
#endif
@@ -74,9 +74,7 @@ void GcodeSuite::M1000() {
#else
recovery.cancel();
#endif
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onPrintTimerStopped();
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onPrintTimerStopped());
}
else
recovery.resume();
diff --git a/Marlin/src/gcode/feature/powerloss/M413.cpp b/Marlin/src/gcode/feature/powerloss/M413.cpp
index 67e756d5d..5a08053e7 100644
--- a/Marlin/src/gcode/feature/powerloss/M413.cpp
+++ b/Marlin/src/gcode/feature/powerloss/M413.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -50,6 +50,9 @@ void GcodeSuite::M413() {
if (parser.seen("RL")) recovery.load();
if (parser.seen('W')) recovery.save(true);
if (parser.seen('P')) recovery.purge();
+ #if PIN_EXISTS(POWER_LOSS)
+ if (parser.seen('O')) recovery._outage();
+ #endif
if (parser.seen('E')) serialprintPGM(recovery.exists() ? PSTR("PLR Exists\n") : PSTR("No PLR\n"));
if (parser.seen('V')) serialprintPGM(recovery.valid() ? PSTR("Valid\n") : PSTR("Invalid\n"));
#endif
diff --git a/Marlin/src/gcode/feature/prusa_MMU2/M403.cpp b/Marlin/src/gcode/feature/prusa_MMU2/M403.cpp
index 0a9c51945..91e35dbf6 100644
--- a/Marlin/src/gcode/feature/prusa_MMU2/M403.cpp
+++ b/Marlin/src/gcode/feature/prusa_MMU2/M403.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/feature/runout/M412.cpp b/Marlin/src/gcode/feature/runout/M412.cpp
index f746dddfa..130f9c83e 100644
--- a/Marlin/src/gcode/feature/runout/M412.cpp
+++ b/Marlin/src/gcode/feature/runout/M412.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -29,15 +29,17 @@
/**
* M412: Enable / Disable filament runout detection
+ *
+ * Parameters
+ * R : Reset the runout sensor
+ * S : Reset and enable/disable the runout sensor
+ * H : Enable/disable host handling of filament runout
+ * D : Extra distance to continue after runout is triggered
*/
void GcodeSuite::M412() {
if (parser.seen("RS"
- #ifdef FILAMENT_RUNOUT_DISTANCE_MM
- "D"
- #endif
- #if ENABLED(HOST_ACTION_COMMANDS)
- "H"
- #endif
+ TERN_(HAS_FILAMENT_RUNOUT_DISTANCE, "D")
+ TERN_(HOST_ACTION_COMMANDS, "H")
)) {
#if ENABLED(HOST_ACTION_COMMANDS)
if (parser.seen('H')) runout.host_handling = parser.value_bool();
@@ -45,7 +47,7 @@ void GcodeSuite::M412() {
const bool seenR = parser.seen('R'), seenS = parser.seen('S');
if (seenR || seenS) runout.reset();
if (seenS) runout.enabled = parser.value_bool();
- #ifdef FILAMENT_RUNOUT_DISTANCE_MM
+ #if HAS_FILAMENT_RUNOUT_DISTANCE
if (parser.seen('D')) runout.set_runout_distance(parser.value_linear_units());
#endif
}
@@ -53,7 +55,7 @@ void GcodeSuite::M412() {
SERIAL_ECHO_START();
SERIAL_ECHOPGM("Filament runout ");
serialprintln_onoff(runout.enabled);
- #ifdef FILAMENT_RUNOUT_DISTANCE_MM
+ #if HAS_FILAMENT_RUNOUT_DISTANCE
SERIAL_ECHOLNPAIR("Filament runout distance (mm): ", runout.runout_distance());
#endif
}
diff --git a/Marlin/src/gcode/feature/trinamic/M122.cpp b/Marlin/src/gcode/feature/trinamic/M122.cpp
index 0eb93a800..46e4365f3 100644
--- a/Marlin/src/gcode/feature/trinamic/M122.cpp
+++ b/Marlin/src/gcode/feature/trinamic/M122.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -26,6 +26,7 @@
#include "../../gcode.h"
#include "../../../feature/tmc_util.h"
+#include "../../../module/stepper/indirection.h"
/**
* M122: Debug TMC drivers
@@ -37,11 +38,14 @@ void GcodeSuite::M122() {
if (print_all) LOOP_XYZE(i) print_axis[i] = true;
+ if (parser.boolval('I')) restore_stepper_drivers();
+
#if ENABLED(TMC_DEBUG)
#if ENABLED(MONITOR_DRIVER_STATUS)
- const bool sflag = parser.seen('S'), s0 = sflag && !parser.value_bool();
- if (sflag) tmc_set_report_interval(s0 ? 0 : MONITOR_DRIVER_STATUS_INTERVAL_MS);
- if (!s0 && parser.seenval('P')) tmc_set_report_interval(_MIN(parser.value_ushort(), MONITOR_DRIVER_STATUS_INTERVAL_MS));
+ uint16_t interval = MONITOR_DRIVER_STATUS_INTERVAL_MS;
+ if (parser.seen('S') && !parser.value_bool()) interval = 0;
+ if (parser.seenval('P')) NOMORE(interval, parser.value_ushort());
+ tmc_set_report_interval(interval);
#endif
if (parser.seen('V'))
diff --git a/Marlin/src/gcode/feature/trinamic/M569.cpp b/Marlin/src/gcode/feature/trinamic/M569.cpp
index f88e11683..e72d03e76 100644
--- a/Marlin/src/gcode/feature/trinamic/M569.cpp
+++ b/Marlin/src/gcode/feature/trinamic/M569.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/feature/trinamic/M906.cpp b/Marlin/src/gcode/feature/trinamic/M906.cpp
index 95ad310ed..e834ebd67 100644
--- a/Marlin/src/gcode/feature/trinamic/M906.cpp
+++ b/Marlin/src/gcode/feature/trinamic/M906.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp
index 582e779cc..8c840db5b 100644
--- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp
+++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp
index 1f9d710bb..7f00ec5a3 100644
--- a/Marlin/src/gcode/gcode.cpp
+++ b/Marlin/src/gcode/gcode.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -53,9 +53,16 @@ GcodeSuite gcode;
#include "../feature/cancel_object.h"
#endif
+#if ENABLED(LASER_MOVE_POWER)
+ #include "../feature/spindle_laser.h"
+#endif
+
#include "../MarlinCore.h" // for idle()
-millis_t GcodeSuite::previous_move_ms;
+// Inactivity shutdown
+millis_t GcodeSuite::previous_move_ms = 0,
+ GcodeSuite::max_inactive_time = 0,
+ GcodeSuite::stepper_inactive_time = SEC_TO_MS(DEFAULT_STEPPER_DEACTIVE_TIME);
// Relative motion mode for each logical axis
static constexpr xyze_bool_t ar_init = AXIS_RELATIVE_MODES;
@@ -66,7 +73,7 @@ uint8_t GcodeSuite::axis_relative = (
| (ar_init.e ? _BV(REL_E) : 0)
);
-#if HAS_AUTO_REPORTING || ENABLED(HOST_KEEPALIVE_FEATURE)
+#if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE)
bool GcodeSuite::autoreport_paused; // = false
#endif
@@ -172,6 +179,16 @@ void GcodeSuite::get_destination_from_command() {
#if BOTH(MIXING_EXTRUDER, DIRECT_MIXING_IN_G1)
M165();
#endif
+
+ #if ENABLED(LASER_MOVE_POWER)
+ // Set the laser power in the planner to configure this move
+ if (parser.seen('S')) {
+ const float spwr = parser.value_float();
+ cutter.inline_power(TERN(SPINDLE_LASER_PWM, cutter.power_to_range(cutter_power_t(round(spwr))), spwr > 0 ? 255 : 0));
+ }
+ else if (ENABLED(LASER_MOVE_G0_OFF) && parser.codenum == 0) // G0
+ cutter.set_inline_enabled(false);
+ #endif
}
/**
@@ -186,7 +203,7 @@ void GcodeSuite::dwell(millis_t time) {
* When G29_RETRY_AND_RECOVER is enabled, call G29() in
* a loop with recovery and retry handling.
*/
-#if HAS_LEVELING && ENABLED(G29_RETRY_AND_RECOVER)
+#if BOTH(HAS_LEVELING, G29_RETRY_AND_RECOVER)
#ifndef G29_MAX_RETRIES
#define G29_MAX_RETRIES 0
@@ -202,9 +219,7 @@ void GcodeSuite::dwell(millis_t time) {
}
}
- #if ENABLED(HOST_PROMPT_SUPPORT)
- host_action_prompt_end();
- #endif
+ TERN_(HOST_PROMPT_SUPPORT, host_action_prompt_end());
#ifdef G29_SUCCESS_COMMANDS
process_subcommands_now_P(PSTR(G29_SUCCESS_COMMANDS));
@@ -247,6 +262,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
case 5: G5(); break; // G5: Cubic B_spline
#endif
+ #if ENABLED(DIRECT_STEPPING)
+ case 6: G6(); break; // G6: Direct Stepper Move
+ #endif
+
#if ENABLED(FWRETRACT)
case 10: G10(); break; // G10: Retract / Swap Retract
case 11: G11(); break; // G11: Recover / Swap Recover
@@ -305,15 +324,14 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
case 34: G34(); break; // G34: Z Stepper automatic alignment using probe
#endif
+ #if ENABLED(ASSISTED_TRAMMING)
+ case 35: G35(); break; // G35: Read four bed corners to help adjust bed screws
+ #endif
+
#if ENABLED(G38_PROBE_TARGET)
case 38: // G38.2, G38.3: Probe towards target
- if (WITHIN(parser.subcode, 2,
- #if ENABLED(G38_PROBE_AWAY)
- 5
- #else
- 3
- #endif
- )) G38(parser.subcode); // G38.4, G38.5: Probe away from target
+ if (WITHIN(parser.subcode, 2, TERN(G38_PROBE_AWAY, 5, 3)))
+ G38(parser.subcode); // G38.4, G38.5: Probe away from target
break;
#endif
@@ -453,7 +471,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
case 105: M105(); return; // M105: Report Temperatures (and say "ok")
- #if FAN_COUNT > 0
+ #if HAS_FAN
case 106: M106(); break; // M106: Fan On
case 107: M107(); break; // M107: Fan Off
#endif
@@ -465,14 +483,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
case 108: M108(); break; // M108: Cancel Waiting
case 112: M112(); break; // M112: Full Shutdown
case 410: M410(); break; // M410: Quickstop - Abort all the planned moves.
- #if ENABLED(HOST_PROMPT_SUPPORT)
- case 876: M876(); break; // M876: Handle Host prompt responses
- #endif
+ TERN_(HOST_PROMPT_SUPPORT, case 876:) // M876: Handle Host prompt responses
#else
case 108: case 112: case 410:
- #if ENABLED(HOST_PROMPT_SUPPORT)
- case 876:
- #endif
+ TERN_(HOST_PROMPT_SUPPORT, case 876:)
break;
#endif
@@ -490,7 +504,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
case 191: M191(); break; // M191: Wait for chamber temperature to reach target
#endif
- #if ENABLED(AUTO_REPORT_TEMPERATURES) && HAS_TEMP_SENSOR
+ #if BOTH(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR)
case 155: M155(); break; // M155: Set temperature auto-report interval
#endif
@@ -530,7 +544,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
case 120: M120(); break; // M120: Enable endstops
case 121: M121(); break; // M121: Disable endstops
- #if HOTENDS && HAS_LCD_MENU
+ #if PREHEAT_COUNT
case 145: M145(); break; // M145: Set material heatup parameters
#endif
@@ -649,6 +663,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
case 305: M305(); break; // M305: Set user thermistor parameters
#endif
+ #if ENABLED(REPETIER_GCODE_M360)
+ case 360: M360(); break; // M360: Firmware settings
+ #endif
+
#if ENABLED(MORGAN_SCARA)
case 360: if (M360()) return; break; // M360: SCARA Theta pos1
case 361: if (M361()) return; break; // M361: SCARA Theta pos2
@@ -700,6 +718,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
case 428: M428(); break; // M428: Apply current_position to home_offset
#endif
+ #if HAS_POWER_MONITOR
+ case 430: M430(); break; // M430: Read the system current (A), voltage (V), and power (W)
+ #endif
+
#if ENABLED(CANCEL_OBJECTS)
case 486: M486(); break; // M486: Identify and cancel objects
#endif
@@ -778,9 +800,9 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
case 900: M900(); break; // M900: Set advance K factor.
#endif
- #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || EITHER(DIGIPOT_I2C, DAC_STEPPER_CURRENT)
+ #if ANY(HAS_DIGIPOTSS, HAS_MOTOR_CURRENT_PWM, HAS_I2C_DIGIPOT, DAC_STEPPER_CURRENT)
case 907: M907(); break; // M907: Set digital trimpot motor current using axis codes.
- #if HAS_DIGIPOTSS || ENABLED(DAC_STEPPER_CURRENT)
+ #if EITHER(HAS_DIGIPOTSS, DAC_STEPPER_CURRENT)
case 908: M908(); break; // M908: Control digital trimpot directly.
#if ENABLED(DAC_STEPPER_CURRENT)
case 909: M909(); break; // M909: Print digipot/DAC current value
@@ -972,7 +994,7 @@ void GcodeSuite::process_subcommands_now(char * gcode) {
break;
}
}
- next_busy_signal_ms = ms + host_keepalive_interval * 1000UL;
+ next_busy_signal_ms = ms + SEC_TO_MS(host_keepalive_interval);
}
#endif // HOST_KEEPALIVE_FEATURE
diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h
index 8e5d054d9..b3f339e29 100644
--- a/Marlin/src/gcode/gcode.h
+++ b/Marlin/src/gcode/gcode.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -31,9 +31,9 @@
* -----------------
*
* Helpful G-code references:
- * - http://marlinfw.org/meta/gcode
+ * - https://marlinfw.org/meta/gcode
* - https://reprap.org/wiki/G-code
- * - http://linuxcnc.org/docs/html/gcode.html
+ * - https://linuxcnc.org/docs/html/gcode.html
*
* Help to document Marlin's G-codes online:
* - https://github.com/MarlinFirmware/MarlinDocumentation
@@ -65,6 +65,7 @@
* G32 - Undock sled (Z_PROBE_SLED only)
* G33 - Delta Auto-Calibration (Requires DELTA_AUTO_CALIBRATION)
* G34 - Z Stepper automatic alignment using probe: I T A (Requires Z_STEPPER_AUTO_ALIGN)
+ * G35 - Read bed corners to help adjust bed screws: T (Requires ASSISTED_TRAMMING)
* G38 - Probe in any direction using the Z_MIN_PROBE (Requires G38_PROBE_TARGET)
* G42 - Coordinated move to a mesh point (Requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BLINEAR, or AUTO_BED_LEVELING_UBL)
* G60 - Save current position. (Requires SAVED_POSITIONS)
@@ -217,6 +218,7 @@
* M422 - Set Z Stepper automatic alignment position using probe. X Y A (Requires Z_STEPPER_AUTO_ALIGN)
* M425 - Enable/Disable and tune backlash correction. (Requires BACKLASH_COMPENSATION and BACKLASH_GCODE)
* M428 - Set the home_offset based on the current_position. Nearest edge applies. (Disabled by NO_WORKSPACE_OFFSETS or DELTA)
+ * M430 - Read the system current, voltage, and power (Requires POWER_MONITOR_CURRENT, POWER_MONITOR_VOLTAGE, or POWER_MONITOR_FIXED_VOLTAGE)
* M486 - Identify and cancel objects. (Requires CANCEL_OBJECTS)
* M500 - Store parameters in EEPROM. (Requires EEPROM_SETTINGS)
* M501 - Restore parameters from EEPROM. (Requires EEPROM_SETTINGS)
@@ -332,8 +334,14 @@ public:
static bool select_coordinate_system(const int8_t _new);
#endif
- static millis_t previous_move_ms;
- FORCE_INLINE static void reset_stepper_timeout() { previous_move_ms = millis(); }
+ static millis_t previous_move_ms, max_inactive_time, stepper_inactive_time;
+ FORCE_INLINE static void reset_stepper_timeout(const millis_t ms=millis()) { previous_move_ms = ms; }
+ FORCE_INLINE static bool stepper_max_timed_out(const millis_t ms=millis()) {
+ return max_inactive_time && ELAPSED(ms, previous_move_ms + max_inactive_time);
+ }
+ FORCE_INLINE static bool stepper_inactive_timeout(const millis_t ms=millis()) {
+ return ELAPSED(ms, previous_move_ms + stepper_inactive_time);
+ }
static int8_t get_target_extruder_from_command();
static int8_t get_target_e_stepper_from_command();
@@ -351,7 +359,7 @@ public:
process_subcommands_now_P(G28_STR);
}
- #if HAS_AUTO_REPORTING || ENABLED(HOST_KEEPALIVE_FEATURE)
+ #if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE)
static bool autoreport_paused;
static inline bool set_autoreport_paused(const bool p) {
const bool was = autoreport_paused;
@@ -396,24 +404,20 @@ private:
#endif
);
- #if ENABLED(ARC_SUPPORT)
- static void G2_G3(const bool clockwise);
- #endif
+ TERN_(ARC_SUPPORT, static void G2_G3(const bool clockwise));
static void G4();
- #if ENABLED(BEZIER_CURVE_SUPPORT)
- static void G5();
- #endif
+ TERN_(BEZIER_CURVE_SUPPORT, static void G5());
+
+ TERN_(DIRECT_STEPPING, static void G6());
#if ENABLED(FWRETRACT)
static void G10();
static void G11();
#endif
- #if ENABLED(NOZZLE_CLEAN_FEATURE)
- static void G12();
- #endif
+ TERN_(NOZZLE_CLEAN_FEATURE, static void G12());
#if ENABLED(CNC_WORKSPACE_PLANES)
static void G17();
@@ -426,13 +430,9 @@ private:
static void G21();
#endif
- #if ENABLED(G26_MESH_VALIDATION)
- static void G26();
- #endif
+ TERN_(G26_MESH_VALIDATION, static void G26());
- #if ENABLED(NOZZLE_PARK_FEATURE)
- static void G27();
- #endif
+ TERN_(NOZZLE_PARK_FEATURE, static void G27());
static void G28();
@@ -454,22 +454,18 @@ private:
#endif
#endif
- #if ENABLED(DELTA_AUTO_CALIBRATION)
- static void G33();
- #endif
+ TERN_(DELTA_AUTO_CALIBRATION, static void G33());
#if ENABLED(Z_STEPPER_AUTO_ALIGN)
static void G34();
static void M422();
#endif
- #if ENABLED(G38_PROBE_TARGET)
- static void G38(const int8_t subcode);
- #endif
+ TERN_(ASSISTED_TRAMMING, static void G35());
- #if HAS_MESH
- static void G42();
- #endif
+ TERN_(G38_PROBE_TARGET, static void G38(const int8_t subcode));
+
+ TERN_(HAS_MESH, static void G42());
#if ENABLED(CNC_COORDINATE_SYSTEMS)
static void G53();
@@ -481,28 +477,20 @@ private:
static void G59();
#endif
- #if ENABLED(PROBE_TEMP_COMPENSATION)
- static void G76();
- #endif
+ TERN_(PROBE_TEMP_COMPENSATION, static void G76());
#if SAVED_POSITIONS
static void G60();
static void G61();
#endif
- #if ENABLED(GCODE_MOTION_MODES)
- static void G80();
- #endif
+ TERN_(GCODE_MOTION_MODES, static void G80());
static void G92();
- #if ENABLED(CALIBRATION_GCODE)
- static void G425();
- #endif
+ TERN_(CALIBRATION_GCODE, static void G425());
- #if HAS_RESUME_CONTINUE
- static void M0_M1();
- #endif
+ TERN_(HAS_RESUME_CONTINUE, static void M0_M1());
#if HAS_CUTTER
static void M3_M4(const bool is_M4);
@@ -510,22 +498,14 @@ private:
#endif
#if ENABLED(COOLANT_CONTROL)
- #if ENABLED(COOLANT_MIST)
- static void M7();
- #endif
- #if ENABLED(COOLANT_FLOOD)
- static void M8();
- #endif
+ TERN_(COOLANT_MIST, static void M7());
+ TERN_(COOLANT_FLOOD, static void M8());
static void M9();
#endif
- #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER)
- static void M12();
- #endif
+ TERN_(EXTERNAL_CLOSED_LOOP_CONTROLLER, static void M12());
- #if ENABLED(EXPECTED_PRINTER_CHECK)
- static void M16();
- #endif
+ TERN_(EXPECTED_PRINTER_CHECK, static void M16());
static void M17();
@@ -549,9 +529,7 @@ private:
#if ENABLED(SDSUPPORT)
static void M32();
- #if ENABLED(LONG_FILENAME_HOST_SUPPORT)
- static void M33();
- #endif
+ TERN_(LONG_FILENAME_HOST_SUPPORT, static void M33());
#if BOTH(SDCARD_SORT_ALPHA, SDSORT_GCODE)
static void M34();
#endif
@@ -559,29 +537,19 @@ private:
static void M42();
- #if ENABLED(PINS_DEBUGGING)
- static void M43();
- #endif
+ TERN_(PINS_DEBUGGING, static void M43());
- #if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST)
- static void M48();
- #endif
+ TERN_(Z_MIN_PROBE_REPEATABILITY_TEST, static void M48());
- #if ENABLED(LCD_SET_PROGRESS_MANUALLY)
- static void M73();
- #endif
+ TERN_(LCD_SET_PROGRESS_MANUALLY, static void M73());
static void M75();
static void M76();
static void M77();
- #if ENABLED(PRINTCOUNTER)
- static void M78();
- #endif
+ TERN_(PRINTCOUNTER, static void M78());
- #if ENABLED(PSU_CONTROL)
- static void M80();
- #endif
+ TERN_(PSU_CONTROL, static void M80());
static void M81();
static void M82();
@@ -589,9 +557,7 @@ private:
static void M85();
static void M92();
- #if ENABLED(M100_FREE_MEMORY_WATCHER)
- static void M100();
- #endif
+ TERN_(M100_FREE_MEMORY_WATCHER, static void M100());
#if EXTRUDERS
static void M104();
@@ -600,7 +566,7 @@ private:
static void M105();
- #if FAN_COUNT > 0
+ #if HAS_FAN
static void M106();
static void M107();
#endif
@@ -609,17 +575,13 @@ private:
static void M108();
static void M112();
static void M410();
- #if ENABLED(HOST_PROMPT_SUPPORT)
- static void M876();
- #endif
+ TERN_(HOST_PROMPT_SUPPORT, static void M876());
#endif
static void M110();
static void M111();
- #if ENABLED(HOST_KEEPALIVE_FEATURE)
- static void M113();
- #endif
+ TERN_(HOST_KEEPALIVE_FEATURE, static void M113());
static void M114();
static void M115();
@@ -629,9 +591,7 @@ private:
static void M120();
static void M121();
- #if ENABLED(PARK_HEAD_ON_PAUSE)
- static void M125();
- #endif
+ TERN_(PARK_HEAD_ON_PAUSE, static void M125());
#if ENABLED(BARICUDA)
#if HAS_HEATER_1
@@ -654,31 +614,23 @@ private:
static void M191();
#endif
- #if HOTENDS && HAS_LCD_MENU
+ #if PREHEAT_COUNT
static void M145();
#endif
- #if ENABLED(TEMPERATURE_UNITS_SUPPORT)
- static void M149();
- #endif
+ TERN_(TEMPERATURE_UNITS_SUPPORT, static void M149());
- #if HAS_COLOR_LEDS
- static void M150();
- #endif
+ TERN_(HAS_COLOR_LEDS, static void M150());
- #if ENABLED(AUTO_REPORT_TEMPERATURES) && HAS_TEMP_SENSOR
+ #if BOTH(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR)
static void M155();
#endif
#if ENABLED(MIXING_EXTRUDER)
static void M163();
static void M164();
- #if ENABLED(DIRECT_MIXING_IN_G1)
- static void M165();
- #endif
- #if ENABLED(GRADIENT_MIX)
- static void M166();
- #endif
+ TERN_(DIRECT_MIXING_IN_G1, static void M165());
+ TERN_(GRADIENT_MIX, static void M166());
#endif
static void M200();
@@ -692,16 +644,12 @@ private:
static void M204();
static void M205();
- #if HAS_M206_COMMAND
- static void M206();
- #endif
+ TERN_(HAS_M206_COMMAND, static void M206());
#if ENABLED(FWRETRACT)
static void M207();
static void M208();
- #if ENABLED(FWRETRACT_AUTORETRACT)
- static void M209();
- #endif
+ TERN_(FWRETRACT_AUTORETRACT, static void M209());
#endif
static void M211();
@@ -710,9 +658,7 @@ private:
static void M217();
#endif
- #if HAS_HOTEND_OFFSET
- static void M218();
- #endif
+ TERN_(HAS_HOTEND_OFFSET, static void M218());
static void M220();
@@ -722,13 +668,9 @@ private:
static void M226();
- #if ENABLED(PHOTO_GCODE)
- static void M240();
- #endif
+ TERN_(PHOTO_GCODE, static void M240());
- #if HAS_LCD_CONTRAST
- static void M250();
- #endif
+ TERN_(HAS_LCD_CONTRAST, static void M250());
#if ENABLED(EXPERIMENTAL_I2CBUS)
static void M260();
@@ -737,47 +679,31 @@ private:
#if HAS_SERVOS
static void M280();
- #if ENABLED(EDITABLE_SERVO_ANGLES)
- static void M281();
- #endif
+ TERN_(EDITABLE_SERVO_ANGLES, static void M281());
#endif
- #if ENABLED(BABYSTEPPING)
- static void M290();
- #endif
+ TERN_(BABYSTEPPING, static void M290());
- #if HAS_BUZZER
- static void M300();
- #endif
+ TERN_(HAS_BUZZER, static void M300());
- #if ENABLED(PIDTEMP)
- static void M301();
- #endif
+ TERN_(PIDTEMP, static void M301());
- #if ENABLED(PREVENT_COLD_EXTRUSION)
- static void M302();
- #endif
+ TERN_(PREVENT_COLD_EXTRUSION, static void M302());
- #if HAS_PID_HEATING
- static void M303();
- #endif
+ TERN_(HAS_PID_HEATING, static void M303());
- #if ENABLED(PIDTEMPBED)
- static void M304();
- #endif
+ TERN_(PIDTEMPBED, static void M304());
- #if HAS_USER_THERMISTORS
- static void M305();
- #endif
+ TERN_(HAS_USER_THERMISTORS, static void M305());
#if HAS_MICROSTEPS
static void M350();
static void M351();
#endif
- #if HAS_CASE_LIGHT
- static void M355();
- #endif
+ TERN_(HAS_CASE_LIGHT, static void M355());
+
+ TERN_(REPETIER_GCODE_M360, static void M360());
#if ENABLED(MORGAN_SCARA)
static bool M360();
@@ -799,9 +725,7 @@ private:
static void M402();
#endif
- #if ENABLED(PRUSA_MMU2)
- static void M403();
- #endif
+ TERN_(PRUSA_MMU2, static void M403());
#if ENABLED(FILAMENT_WIDTH_SENSOR)
static void M404();
@@ -810,26 +734,20 @@ private:
static void M407();
#endif
- #if HAS_FILAMENT_SENSOR
- static void M412();
- #endif
+ TERN_(HAS_FILAMENT_SENSOR, static void M412());
#if HAS_LEVELING
static void M420();
static void M421();
#endif
- #if ENABLED(BACKLASH_GCODE)
- static void M425();
- #endif
+ TERN_(BACKLASH_GCODE, static void M425());
- #if HAS_M206_COMMAND
- static void M428();
- #endif
+ TERN_(HAS_M206_COMMAND, static void M428());
- #if ENABLED(CANCEL_OBJECTS)
- static void M486();
- #endif
+ TERN_(HAS_POWER_MONITOR, static void M430());
+
+ TERN_(CANCEL_OBJECTS, static void M486());
static void M500();
static void M501();
@@ -837,34 +755,22 @@ private:
#if DISABLED(DISABLE_M503)
static void M503();
#endif
- #if ENABLED(EEPROM_SETTINGS)
- static void M504();
- #endif
+ TERN_(EEPROM_SETTINGS, static void M504());
- #if ENABLED(SDSUPPORT)
- static void M524();
- #endif
+ TERN_(SDSUPPORT, static void M524());
- #if ENABLED(SD_ABORT_ON_ENDSTOP_HIT)
- static void M540();
- #endif
+ TERN_(SD_ABORT_ON_ENDSTOP_HIT, static void M540());
- #if ENABLED(BAUD_RATE_GCODE)
- static void M575();
- #endif
+ TERN_(BAUD_RATE_GCODE, static void M575());
#if ENABLED(ADVANCED_PAUSE_FEATURE)
static void M600();
static void M603();
#endif
- #if HAS_DUPLICATION_MODE
- static void M605();
- #endif
+ TERN_(HAS_DUPLICATION_MODE, static void M605());
- #if IS_KINEMATIC
- static void M665();
- #endif
+ TERN_(IS_KINEMATIC, static void M665());
#if ENABLED(DELTA) || HAS_EXTRA_ENDSTOPS
static void M666();
@@ -879,17 +785,11 @@ private:
static void M702();
#endif
- #if ENABLED(GCODE_MACROS)
- static void M810_819();
- #endif
+ TERN_(GCODE_MACROS, static void M810_819());
- #if HAS_BED_PROBE
- static void M851();
- #endif
+ TERN_(HAS_BED_PROBE, static void M851());
- #if ENABLED(SKEW_CORRECTION_GCODE)
- static void M852();
- #endif
+ TERN_(SKEW_CORRECTION_GCODE, static void M852());
#if ENABLED(I2C_POSITION_ENCODERS)
FORCE_INLINE static void M860() { I2CPEM.M860(); }
@@ -904,30 +804,20 @@ private:
FORCE_INLINE static void M869() { I2CPEM.M869(); }
#endif
- #if ENABLED(PROBE_TEMP_COMPENSATION)
- static void M871();
- #endif
+ TERN_(PROBE_TEMP_COMPENSATION, static void M871());
- #if ENABLED(LIN_ADVANCE)
- static void M900();
- #endif
+ TERN_(LIN_ADVANCE, static void M900());
#if HAS_TRINAMIC_CONFIG
static void M122();
static void M906();
- #if HAS_STEALTHCHOP
- static void M569();
- #endif
+ TERN_(HAS_STEALTHCHOP, static void M569());
#if ENABLED(MONITOR_DRIVER_STATUS)
static void M911();
static void M912();
#endif
- #if ENABLED(HYBRID_THRESHOLD)
- static void M913();
- #endif
- #if USE_SENSORLESS
- static void M914();
- #endif
+ TERN_(HYBRID_THRESHOLD, static void M913());
+ TERN_(USE_SENSORLESS, static void M914());
#endif
#if HAS_L64XX
@@ -938,9 +828,9 @@ private:
static void M918();
#endif
- #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || EITHER(DIGIPOT_I2C, DAC_STEPPER_CURRENT)
+ #if ANY(HAS_DIGIPOTSS, HAS_MOTOR_CURRENT_PWM, HAS_I2C_DIGIPOT, DAC_STEPPER_CURRENT)
static void M907();
- #if HAS_DIGIPOTSS || ENABLED(DAC_STEPPER_CURRENT)
+ #if EITHER(HAS_DIGIPOTSS, DAC_STEPPER_CURRENT)
static void M908();
#if ENABLED(DAC_STEPPER_CURRENT)
static void M909();
@@ -949,17 +839,11 @@ private:
#endif
#endif
- #if ENABLED(SDSUPPORT)
- static void M928();
- #endif
+ TERN_(SDSUPPORT, static void M928());
- #if ENABLED(MAGNETIC_PARKING_EXTRUDER)
- static void M951();
- #endif
+ TERN_(MAGNETIC_PARKING_EXTRUDER, static void M951());
- #if ENABLED(PLATFORM_M997_SUPPORT)
- static void M997();
- #endif
+ TERN_(PLATFORM_M997_SUPPORT, static void M997());
static void M999();
@@ -968,17 +852,11 @@ private:
static void M1000();
#endif
- #if ENABLED(SDSUPPORT)
- static void M1001();
- #endif
+ TERN_(SDSUPPORT, static void M1001());
- #if ENABLED(MAX7219_GCODE)
- static void M7219();
- #endif
+ TERN_(MAX7219_GCODE, static void M7219());
- #if ENABLED(CONTROLLER_FAN_EDITABLE)
- static void M710();
- #endif
+ TERN_(CONTROLLER_FAN_EDITABLE, static void M710());
static void T(const uint8_t tool_index);
diff --git a/Marlin/src/gcode/geometry/G17-G19.cpp b/Marlin/src/gcode/geometry/G17-G19.cpp
index 14f3e80bb..7510eaba8 100644
--- a/Marlin/src/gcode/geometry/G17-G19.cpp
+++ b/Marlin/src/gcode/geometry/G17-G19.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/geometry/G53-G59.cpp b/Marlin/src/gcode/geometry/G53-G59.cpp
index e24247b2c..05bc52276 100644
--- a/Marlin/src/gcode/geometry/G53-G59.cpp
+++ b/Marlin/src/gcode/geometry/G53-G59.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/geometry/G92.cpp b/Marlin/src/gcode/geometry/G92.cpp
index 91a746dd7..1a0382ed7 100644
--- a/Marlin/src/gcode/geometry/G92.cpp
+++ b/Marlin/src/gcode/geometry/G92.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -99,5 +99,7 @@ void GcodeSuite::G92() {
if (sync_XYZ) sync_plan_position();
else if (sync_E) sync_plan_position_e();
- report_current_position();
+ #if DISABLED(DIRECT_STEPPING)
+ report_current_position();
+ #endif
}
diff --git a/Marlin/src/gcode/geometry/M206_M428.cpp b/Marlin/src/gcode/geometry/M206_M428.cpp
index 13e82a0c7..2a007427a 100644
--- a/Marlin/src/gcode/geometry/M206_M428.cpp
+++ b/Marlin/src/gcode/geometry/M206_M428.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/host/M110.cpp b/Marlin/src/gcode/host/M110.cpp
index f7b6dfd4f..b12b38ea0 100644
--- a/Marlin/src/gcode/host/M110.cpp
+++ b/Marlin/src/gcode/host/M110.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -27,5 +27,8 @@
* M110: Set Current Line Number
*/
void GcodeSuite::M110() {
- if (parser.seenval('N')) queue.last_N = parser.value_long();
+
+ if (parser.seenval('N'))
+ queue.last_N[queue.command_port()] = parser.value_long();
+
}
diff --git a/Marlin/src/gcode/host/M113.cpp b/Marlin/src/gcode/host/M113.cpp
index 872986561..ce826d6ac 100644
--- a/Marlin/src/gcode/host/M113.cpp
+++ b/Marlin/src/gcode/host/M113.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp
index ec5b950b6..85a38f646 100644
--- a/Marlin/src/gcode/host/M114.cpp
+++ b/Marlin/src/gcode/host/M114.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -38,11 +38,12 @@
char str[12];
LOOP_L_N(a, n) {
SERIAL_CHAR(' ', axis_codes[a], ':');
+ if (pos[a] >= 0) SERIAL_CHAR(' ');
SERIAL_ECHO(dtostrf(pos[a], 1, precision, str));
}
SERIAL_EOL();
}
- inline void report_xyz(const xyze_pos_t &pos) { report_xyze(pos, 3); }
+ inline void report_xyz(const xyze_pos_t &pos) { report_xyze(pos, XYZ); }
void report_xyz(const xyz_pos_t &pos, const uint8_t precision=3) {
char str[12];
@@ -178,7 +179,7 @@
report_xyze(from_steppers);
const xyze_float_t diff = from_steppers - leveled;
- SERIAL_ECHOPGM("Diff: ");
+ SERIAL_ECHOPGM("Diff: ");
report_xyze(diff);
}
@@ -213,8 +214,6 @@ void GcodeSuite::M114() {
if (parser.seen('R')) { report_real_position(); return; }
#endif
- #if ENABLED(M114_LEGACY)
- planner.synchronize();
- #endif
+ TERN_(M114_LEGACY, planner.synchronize());
report_current_position_projected();
}
diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp
index d74f909c4..c3ff9c8c1 100644
--- a/Marlin/src/gcode/host/M115.cpp
+++ b/Marlin/src/gcode/host/M115.cpp
@@ -16,13 +16,17 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#include "../gcode.h"
#include "../../inc/MarlinConfig.h"
+#if ENABLED(M115_GEOMETRY_REPORT)
+ #include "../../module/motion.h"
+#endif
+
#if ENABLED(EXTENDED_CAPABILITIES_REPORT)
static void cap_line(PGM_P const name, bool ena=false) {
SERIAL_ECHOPGM("Cap:");
@@ -44,14 +48,10 @@ void GcodeSuite::M115() {
#if ENABLED(EXTENDED_CAPABILITIES_REPORT)
// PAREN_COMMENTS
- #if ENABLED(PAREN_COMMENTS)
- cap_line(PSTR("PAREN_COMMENTS"), true);
- #endif
+ TERN_(PAREN_COMMENTS, cap_line(PSTR("PAREN_COMMENTS"), true));
// QUOTED_STRINGS
- #if ENABLED(GCODE_QUOTED_STRINGS)
- cap_line(PSTR("QUOTED_STRINGS"), true);
- #endif
+ TERN_(GCODE_QUOTED_STRINGS, cap_line(PSTR("QUOTED_STRINGS"), true));
// SERIAL_XON_XOFF
cap_line(PSTR("SERIAL_XON_XOFF"), ENABLED(SERIAL_XON_XOFF));
@@ -77,6 +77,9 @@ void GcodeSuite::M115() {
// AUTOLEVEL (G29)
cap_line(PSTR("AUTOLEVEL"), ENABLED(HAS_AUTOLEVEL));
+ // RUNOUT (M412, M600)
+ cap_line(PSTR("RUNOUT"), ENABLED(FILAMENT_RUNOUT_SENSOR));
+
// Z_PROBE (G30)
cap_line(PSTR("Z_PROBE"), ENABLED(HAS_BED_PROBE));
@@ -89,10 +92,9 @@ void GcodeSuite::M115() {
// SOFTWARE_POWER (M80, M81)
cap_line(PSTR("SOFTWARE_POWER"), ENABLED(PSU_CONTROL));
- // CASE LIGHTS (M355)
+ // TOGGLE_LIGHTS (M355)
cap_line(PSTR("TOGGLE_LIGHTS"), ENABLED(HAS_CASE_LIGHT));
-
- cap_line(PSTR("CASE_LIGHT_BRIGHTNESS"), TERN(HAS_CASE_LIGHT, PWM_PIN(CASE_LIGHT_PIN), 0));
+ cap_line(PSTR("CASE_LIGHT_BRIGHTNESS"), TERN0(HAS_CASE_LIGHT, PWM_PIN(CASE_LIGHT_PIN)));
// EMERGENCY_PARSER (M108, M112, M410, M876)
cap_line(PSTR("EMERGENCY_PARSER"), ENABLED(EMERGENCY_PARSER));
@@ -100,17 +102,52 @@ void GcodeSuite::M115() {
// PROMPT SUPPORT (M876)
cap_line(PSTR("PROMPT_SUPPORT"), ENABLED(HOST_PROMPT_SUPPORT));
+ // SDCARD (M20, M23, M24, etc.)
+ cap_line(PSTR("SDCARD"), ENABLED(SDSUPPORT));
+
// AUTOREPORT_SD_STATUS (M27 extension)
cap_line(PSTR("AUTOREPORT_SD_STATUS"), ENABLED(AUTO_REPORT_SD_STATUS));
+ // LONG_FILENAME_HOST_SUPPORT (M33)
+ cap_line(PSTR("LONG_FILENAME"), ENABLED(LONG_FILENAME_HOST_SUPPORT));
+
// THERMAL_PROTECTION
cap_line(PSTR("THERMAL_PROTECTION"), ENABLED(THERMALLY_SAFE));
// MOTION_MODES (M80-M89)
cap_line(PSTR("MOTION_MODES"), ENABLED(GCODE_MOTION_MODES));
+ // ARC_SUPPORT (G2-G3)
+ cap_line(PSTR("ARCS"), ENABLED(ARC_SUPPORT));
+
+ // BABYSTEPPING (M290)
+ cap_line(PSTR("BABYSTEPPING"), ENABLED(BABYSTEPPING));
+
// CHAMBER_TEMPERATURE (M141, M191)
cap_line(PSTR("CHAMBER_TEMPERATURE"), ENABLED(HAS_HEATED_CHAMBER));
+ // Machine Geometry
+ #if ENABLED(M115_GEOMETRY_REPORT)
+ const xyz_pos_t dmin = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS },
+ dmax = { X_MAX_POS, Y_MAX_POS, Z_MAX_POS };
+ xyz_pos_t cmin = dmin, cmax = dmax;
+ apply_motion_limits(cmin);
+ apply_motion_limits(cmax);
+ const xyz_pos_t lmin = dmin.asLogical(), lmax = dmax.asLogical(),
+ wmin = cmin.asLogical(), wmax = cmax.asLogical();
+ SERIAL_ECHOLNPAIR(
+ "area:{"
+ "full:{"
+ "min:{x:", lmin.x, ",y:", lmin.y, ",z:", lmin.z, "},"
+ "max:{x:", lmax.x, ",y:", lmax.y, ",z:", lmax.z, "}"
+ "},"
+ "work:{"
+ "min:{x:", wmin.x, ",y:", wmin.y, ",z:", wmin.z, "},"
+ "max:{x:", wmax.x, ",y:", wmax.y, ",z:", wmax.z, "}",
+ "}"
+ "}"
+ );
+ #endif
+
#endif // EXTENDED_CAPABILITIES_REPORT
}
diff --git a/Marlin/src/gcode/host/M118.cpp b/Marlin/src/gcode/host/M118.cpp
index ba52a4f81..3be290254 100644
--- a/Marlin/src/gcode/host/M118.cpp
+++ b/Marlin/src/gcode/host/M118.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -34,7 +34,7 @@
*/
void GcodeSuite::M118() {
bool hasE = false, hasA = false;
- #if NUM_SERIAL > 1
+ #if HAS_MULTI_SERIAL
int8_t port = -1; // Assume no redirect
#endif
char *p = parser.string_arg;
@@ -44,7 +44,7 @@ void GcodeSuite::M118() {
switch (p[0]) {
case 'A': hasA = true; break;
case 'E': hasE = true; break;
- #if NUM_SERIAL > 1
+ #if HAS_MULTI_SERIAL
case 'P': port = p[1] - '0'; break;
#endif
}
@@ -52,7 +52,7 @@ void GcodeSuite::M118() {
while (*p == ' ') ++p;
}
- #if NUM_SERIAL > 1
+ #if HAS_MULTI_SERIAL
const int8_t old_serial = serial_port_index;
if (WITHIN(port, 0, NUM_SERIAL))
serial_port_index = (
@@ -69,7 +69,5 @@ void GcodeSuite::M118() {
if (hasA) SERIAL_ECHOPGM("// ");
SERIAL_ECHOLN(p);
- #if NUM_SERIAL > 1
- serial_port_index = old_serial;
- #endif
+ TERN_(HAS_MULTI_SERIAL, serial_port_index = old_serial);
}
diff --git a/Marlin/src/gcode/host/M119.cpp b/Marlin/src/gcode/host/M119.cpp
index b3cb7290b..f0066bddf 100644
--- a/Marlin/src/gcode/host/M119.cpp
+++ b/Marlin/src/gcode/host/M119.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/host/M16.cpp b/Marlin/src/gcode/host/M16.cpp
index fd3320db9..1ac858039 100644
--- a/Marlin/src/gcode/host/M16.cpp
+++ b/Marlin/src/gcode/host/M16.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -33,7 +33,7 @@
void GcodeSuite::M16() {
if (strcmp_P(parser.string_arg, PSTR(MACHINE_NAME)))
- kill(GET_TEXT(MSG_EXPECTED_PRINTER));
+ kill(GET_TEXT(MSG_KILL_EXPECTED_PRINTER));
}
diff --git a/Marlin/src/gcode/host/M360.cpp b/Marlin/src/gcode/host/M360.cpp
new file mode 100644
index 000000000..87ca23bec
--- /dev/null
+++ b/Marlin/src/gcode/host/M360.cpp
@@ -0,0 +1,188 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(REPETIER_GCODE_M360)
+
+#include "../gcode.h"
+
+#include "../../module/motion.h"
+#include "../../module/planner.h"
+
+static void config_prefix(PGM_P const name, PGM_P const pref=nullptr) {
+ SERIAL_ECHOPGM("Config:");
+ if (pref) serialprintPGM(pref);
+ serialprintPGM(name);
+ SERIAL_CHAR(':');
+}
+static void config_line(PGM_P const name, const float val, PGM_P const pref=nullptr) {
+ config_prefix(name, pref);
+ SERIAL_ECHOLN(val);
+}
+
+/**
+ * M360: Report Firmware configuration
+ * in RepRapFirmware-compatible format
+ */
+void GcodeSuite::M360() {
+ PGMSTR(X_STR, "X");
+ PGMSTR(Y_STR, "Y");
+ PGMSTR(Z_STR, "Z");
+ PGMSTR(JERK_STR, "Jerk");
+
+ //
+ // Basics and Enabled items
+ //
+ config_line(PSTR("Baudrate"), BAUDRATE);
+ config_line(PSTR("InputBuffer"), MAX_CMD_SIZE);
+ config_line(PSTR("PrintlineCache"), BUFSIZE);
+ config_line(PSTR("MixingExtruder"), ENABLED(MIXING_EXTRUDER));
+ config_line(PSTR("SDCard"), ENABLED(SDSUPPORT));
+ config_line(PSTR("Fan"), ENABLED(HAS_FAN));
+ config_line(PSTR("LCD"), ENABLED(HAS_DISPLAY));
+ config_line(PSTR("SoftwarePowerSwitch"), 1);
+ config_line(PSTR("SupportLocalFilamentchange"), ENABLED(ADVANCED_PAUSE_FEATURE));
+ config_line(PSTR("CaseLights"), ENABLED(CASE_LIGHT_ENABLE));
+ config_line(PSTR("ZProbe"), ENABLED(HAS_BED_PROBE));
+ config_line(PSTR("Autolevel"), ENABLED(HAS_LEVELING));
+ config_line(PSTR("EEPROM"), ENABLED(EEPROM_SETTINGS));
+
+ //
+ // Homing Directions
+ //
+ PGMSTR(H_DIR_STR, "HomeDir");
+ config_line(H_DIR_STR, X_HOME_DIR, X_STR);
+ config_line(H_DIR_STR, Y_HOME_DIR, Y_STR);
+ config_line(H_DIR_STR, Z_HOME_DIR, Z_STR);
+
+ //
+ // XYZ Axis Jerk
+ //
+ #if HAS_CLASSIC_JERK
+ if (planner.max_jerk.x == planner.max_jerk.y)
+ config_line(PSTR("XY"), planner.max_jerk.x, JERK_STR);
+ else {
+ config_line(X_STR, planner.max_jerk.x, JERK_STR);
+ config_line(Y_STR, planner.max_jerk.y, JERK_STR);
+ }
+ config_line(Z_STR, planner.max_jerk.z, JERK_STR);
+ #endif
+
+ //
+ // Firmware Retraction
+ //
+ config_line(PSTR("SupportG10G11"), ENABLED(FWRETRACT));
+ #if ENABLED(FWRETRACT)
+ PGMSTR(RET_STR, "Retraction");
+ PGMSTR(UNRET_STR, "RetractionUndo");
+ PGMSTR(SPEED_STR, "Speed");
+ // M10 Retract with swap (long) moves
+ config_line(PSTR("Length"), fwretract.settings.retract_length, RET_STR);
+ config_line(SPEED_STR, fwretract.settings.retract_feedrate_mm_s, RET_STR);
+ config_line(PSTR("ZLift"), fwretract.settings.retract_zraise, RET_STR);
+ config_line(PSTR("LongLength"), fwretract.settings.swap_retract_length, RET_STR);
+ // M11 Recover (undo) with swap (long) moves
+ config_line(SPEED_STR, fwretract.settings.retract_recover_feedrate_mm_s, UNRET_STR);
+ config_line(PSTR("ExtraLength"), fwretract.settings.retract_recover_extra, UNRET_STR);
+ config_line(PSTR("ExtraLongLength"), fwretract.settings.swap_retract_recover_extra, UNRET_STR);
+ config_line(PSTR("LongSpeed"), fwretract.settings.swap_retract_recover_feedrate_mm_s, UNRET_STR);
+ #endif
+
+ //
+ // Workspace boundaries
+ //
+ const xyz_pos_t dmin = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS },
+ dmax = { X_MAX_POS, Y_MAX_POS, Z_MAX_POS };
+ xyz_pos_t cmin = dmin, cmax = dmax;
+ apply_motion_limits(cmin);
+ apply_motion_limits(cmax);
+ const xyz_pos_t wmin = cmin.asLogical(), wmax = cmax.asLogical();
+
+ PGMSTR(MIN_STR, "Min");
+ PGMSTR(MAX_STR, "Max");
+ PGMSTR(SIZE_STR, "Size");
+ config_line(MIN_STR, wmin.x, X_STR);
+ config_line(MIN_STR, wmin.y, Y_STR);
+ config_line(MIN_STR, wmin.z, Z_STR);
+ config_line(MAX_STR, wmax.x, X_STR);
+ config_line(MAX_STR, wmax.y, Y_STR);
+ config_line(MAX_STR, wmax.z, Z_STR);
+ config_line(SIZE_STR, wmax.x - wmin.x, X_STR);
+ config_line(SIZE_STR, wmax.y - wmin.y, Y_STR);
+ config_line(SIZE_STR, wmax.z - wmin.z, Z_STR);
+
+ //
+ // Print and Travel Acceleration
+ //
+ #define _ACCEL(A,B) _MIN(planner.settings.max_acceleration_mm_per_s2[A##_AXIS], planner.settings.B)
+ PGMSTR(P_ACC_STR, "PrintAccel");
+ PGMSTR(T_ACC_STR, "TravelAccel");
+ config_line(P_ACC_STR, _ACCEL(X, acceleration), X_STR);
+ config_line(P_ACC_STR, _ACCEL(Y, acceleration), Y_STR);
+ config_line(P_ACC_STR, _ACCEL(Z, acceleration), Z_STR);
+ config_line(T_ACC_STR, _ACCEL(X, travel_acceleration), X_STR);
+ config_line(T_ACC_STR, _ACCEL(Y, travel_acceleration), Y_STR);
+ config_line(T_ACC_STR, _ACCEL(Z, travel_acceleration), Z_STR);
+
+ config_prefix(PSTR("PrinterType"));
+ SERIAL_ECHOLNPGM(
+ TERN_(DELTA, "Delta")
+ TERN_(IS_SCARA, "SCARA")
+ TERN_(IS_CORE, "Core")
+ TERN_(IS_CARTESIAN, "Cartesian")
+ );
+
+ //
+ // Heated Bed
+ //
+ config_line(PSTR("HeatedBed"), ENABLED(HAS_HEATED_BED));
+ #if HAS_HEATED_BED
+ config_line(PSTR("MaxBedTemp"), BED_MAX_TARGET);
+ #endif
+
+ //
+ // Per-Extruder settings
+ //
+ config_line(PSTR("NumExtruder"), EXTRUDERS);
+ #if EXTRUDERS
+ #define DIAM_VALUE(N) TERN(NO_VOLUMETRICS, DEFAULT_NOMINAL_FILAMENT_DIA, planner.filament_size[N])
+ #if HAS_LINEAR_E_JERK
+ #define E_JERK_VAL(N) planner.max_e_jerk[E_INDEX_N(N)]
+ #elif HAS_CLASSIC_JERK
+ #define E_JERK_VAL(N) planner.max_jerk.e
+ #else
+ #define E_JERK_VAL(N) DEFAULT_EJERK
+ #endif
+ #define _EXTR_ITEM(N) do{ \
+ PGMSTR(EXTR_STR, "Extr." STRINGIFY(INCREMENT(N)) ":"); \
+ config_line(JERK_STR, E_JERK_VAL(N), EXTR_STR); \
+ config_line(PSTR("MaxSpeed"), planner.settings.max_feedrate_mm_s[E_AXIS_N(N)], EXTR_STR); \
+ config_line(PSTR("Acceleration"), planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(N)], EXTR_STR); \
+ config_line(PSTR("Diameter"), DIAM_VALUE(N), EXTR_STR); \
+ config_line(PSTR("MaxTemp"), (HEATER_##N##_MAXTEMP) - (HOTEND_OVERSHOOT), EXTR_STR); \
+ }while(0)
+
+ REPEAT(EXTRUDERS, _EXTR_ITEM);
+ #endif
+}
+
+#endif
diff --git a/Marlin/src/gcode/host/M876.cpp b/Marlin/src/gcode/host/M876.cpp
index fe0ca1541..0d8256cf0 100644
--- a/Marlin/src/gcode/host/M876.cpp
+++ b/Marlin/src/gcode/host/M876.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#include "../../inc/MarlinConfig.h"
diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp
index 190023b09..1d18b7060 100644
--- a/Marlin/src/gcode/lcd/M0_M1.cpp
+++ b/Marlin/src/gcode/lcd/M0_M1.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -77,15 +77,11 @@ void GcodeSuite::M0_M1() {
#endif
- #if ENABLED(HOST_PROMPT_SUPPORT)
- host_prompt_do(PROMPT_USER_CONTINUE, parser.codenum ? PSTR("M1 Stop") : PSTR("M0 Stop"), CONTINUE_STR);
- #endif
+ TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, parser.codenum ? PSTR("M1 Stop") : PSTR("M0 Stop"), CONTINUE_STR));
wait_for_user_response(ms);
- #if HAS_LCD_MENU
- ui.reset_status();
- #endif
+ TERN_(HAS_LCD_MENU, ui.reset_status());
}
#endif // HAS_RESUME_CONTINUE
diff --git a/Marlin/src/gcode/lcd/M117.cpp b/Marlin/src/gcode/lcd/M117.cpp
index 7e314731f..8459135f3 100644
--- a/Marlin/src/gcode/lcd/M117.cpp
+++ b/Marlin/src/gcode/lcd/M117.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/lcd/M145.cpp b/Marlin/src/gcode/lcd/M145.cpp
index 311672753..abd4dcc74 100644
--- a/Marlin/src/gcode/lcd/M145.cpp
+++ b/Marlin/src/gcode/lcd/M145.cpp
@@ -16,13 +16,13 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#include "../../inc/MarlinConfig.h"
-#if HOTENDS && HAS_LCD_MENU
+#if PREHEAT_COUNT
#include "../gcode.h"
#include "../../lcd/ultralcd.h"
@@ -37,25 +37,23 @@
*/
void GcodeSuite::M145() {
const uint8_t material = (uint8_t)parser.intval('S');
- if (material >= COUNT(ui.preheat_hotend_temp))
+ if (material >= PREHEAT_COUNT)
SERIAL_ERROR_MSG(STR_ERR_MATERIAL_INDEX);
else {
- int v;
- if (parser.seenval('H')) {
- v = parser.value_int();
- ui.preheat_hotend_temp[material] = constrain(v, EXTRUDE_MINTEMP, HEATER_0_MAXTEMP - 15);
- }
- if (parser.seenval('F')) {
- v = parser.value_int();
- ui.preheat_fan_speed[material] = (uint8_t)constrain(v, 0, 255);
- }
- #if TEMP_SENSOR_BED != 0
- if (parser.seenval('B')) {
- v = parser.value_int();
- ui.preheat_bed_temp[material] = constrain(v, BED_MINTEMP, BED_MAXTEMP - 10);
- }
+ preheat_t &mat = ui.material_preset[material];
+ #if HAS_HOTEND
+ if (parser.seenval('H'))
+ mat.hotend_temp = constrain(parser.value_int(), EXTRUDE_MINTEMP, (HEATER_0_MAXTEMP) - (HOTEND_OVERSHOOT));
+ #endif
+ #if HAS_HEATED_BED
+ if (parser.seenval('B'))
+ mat.bed_temp = constrain(parser.value_int(), BED_MINTEMP, BED_MAX_TARGET);
+ #endif
+ #if HAS_FAN
+ if (parser.seenval('F'))
+ mat.fan_speed = constrain(parser.value_int(), 0, 255);
#endif
}
}
-#endif // HOTENDS && HAS_LCD_MENU
+#endif // PREHEAT_COUNT
diff --git a/Marlin/src/gcode/lcd/M250.cpp b/Marlin/src/gcode/lcd/M250.cpp
index 839fd2596..f42daaeac 100644
--- a/Marlin/src/gcode/lcd/M250.cpp
+++ b/Marlin/src/gcode/lcd/M250.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/lcd/M300.cpp b/Marlin/src/gcode/lcd/M300.cpp
index 5d7e766b2..56d9ee5d7 100644
--- a/Marlin/src/gcode/lcd/M300.cpp
+++ b/Marlin/src/gcode/lcd/M300.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/lcd/M73.cpp b/Marlin/src/gcode/lcd/M73.cpp
index 347c42c44..7a5454419 100644
--- a/Marlin/src/gcode/lcd/M73.cpp
+++ b/Marlin/src/gcode/lcd/M73.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -33,9 +33,6 @@
*
* Example:
* M73 P25 ; Set progress to 25%
- *
- * Notes:
- * This has no effect during an SD print job
*/
void GcodeSuite::M73() {
if (parser.seen('P'))
diff --git a/Marlin/src/gcode/motion/G0_G1.cpp b/Marlin/src/gcode/motion/G0_G1.cpp
index 069d76fda..3aa082c25 100644
--- a/Marlin/src/gcode/motion/G0_G1.cpp
+++ b/Marlin/src/gcode/motion/G0_G1.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -69,7 +69,7 @@ void GcodeSuite::G0_G1(
#endif
#endif
- get_destination_from_command(); // Process X Y Z E F parameters
+ get_destination_from_command(); // Get X Y Z E F (and set cutter power)
#ifdef G0_FEEDRATE
if (fast_move) {
diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp
index b0fb299ab..59a534635 100644
--- a/Marlin/src/gcode/motion/G2_G3.cpp
+++ b/Marlin/src/gcode/motion/G2_G3.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -70,14 +70,12 @@ void plan_arc(
ab_float_t rvec = -offset;
const float radius = HYPOT(rvec.a, rvec.b),
- #if ENABLED(AUTO_BED_LEVELING_UBL)
- start_L = current_position[l_axis],
- #endif
center_P = current_position[p_axis] - rvec.a,
center_Q = current_position[q_axis] - rvec.b,
rt_X = cart[p_axis] - center_P,
rt_Y = cart[q_axis] - center_Q,
- linear_travel = cart[l_axis] - current_position[l_axis],
+ start_L = current_position[l_axis],
+ linear_travel = cart[l_axis] - start_L,
extruder_travel = cart.e - current_position.e;
// CCW angle of rotation between position and target from the circle center. Only one atan2() trig computation required.
@@ -105,17 +103,22 @@ void plan_arc(
const feedRate_t scaled_fr_mm_s = MMS_SCALED(feedrate_mm_s);
- #ifdef ARC_SEGMENTS_PER_R
- float seg_length = MM_PER_ARC_SEGMENT * radius;
- LIMIT(seg_length, MM_PER_ARC_SEGMENT, ARC_SEGMENTS_PER_R);
- #elif ARC_SEGMENTS_PER_SEC
- float seg_length = scaled_fr_mm_s * RECIPROCAL(ARC_SEGMENTS_PER_SEC);
- NOLESS(seg_length, MM_PER_ARC_SEGMENT);
- #else
- constexpr float seg_length = MM_PER_ARC_SEGMENT;
- #endif
+ // Start with a nominal segment length
+ float seg_length = (
+ #ifdef ARC_SEGMENTS_PER_R
+ constrain(MM_PER_ARC_SEGMENT * radius, MM_PER_ARC_SEGMENT, ARC_SEGMENTS_PER_R)
+ #elif ARC_SEGMENTS_PER_SEC
+ _MAX(scaled_fr_mm_s * RECIPROCAL(ARC_SEGMENTS_PER_SEC), MM_PER_ARC_SEGMENT)
+ #else
+ MM_PER_ARC_SEGMENT
+ #endif
+ );
+ // Divide total travel by nominal segment length
uint16_t segments = FLOOR(mm_of_travel / seg_length);
- NOLESS(segments, min_segments);
+ if (segments < min_segments) { // Too few segments?
+ segments = min_segments; // More segments
+ }
+ seg_length = mm_of_travel / segments;
/**
* Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector,
@@ -148,8 +151,9 @@ void plan_arc(
const float theta_per_segment = angular_travel / segments,
linear_per_segment = linear_travel / segments,
extruder_per_segment = extruder_travel / segments,
- sin_T = theta_per_segment,
- cos_T = 1 - 0.5f * sq(theta_per_segment); // Small angle approximation
+ sq_theta_per_segment = sq(theta_per_segment),
+ sin_T = theta_per_segment - sq_theta_per_segment*theta_per_segment/6,
+ cos_T = 1 - 0.5f * sq_theta_per_segment; // Small angle approximation
// Initialize the linear axis
raw[l_axis] = current_position[l_axis];
@@ -157,7 +161,6 @@ void plan_arc(
// Initialize the extruder axis
raw.e = current_position.e;
-
#if ENABLED(SCARA_FEEDRATE_SCALING)
const float inv_duration = scaled_fr_mm_s / seg_length;
#endif
@@ -216,19 +219,16 @@ void plan_arc(
planner.apply_leveling(raw);
#endif
- if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, seg_length
+ if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0
#if ENABLED(SCARA_FEEDRATE_SCALING)
, inv_duration
#endif
- ))
- break;
+ )) break;
}
// Ensure last segment arrives at target location.
raw = cart;
- #if ENABLED(AUTO_BED_LEVELING_UBL)
- raw[l_axis] = start_L;
- #endif
+ TERN_(AUTO_BED_LEVELING_UBL, raw[l_axis] = start_L);
apply_motion_limits(raw);
@@ -242,10 +242,9 @@ void plan_arc(
#endif
);
- #if ENABLED(AUTO_BED_LEVELING_UBL)
- raw[l_axis] = start_L;
- #endif
+ TERN_(AUTO_BED_LEVELING_UBL, raw[l_axis] = start_L);
current_position = raw;
+
} // plan_arc
/**
@@ -283,11 +282,9 @@ void GcodeSuite::G2_G3(const bool clockwise) {
relative_mode = true;
#endif
- get_destination_from_command();
+ get_destination_from_command(); // Get X Y Z E F (and set cutter power)
- #if ENABLED(SF_ARC_FIX)
- relative_mode = relative_mode_backup;
- #endif
+ TERN_(SF_ARC_FIX, relative_mode = relative_mode_backup);
ab_float_t arc_offset = { 0, 0 };
if (parser.seenval('R')) {
diff --git a/Marlin/src/gcode/motion/G4.cpp b/Marlin/src/gcode/motion/G4.cpp
index d157face9..3a37fe5b2 100644
--- a/Marlin/src/gcode/motion/G4.cpp
+++ b/Marlin/src/gcode/motion/G4.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/motion/G5.cpp b/Marlin/src/gcode/motion/G5.cpp
index 89b45ce8f..35cc42802 100644
--- a/Marlin/src/gcode/motion/G5.cpp
+++ b/Marlin/src/gcode/motion/G5.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/motion/G6.cpp b/Marlin/src/gcode/motion/G6.cpp
new file mode 100644
index 000000000..168dc28ab
--- /dev/null
+++ b/Marlin/src/gcode/motion/G6.cpp
@@ -0,0 +1,61 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(DIRECT_STEPPING)
+
+#include "../../feature/direct_stepping.h"
+
+#include "../gcode.h"
+#include "../../module/planner.h"
+
+/**
+ * G6: Direct Stepper Move
+ */
+void GcodeSuite::G6() {
+ // TODO: feedrate support?
+ if (parser.seen('R'))
+ planner.last_page_step_rate = parser.value_ulong();
+
+ if (!DirectStepping::Config::DIRECTIONAL) {
+ if (parser.seen('X')) planner.last_page_dir.x = !!parser.value_byte();
+ if (parser.seen('Y')) planner.last_page_dir.y = !!parser.value_byte();
+ if (parser.seen('Z')) planner.last_page_dir.z = !!parser.value_byte();
+ if (parser.seen('E')) planner.last_page_dir.e = !!parser.value_byte();
+ }
+
+ // No index means we just set the state
+ if (!parser.seen('I')) return;
+
+ // No speed is set, can't schedule the move
+ if (!planner.last_page_step_rate) return;
+
+ const page_idx_t page_idx = (page_idx_t) parser.value_ulong();
+
+ uint16_t num_steps = DirectStepping::Config::TOTAL_STEPS;
+ if (parser.seen('S')) num_steps = parser.value_ushort();
+
+ planner.buffer_page(page_idx, 0, num_steps);
+ reset_stepper_timeout();
+}
+
+#endif // DIRECT_STEPPING
diff --git a/Marlin/src/gcode/motion/G80.cpp b/Marlin/src/gcode/motion/G80.cpp
index 700038df0..f674596dd 100644
--- a/Marlin/src/gcode/motion/G80.cpp
+++ b/Marlin/src/gcode/motion/G80.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/motion/M290.cpp b/Marlin/src/gcode/motion/M290.cpp
index 5fef948fa..7158525ed 100644
--- a/Marlin/src/gcode/motion/M290.cpp
+++ b/Marlin/src/gcode/motion/M290.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -41,14 +41,10 @@
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
FORCE_INLINE void mod_probe_offset(const float &offs) {
- if (true
- #if ENABLED(BABYSTEP_HOTEND_Z_OFFSET)
- && active_extruder == 0
- #endif
- ) {
+ if (TERN1(BABYSTEP_HOTEND_Z_OFFSET, active_extruder == 0)) {
probe.offset.z += offs;
SERIAL_ECHO_START();
- SERIAL_ECHOLNPAIR(STR_PROBE_OFFSET STR_Z ": ", probe.offset.z);
+ SERIAL_ECHOLNPAIR(STR_PROBE_OFFSET " " STR_Z, probe.offset.z);
}
else {
#if ENABLED(BABYSTEP_HOTEND_Z_OFFSET)
diff --git a/Marlin/src/gcode/parser.cpp b/Marlin/src/gcode/parser.cpp
index 4ece6ede4..91a24d1dd 100644
--- a/Marlin/src/gcode/parser.cpp
+++ b/Marlin/src/gcode/parser.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -28,7 +28,7 @@
#include "../MarlinCore.h"
-#if NUM_SERIAL > 1
+#if HAS_MULTI_SERIAL
#include "queue.h"
#endif
@@ -83,9 +83,7 @@ void GCodeParser::reset() {
string_arg = nullptr; // No whole line argument
command_letter = '?'; // No command letter
codenum = 0; // No command code
- #if ENABLED(USE_GCODE_SUBCODES)
- subcode = 0; // No command sub-code
- #endif
+ TERN_(USE_GCODE_SUBCODES, subcode = 0); // No command sub-code
#if ENABLED(FASTER_GCODE_PARSER)
codebits = 0; // No codes yet
//ZERO(param); // No parameters (should be safe to comment out this line)
@@ -119,9 +117,8 @@ void GCodeParser::parse(char *p) {
reset(); // No codes to report
auto uppercase = [](char c) {
- #if ENABLED(GCODE_CASE_INSENSITIVE)
- if (WITHIN(c, 'a', 'z')) c += 'A' - 'a';
- #endif
+ if (TERN0(GCODE_CASE_INSENSITIVE, WITHIN(c, 'a', 'z')))
+ c += 'A' - 'a';
return c;
};
@@ -130,9 +127,7 @@ void GCodeParser::parse(char *p) {
// Skip N[-0-9] if included in the command line
if (uppercase(*p) == 'N' && NUMERIC_SIGNED(p[1])) {
- #if ENABLED(FASTER_GCODE_PARSER)
- //set('N', p + 1); // (optional) Set the 'N' parameter value
- #endif
+ //TERN_(FASTER_GCODE_PARSER, set('N', p + 1)); // (optional) Set the 'N' parameter value
p += 2; // skip N[-0-9]
while (NUMERIC(*p)) ++p; // skip [0-9]*
while (*p == ' ') ++p; // skip [ ]*
@@ -213,9 +208,7 @@ void GCodeParser::parse(char *p) {
)
) {
motion_mode_codenum = codenum;
- #if ENABLED(USE_GCODE_SUBCODES)
- motion_mode_subcode = subcode;
- #endif
+ TERN_(USE_GCODE_SUBCODES, motion_mode_subcode = subcode);
}
#endif
@@ -232,9 +225,7 @@ void GCodeParser::parse(char *p) {
if (motion_mode_codenum < 0) return;
command_letter = 'G';
codenum = motion_mode_codenum;
- #if ENABLED(USE_GCODE_SUBCODES)
- subcode = motion_mode_subcode;
- #endif
+ TERN_(USE_GCODE_SUBCODES, subcode = motion_mode_subcode);
p--; // Back up one character to use the current parameter
break;
#endif // GCODE_MOTION_MODES
@@ -331,13 +322,9 @@ void GCodeParser::parse(char *p) {
#endif
}
- #if ENABLED(DEBUG_GCODE_PARSER)
- if (debug) SERIAL_EOL();
- #endif
+ if (TERN0(DEBUG_GCODE_PARSER, debug)) SERIAL_EOL();
- #if ENABLED(FASTER_GCODE_PARSER)
- set(param, valptr); // Set parameter exists and pointer (nullptr for no value)
- #endif
+ TERN_(FASTER_GCODE_PARSER, set(param, valptr)); // Set parameter exists and pointer (nullptr for no value)
}
else if (!string_arg) { // Not A-Z? First time, keep as the string_arg
string_arg = p - 1;
diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h
index 06e41ccf1..5474e5e5f 100644
--- a/Marlin/src/gcode/parser.h
+++ b/Marlin/src/gcode/parser.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/gcode/probe/G30.cpp b/Marlin/src/gcode/probe/G30.cpp
index 21d56b3fd..4347f55aa 100644
--- a/Marlin/src/gcode/probe/G30.cpp
+++ b/Marlin/src/gcode/probe/G30.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -46,22 +46,19 @@ void GcodeSuite::G30() {
if (!probe.can_reach(pos)) return;
// Disable leveling so the planner won't mess with us
- #if HAS_LEVELING
- set_bed_leveling_enabled(false);
- #endif
+ TERN_(HAS_LEVELING, set_bed_leveling_enabled(false));
remember_feedrate_scaling_off();
const ProbePtRaise raise_after = parser.boolval('E', true) ? PROBE_PT_STOW : PROBE_PT_NONE;
const float measured_z = probe.probe_at_point(pos, raise_after, 1);
if (!isnan(measured_z))
- SERIAL_ECHOLNPAIR("Bed X: ", FIXFLOAT(pos.x), " Y: ", FIXFLOAT(pos.y), " Z: ", FIXFLOAT(measured_z));
+ SERIAL_ECHOLNPAIR("Bed X: ", pos.x, " Y: ", pos.y, " Z: ", measured_z);
restore_feedrate_and_scaling();
- #ifdef Z_AFTER_PROBING
- if (raise_after == PROBE_PT_STOW) probe.move_z_after_probing();
- #endif
+ if (raise_after == PROBE_PT_STOW)
+ probe.move_z_after_probing();
report_current_position();
}
diff --git a/Marlin/src/gcode/probe/G31_G32.cpp b/Marlin/src/gcode/probe/G31_G32.cpp
index e2e43e35e..af44257d6 100644
--- a/Marlin/src/gcode/probe/G31_G32.cpp
+++ b/Marlin/src/gcode/probe/G31_G32.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/probe/G38.cpp b/Marlin/src/gcode/probe/G38.cpp
index 512e1ff89..b06cd4735 100644
--- a/Marlin/src/gcode/probe/G38.cpp
+++ b/Marlin/src/gcode/probe/G38.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/probe/M401_M402.cpp b/Marlin/src/gcode/probe/M401_M402.cpp
index a0a6c1cec..8e9bd11b8 100644
--- a/Marlin/src/gcode/probe/M401_M402.cpp
+++ b/Marlin/src/gcode/probe/M401_M402.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -41,9 +41,7 @@ void GcodeSuite::M401() {
*/
void GcodeSuite::M402() {
probe.stow();
- #ifdef Z_AFTER_PROBING
- probe.move_z_after_probing();
- #endif
+ probe.move_z_after_probing();
report_current_position();
}
diff --git a/Marlin/src/gcode/probe/M851.cpp b/Marlin/src/gcode/probe/M851.cpp
index c2e746cf0..ee60e9ebc 100644
--- a/Marlin/src/gcode/probe/M851.cpp
+++ b/Marlin/src/gcode/probe/M851.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/probe/M951.cpp b/Marlin/src/gcode/probe/M951.cpp
index c7e4ea8a7..f461fc2b0 100644
--- a/Marlin/src/gcode/probe/M951.cpp
+++ b/Marlin/src/gcode/probe/M951.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -46,9 +46,7 @@ void mpe_settings_init() {
mpe_settings.parking_xpos[0] = pex[0]; // M951 L
mpe_settings.parking_xpos[1] = pex[1]; // M951 R
mpe_settings.grab_distance = PARKING_EXTRUDER_GRAB_DISTANCE; // M951 I
- #if HAS_HOME_OFFSET
- set_home_offset(X_AXIS, mpe_settings.grab_distance * -1);
- #endif
+ TERN_(HAS_HOME_OFFSET, set_home_offset(X_AXIS, mpe_settings.grab_distance * -1));
mpe_settings.slow_feedrate = MMM_TO_MMS(MPE_SLOW_SPEED); // M951 J
mpe_settings.fast_feedrate = MMM_TO_MMS(MPE_FAST_SPEED); // M951 H
mpe_settings.travel_distance = MPE_TRAVEL_DISTANCE; // M951 D
@@ -61,9 +59,7 @@ void GcodeSuite::M951() {
if (parser.seenval('R')) mpe_settings.parking_xpos[1] = parser.value_linear_units();
if (parser.seenval('I')) {
mpe_settings.grab_distance = parser.value_linear_units();
- #if HAS_HOME_OFFSET
- set_home_offset(X_AXIS, mpe_settings.grab_distance * -1);
- #endif
+ TERN_(HAS_HOME_OFFSET, set_home_offset(X_AXIS, mpe_settings.grab_distance * -1));
}
if (parser.seenval('J')) mpe_settings.slow_feedrate = MMM_TO_MMS(parser.value_linear_units());
if (parser.seenval('H')) mpe_settings.fast_feedrate = MMM_TO_MMS(parser.value_linear_units());
diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp
index abb50b960..c77db0bf2 100644
--- a/Marlin/src/gcode/queue.cpp
+++ b/Marlin/src/gcode/queue.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -52,7 +52,7 @@ GCodeQueue queue;
* sending commands to Marlin, and lines will be checked for sequentiality.
* M110 N sets the current line number.
*/
-long gcode_N, GCodeQueue::last_N;
+long GCodeQueue::last_N[NUM_SERIAL];
/**
* GCode Command Queue
@@ -72,7 +72,7 @@ char GCodeQueue::command_buffer[BUFSIZE][MAX_CMD_SIZE];
/*
* The port that the command was received on
*/
-#if NUM_SERIAL > 1
+#if HAS_MULTI_SERIAL
int16_t GCodeQueue::port[BUFSIZE];
#endif
@@ -86,11 +86,15 @@ static int serial_count[NUM_SERIAL] = { 0 };
bool send_ok[BUFSIZE];
/**
- * Next Injected Command pointer. nullptr if no commands are being injected.
- * Used by Marlin internally to ensure that commands initiated from within
- * are enqueued ahead of any pending serial or sd card commands.
+ * Next Injected PROGMEM Command pointer. (nullptr == empty)
+ * Internal commands are enqueued ahead of serial / SD commands.
*/
-static PGM_P injected_commands_P = nullptr;
+PGM_P GCodeQueue::injected_commands_P; // = nullptr
+
+/**
+ * Injected SRAM Commands
+ */
+char GCodeQueue::injected_commands[64]; // = { 0 }
GCodeQueue::GCodeQueue() {
// Send "ok" after commands by default
@@ -101,7 +105,7 @@ GCodeQueue::GCodeQueue() {
* Check whether there are any commands yet to be executed
*/
bool GCodeQueue::has_commands_queued() {
- return queue.length || injected_commands_P;
+ return queue.length || injected_commands_P || injected_commands[0];
}
/**
@@ -115,17 +119,13 @@ void GCodeQueue::clear() {
* Once a new command is in the ring buffer, call this to commit it
*/
void GCodeQueue::_commit_command(bool say_ok
- #if NUM_SERIAL > 1
+ #if HAS_MULTI_SERIAL
, int16_t p/*=-1*/
#endif
) {
send_ok[index_w] = say_ok;
- #if NUM_SERIAL > 1
- port[index_w] = p;
- #endif
- #if ENABLED(POWER_LOSS_RECOVERY)
- recovery.commit_sdpos(index_w);
- #endif
+ TERN_(HAS_MULTI_SERIAL, port[index_w] = p);
+ TERN_(POWER_LOSS_RECOVERY, recovery.commit_sdpos(index_w));
if (++index_w >= BUFSIZE) index_w = 0;
length++;
}
@@ -136,14 +136,14 @@ void GCodeQueue::_commit_command(bool say_ok
* Return false for a full buffer, or if the 'command' is a comment.
*/
bool GCodeQueue::_enqueue(const char* cmd, bool say_ok/*=false*/
- #if NUM_SERIAL > 1
+ #if HAS_MULTI_SERIAL
, int16_t pn/*=-1*/
#endif
) {
if (*cmd == ';' || length >= BUFSIZE) return false;
strcpy(command_buffer[index_w], cmd);
_commit_command(say_ok
- #if NUM_SERIAL > 1
+ #if HAS_MULTI_SERIAL
, pn
#endif
);
@@ -172,11 +172,10 @@ bool GCodeQueue::enqueue_one(const char* cmd) {
}
/**
- * Process the next "immediate" command.
- * Return 'true' if any commands were processed,
- * or remain to process.
+ * Process the next "immediate" command from PROGMEM.
+ * Return 'true' if any commands were processed.
*/
-bool GCodeQueue::process_injected_command() {
+bool GCodeQueue::process_injected_command_P() {
if (injected_commands_P == nullptr) return false;
char c;
@@ -198,12 +197,32 @@ bool GCodeQueue::process_injected_command() {
}
/**
- * Enqueue one or many commands to run from program memory.
- * Do not inject a comment or use leading spaces!
- * Aborts the current queue, if any.
- * Note: process_injected_command() will be called to drain any commands afterwards
+ * Process the next "immediate" command from SRAM.
+ * Return 'true' if any commands were processed.
*/
-void GCodeQueue::inject_P(PGM_P const pgcode) { injected_commands_P = pgcode; }
+bool GCodeQueue::process_injected_command() {
+ if (injected_commands[0] == '\0') return false;
+
+ char c;
+ size_t i = 0;
+ while ((c = injected_commands[i]) && c != '\n') i++;
+
+ // Execute a non-blank command
+ if (i) {
+ injected_commands[i] = '\0';
+ parser.parse(injected_commands);
+ gcode.process_parsed_command();
+ }
+
+ // Copy the next command into place
+ for (
+ uint8_t d = 0, s = i + !!c; // dst, src
+ (injected_commands[d] = injected_commands[s]); // copy, exit if 0
+ d++, s++ // next dst, src
+ );
+
+ return true;
+}
/**
* Enqueue and return only when commands are actually enqueued.
@@ -255,8 +274,8 @@ void GCodeQueue::enqueue_now_P(PGM_P const pgcode) {
* B Block queue space remaining
*/
void GCodeQueue::ok_to_send() {
- #if NUM_SERIAL > 1
- const int16_t pn = port[index_r];
+ #if HAS_MULTI_SERIAL
+ const int16_t pn = command_port();
if (pn < 0) return;
PORT_REDIRECT(pn); // Reply to the serial port that sent the command
#endif
@@ -270,8 +289,8 @@ void GCodeQueue::ok_to_send() {
while (NUMERIC_SIGNED(*p))
SERIAL_ECHO(*p++);
}
- SERIAL_ECHOPAIR_P(SP_P_STR, int(planner.moves_free()));
- SERIAL_ECHOPAIR(" B", int(BUFSIZE - length));
+ SERIAL_ECHOPAIR_P(SP_P_STR, int(planner.moves_free()),
+ SP_B_STR, int(BUFSIZE - length));
#endif
SERIAL_EOL();
}
@@ -281,30 +300,25 @@ void GCodeQueue::ok_to_send() {
* indicate that a command needs to be re-sent.
*/
void GCodeQueue::flush_and_request_resend() {
- #if NUM_SERIAL > 1
- const int16_t pn = port[index_r];
+ const int16_t pn = command_port();
+ #if HAS_MULTI_SERIAL
if (pn < 0) return;
PORT_REDIRECT(pn); // Reply to the serial port that sent the command
#endif
SERIAL_FLUSH();
SERIAL_ECHOPGM(STR_RESEND);
- SERIAL_ECHOLN(last_N + 1);
+ SERIAL_ECHOLN(last_N[pn] + 1);
ok_to_send();
}
inline bool serial_data_available() {
- return false
- || MYSERIAL0.available()
- #if NUM_SERIAL > 1
- || MYSERIAL1.available()
- #endif
- ;
+ return MYSERIAL0.available() || TERN0(HAS_MULTI_SERIAL, MYSERIAL1.available());
}
inline int read_serial(const uint8_t index) {
switch (index) {
case 0: return MYSERIAL0.read();
- #if NUM_SERIAL > 1
+ #if HAS_MULTI_SERIAL
case 1: return MYSERIAL1.read();
#endif
default: return -1;
@@ -315,7 +329,7 @@ void GCodeQueue::gcode_line_error(PGM_P const err, const int8_t pn) {
PORT_REDIRECT(pn); // Reply to the serial port that sent the command
SERIAL_ERROR_START();
serialprintPGM(err);
- SERIAL_ECHOLN(last_N);
+ SERIAL_ECHOLN(last_N[pn]);
while (read_serial(pn) != -1); // Clear out the RX buffer
flush_and_request_resend();
serial_count[pn] = 0;
@@ -373,9 +387,15 @@ inline void process_stream_char(const char c, uint8_t &sis, char (&buff)[MAX_CMD
}
#endif
- buff[ind++] = c;
- if (ind >= MAX_CMD_SIZE - 1)
- sis = PS_EOL; // Skip the rest on overflow
+ // Backspace erases previous characters
+ if (c == 0x08) {
+ if (ind) buff[--ind] = '\0';
+ }
+ else {
+ buff[ind++] = c;
+ if (ind >= MAX_CMD_SIZE - 1)
+ sis = PS_EOL; // Skip the rest on overflow
+ }
}
/**
@@ -454,9 +474,9 @@ void GCodeQueue::get_serial_commands() {
if (n2pos) npos = n2pos;
}
- gcode_N = strtol(npos + 1, nullptr, 10);
+ const long gcode_N = strtol(npos + 1, nullptr, 10);
- if (gcode_N != last_N + 1 && !M110)
+ if (gcode_N != last_N[i] + 1 && !M110)
return gcode_line_error(PSTR(STR_ERR_LINE_NO), i);
char *apos = strrchr(command, '*');
@@ -469,7 +489,7 @@ void GCodeQueue::get_serial_commands() {
else
return gcode_line_error(PSTR(STR_ERR_NO_CHECKSUM), i);
- last_N = gcode_N;
+ last_N[i] = gcode_N;
}
#if ENABLED(SDSUPPORT)
// Pronterface "M29" and "M29 " has no line number
@@ -502,14 +522,12 @@ void GCodeQueue::get_serial_commands() {
#if DISABLED(EMERGENCY_PARSER)
// Process critical commands early
- if (strcmp(command, "M108") == 0) {
+ if (strcmp_P(command, PSTR("M108")) == 0) {
wait_for_heatup = false;
- #if HAS_LCD_MENU
- wait_for_user = false;
- #endif
+ TERN_(HAS_LCD_MENU, wait_for_user = false);
}
- if (strcmp(command, "M112") == 0) kill(M112_KILL_STR, nullptr, true);
- if (strcmp(command, "M410") == 0) quickstop_stepper();
+ if (strcmp_P(command, PSTR("M112")) == 0) kill(M112_KILL_STR, nullptr, true);
+ if (strcmp_P(command, PSTR("M410")) == 0) quickstop_stepper();
#endif
#if defined(NO_TIMEOUTS) && NO_TIMEOUTS > 0
@@ -518,7 +536,7 @@ void GCodeQueue::get_serial_commands() {
// Add the command to the queue
_enqueue(serial_line_buffer[i], true
- #if NUM_SERIAL > 1
+ #if HAS_MULTI_SERIAL
, i
#endif
);
@@ -575,7 +593,7 @@ void GCodeQueue::get_serial_commands() {
/**
* Add to the circular command queue the next command from:
- * - The command-injection queue (injected_commands_P)
+ * - The command-injection queues (injected_commands_P, injected_commands)
* - The active serial input (usually USB)
* - The SD card file being actively printed
*/
@@ -583,9 +601,7 @@ void GCodeQueue::get_available_commands() {
get_serial_commands();
- #if ENABLED(SDSUPPORT)
- get_sdcard_commands();
- #endif
+ TERN_(SDSUPPORT, get_sdcard_commands());
}
/**
@@ -594,7 +610,7 @@ void GCodeQueue::get_available_commands() {
void GCodeQueue::advance() {
// Process immediate commands
- if (process_injected_command()) return;
+ if (process_injected_command_P() || process_injected_command()) return;
// Return if the G-code buffer is empty
if (!length) return;
diff --git a/Marlin/src/gcode/queue.h b/Marlin/src/gcode/queue.h
index 6a87d47ac..966af2871 100644
--- a/Marlin/src/gcode/queue.h
+++ b/Marlin/src/gcode/queue.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -35,7 +35,8 @@ public:
* commands to Marlin, and lines will be checked for sequentiality.
* M110 N sets the current line number.
*/
- static long last_N;
+
+ static long last_N[NUM_SERIAL];
/**
* GCode Command Queue
@@ -51,13 +52,17 @@ public:
static char command_buffer[BUFSIZE][MAX_CMD_SIZE];
- /*
+ /**
* The port that the command was received on
*/
- #if NUM_SERIAL > 1
+ #if HAS_MULTI_SERIAL
static int16_t port[BUFSIZE];
#endif
+ static int16_t command_port() {
+ return TERN0(HAS_MULTI_SERIAL, port[index_r]);
+ }
+
GCodeQueue();
/**
@@ -66,11 +71,30 @@ public:
static void clear();
/**
- * Enqueue one or many commands to run from program memory.
- * Aborts the current queue, if any.
- * Note: process_injected_command() will process them.
+ * Next Injected Command (PROGMEM) pointer. (nullptr == empty)
+ * Internal commands are enqueued ahead of serial / SD commands.
*/
- static void inject_P(PGM_P const pgcode);
+ static PGM_P injected_commands_P;
+
+ /**
+ * Injected Commands (SRAM)
+ */
+ static char injected_commands[64];
+
+ /**
+ * Enqueue command(s) to run from PROGMEM. Drained by process_injected_command_P().
+ * Don't inject comments or use leading spaces!
+ * Aborts the current PROGMEM queue so only use for one or two commands.
+ */
+ static inline void inject_P(PGM_P const pgcode) { injected_commands_P = pgcode; }
+
+ /**
+ * Enqueue command(s) to run from SRAM. Drained by process_injected_command().
+ * Aborts the current SRAM queue so only use for one or two commands.
+ */
+ static inline void inject(char * const gcode) {
+ strncpy(injected_commands, gcode, sizeof(injected_commands) - 1);
+ }
/**
* Enqueue and return only when commands are actually enqueued
@@ -134,18 +158,21 @@ private:
#endif
static void _commit_command(bool say_ok
- #if NUM_SERIAL > 1
+ #if HAS_MULTI_SERIAL
, int16_t p=-1
#endif
);
static bool _enqueue(const char* cmd, bool say_ok=false
- #if NUM_SERIAL > 1
+ #if HAS_MULTI_SERIAL
, int16_t p=-1
#endif
);
- // Process the next "immediate" command
+ // Process the next "immediate" command (PROGMEM)
+ static bool process_injected_command_P();
+
+ // Process the next "immediate" command (SRAM)
static bool process_injected_command();
/**
diff --git a/Marlin/src/gcode/scara/M360-M364.cpp b/Marlin/src/gcode/scara/M360-M364.cpp
index cd901d5dd..562beee4f 100644
--- a/Marlin/src/gcode/scara/M360-M364.cpp
+++ b/Marlin/src/gcode/scara/M360-M364.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp
index 4261b57f9..54bc452f9 100644
--- a/Marlin/src/gcode/sd/M1001.cpp
+++ b/Marlin/src/gcode/sd/M1001.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -27,6 +27,10 @@
#include "../gcode.h"
#include "../../module/printcounter.h"
+#ifdef SD_FINISHED_RELEASECOMMAND
+ #include "../queue.h"
+#endif
+
#if EITHER(LCD_SET_PROGRESS_MANUALLY, SD_REPRINT_LAST_SELECTED_FILE)
#include "../../lcd/ultralcd.h"
#endif
@@ -36,6 +40,7 @@
#endif
#if HAS_LEDS_OFF_FLAG
+ #include "../../MarlinCore.h" // for wait_for_user_response
#include "../../feature/leds/printer_event_leds.h"
#endif
@@ -47,10 +52,6 @@
#include "../../feature/host_actions.h"
#endif
-#if ENABLED(SD_FINISHED_STEPPERRELEASE) && defined(SD_FINISHED_RELEASECOMMAND)
- #include "../../module/planner.h"
-#endif
-
#ifndef PE_LEDS_COMPLETED_TIME
#define PE_LEDS_COMPLETED_TIME (30*60)
#endif
@@ -68,14 +69,10 @@ void GcodeSuite::M1001() {
gcode.process_subcommands_now_P(PSTR("M77"));
// Set the progress bar "done" state
- #if ENABLED(LCD_SET_PROGRESS_MANUALLY)
- ui.set_progress_done();
- #endif
+ TERN_(LCD_SET_PROGRESS_MANUALLY, ui.set_progress_done());
// Purge the recovery file
- #if ENABLED(POWER_LOSS_RECOVERY)
- recovery.purge();
- #endif
+ TERN_(POWER_LOSS_RECOVERY, recovery.purge());
// Announce SD file completion
SERIAL_ECHOLNPGM(STR_FILE_PRINTED);
@@ -84,26 +81,20 @@ void GcodeSuite::M1001() {
#if HAS_LEDS_OFF_FLAG
if (long_print) {
printerEventLEDs.onPrintCompleted();
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_PRINT_DONE));
- #endif
- #if ENABLED(HOST_PROMPT_SUPPORT)
- host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_PRINT_DONE), CONTINUE_STR);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_PRINT_DONE)));
+ TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_PRINT_DONE), CONTINUE_STR));
wait_for_user_response(1000UL * TERN(HAS_LCD_MENU, PE_LEDS_COMPLETED_TIME, 30));
printerEventLEDs.onResumeAfterWait();
}
#endif
- // Wait for the queue to empty (and "clean"), inject SD_FINISHED_RELEASECOMMAND
- #if ENABLED(SD_FINISHED_STEPPERRELEASE) && defined(SD_FINISHED_RELEASECOMMAND)
- planner.finish_and_disable();
+ // Inject SD_FINISHED_RELEASECOMMAND, if any
+ #ifdef SD_FINISHED_RELEASECOMMAND
+ queue.inject_P(PSTR(SD_FINISHED_RELEASECOMMAND));
#endif
// Re-select the last printed file in the UI
- #if ENABLED(SD_REPRINT_LAST_SELECTED_FILE)
- ui.reselect_last_file();
- #endif
+ TERN_(SD_REPRINT_LAST_SELECTED_FILE, ui.reselect_last_file());
}
#endif // SDSUPPORT
diff --git a/Marlin/src/gcode/sd/M20.cpp b/Marlin/src/gcode/sd/M20.cpp
index c45fcb038..6d4c55752 100644
--- a/Marlin/src/gcode/sd/M20.cpp
+++ b/Marlin/src/gcode/sd/M20.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/sd/M21_M22.cpp b/Marlin/src/gcode/sd/M21_M22.cpp
index 2d5bccaf8..77df751fc 100644
--- a/Marlin/src/gcode/sd/M21_M22.cpp
+++ b/Marlin/src/gcode/sd/M21_M22.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/sd/M23.cpp b/Marlin/src/gcode/sd/M23.cpp
index 4bf8105f6..b88f66b59 100644
--- a/Marlin/src/gcode/sd/M23.cpp
+++ b/Marlin/src/gcode/sd/M23.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -38,9 +38,7 @@ void GcodeSuite::M23() {
for (char *fn = parser.string_arg; *fn; ++fn) if (*fn == ' ') *fn = '\0';
card.openFileRead(parser.string_arg);
- #if ENABLED(LCD_SET_PROGRESS_MANUALLY)
- ui.set_progress(0);
- #endif
+ TERN_(LCD_SET_PROGRESS_MANUALLY, ui.set_progress(0));
}
#endif // SDSUPPORT
diff --git a/Marlin/src/gcode/sd/M24_M25.cpp b/Marlin/src/gcode/sd/M24_M25.cpp
index c1e6dde8d..c27e03862 100644
--- a/Marlin/src/gcode/sd/M24_M25.cpp
+++ b/Marlin/src/gcode/sd/M24_M25.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -31,7 +31,6 @@
#if ENABLED(PARK_HEAD_ON_PAUSE)
#include "../../feature/pause.h"
- #include "../queue.h"
#endif
#if ENABLED(HOST_ACTION_COMMANDS)
@@ -64,18 +63,14 @@ void GcodeSuite::M24() {
if (card.isFileOpen()) {
card.startFileprint(); // SD card will now be read for commands
startOrResumeJob(); // Start (or resume) the print job timer
- #if ENABLED(POWER_LOSS_RECOVERY)
- recovery.prepare();
- #endif
+ TERN_(POWER_LOSS_RECOVERY, recovery.prepare());
}
#if ENABLED(HOST_ACTION_COMMANDS)
#ifdef ACTION_ON_RESUME
host_action_resume();
#endif
- #if ENABLED(HOST_PROMPT_SUPPORT)
- host_prompt_open(PROMPT_INFO, PSTR("Resuming SD"), DISMISS_STR);
- #endif
+ TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, PSTR("Resuming SD"), DISMISS_STR));
#endif
ui.reset_status();
@@ -86,28 +81,27 @@ void GcodeSuite::M24() {
*/
void GcodeSuite::M25() {
- // Set initial pause flag to prevent more commands from landing in the queue while we try to pause
- #if ENABLED(SDSUPPORT)
- if (IS_SD_PRINTING()) card.pauseSDPrint();
- #endif
-
#if ENABLED(PARK_HEAD_ON_PAUSE)
M125();
#else
+ // Set initial pause flag to prevent more commands from landing in the queue while we try to pause
+ #if ENABLED(SDSUPPORT)
+ if (IS_SD_PRINTING()) card.pauseSDPrint();
+ #endif
+
#if ENABLED(POWER_LOSS_RECOVERY)
if (recovery.enabled) recovery.save(true);
#endif
print_job_timer.pause();
- ui.reset_status();
+
+ TERN(DWIN_CREALITY_LCD,,ui.reset_status());
#if ENABLED(HOST_ACTION_COMMANDS)
- #if ENABLED(HOST_PROMPT_SUPPORT)
- host_prompt_open(PROMPT_PAUSE_RESUME, PSTR("Pause SD"), PSTR("Resume"));
- #endif
+ TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_PAUSE_RESUME, PSTR("Pause SD"), PSTR("Resume")));
#ifdef ACTION_ON_PAUSE
host_action_pause();
#endif
diff --git a/Marlin/src/gcode/sd/M26.cpp b/Marlin/src/gcode/sd/M26.cpp
index d2e9e8e72..e0557bfa1 100644
--- a/Marlin/src/gcode/sd/M26.cpp
+++ b/Marlin/src/gcode/sd/M26.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/sd/M27.cpp b/Marlin/src/gcode/sd/M27.cpp
index 9c71e510a..8592b8af2 100644
--- a/Marlin/src/gcode/sd/M27.cpp
+++ b/Marlin/src/gcode/sd/M27.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/sd/M28_M29.cpp b/Marlin/src/gcode/sd/M28_M29.cpp
index 9dc192c09..6f3f2450a 100644
--- a/Marlin/src/gcode/sd/M28_M29.cpp
+++ b/Marlin/src/gcode/sd/M28_M29.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -27,7 +27,7 @@
#include "../gcode.h"
#include "../../sd/cardreader.h"
-#if NUM_SERIAL > 1
+#if HAS_MULTI_SERIAL
#include "../queue.h"
#endif
@@ -49,9 +49,7 @@ void GcodeSuite::M28() {
// Binary transfer mode
if ((card.flag.binary_mode = binary_mode)) {
SERIAL_ECHO_MSG("Switching to Binary Protocol");
- #if NUM_SERIAL > 1
- card.transfer_port_index = queue.port[queue.index_r];
- #endif
+ TERN_(HAS_MULTI_SERIAL, card.transfer_port_index = queue.port[queue.index_r]);
}
else
card.openFileWrite(p);
diff --git a/Marlin/src/gcode/sd/M30.cpp b/Marlin/src/gcode/sd/M30.cpp
index 2fd407341..b95a895f1 100644
--- a/Marlin/src/gcode/sd/M30.cpp
+++ b/Marlin/src/gcode/sd/M30.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/sd/M32.cpp b/Marlin/src/gcode/sd/M32.cpp
index 35a6fb1d6..a6f9fbcd8 100644
--- a/Marlin/src/gcode/sd/M32.cpp
+++ b/Marlin/src/gcode/sd/M32.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/sd/M33.cpp b/Marlin/src/gcode/sd/M33.cpp
index 7c6654a02..b611c8bc0 100644
--- a/Marlin/src/gcode/sd/M33.cpp
+++ b/Marlin/src/gcode/sd/M33.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/sd/M34.cpp b/Marlin/src/gcode/sd/M34.cpp
index ff1a8939a..2dd7dc580 100644
--- a/Marlin/src/gcode/sd/M34.cpp
+++ b/Marlin/src/gcode/sd/M34.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/sd/M524.cpp b/Marlin/src/gcode/sd/M524.cpp
index 401330361..b27814cc3 100644
--- a/Marlin/src/gcode/sd/M524.cpp
+++ b/Marlin/src/gcode/sd/M524.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/sd/M928.cpp b/Marlin/src/gcode/sd/M928.cpp
index b8b9175f0..03a7877a9 100644
--- a/Marlin/src/gcode/sd/M928.cpp
+++ b/Marlin/src/gcode/sd/M928.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/stats/M31.cpp b/Marlin/src/gcode/stats/M31.cpp
index 019598cb8..b39108bb9 100644
--- a/Marlin/src/gcode/stats/M31.cpp
+++ b/Marlin/src/gcode/stats/M31.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/stats/M75-M78.cpp b/Marlin/src/gcode/stats/M75-M78.cpp
index 41d550cb5..908e6e5a3 100644
--- a/Marlin/src/gcode/stats/M75-M78.cpp
+++ b/Marlin/src/gcode/stats/M75-M78.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/temp/M104_M109.cpp b/Marlin/src/gcode/temp/M104_M109.cpp
index 434c6c966..a289983b9 100644
--- a/Marlin/src/gcode/temp/M104_M109.cpp
+++ b/Marlin/src/gcode/temp/M104_M109.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -50,7 +50,12 @@
#endif
/**
- * M104: Set hot end temperature
+ * M104: Set Hotend Temperature target and return immediately
+ *
+ * Parameters:
+ * I : Material Preset index (if material presets are defined)
+ * T : Tool index. If omitted, applies to the active tool
+ * S : The target temperature in current units
*/
void GcodeSuite::M104() {
@@ -63,9 +68,26 @@ void GcodeSuite::M104() {
if (target_extruder < 0) return;
#endif
- if (parser.seenval('S')) {
- const int16_t temp = parser.value_celsius();
- #if ENABLED(SINGLENOZZLE)
+ bool got_temp = false;
+ int16_t temp = 0;
+
+ // Accept 'I' if temperature presets are defined
+ #if PREHEAT_COUNT
+ got_temp = parser.seenval('I');
+ if (got_temp) {
+ const uint8_t index = parser.value_byte();
+ temp = ui.material_preset[_MIN(index, PREHEAT_COUNT - 1)].hotend_temp;
+ }
+ #endif
+
+ // If no 'I' get the temperature from 'S'
+ if (!got_temp) {
+ got_temp = parser.seenval('S');
+ if (got_temp) temp = parser.value_celsius();
+ }
+
+ if (got_temp) {
+ #if ENABLED(SINGLENOZZLE_STANDBY_TEMP)
singlenozzle_temp[target_extruder] = temp;
if (target_extruder != active_extruder) return;
#endif
@@ -87,16 +109,29 @@ void GcodeSuite::M104() {
#endif
}
- #if ENABLED(AUTOTEMP)
- planner.autotemp_M104_M109();
- #endif
+ TERN_(AUTOTEMP, planner.autotemp_M104_M109());
}
/**
- * M109: Sxxx Wait for hotend(s) to reach temperature. Waits only when heating.
- * Rxxx Wait for hotend(s) to reach temperature. Waits when heating and cooling.
+ * M109: Set Hotend Temperature target and wait
*
- * With PRINTJOB_TIMER_AUTOSTART also start the job timer on heating and stop it if turned off.
+ * Parameters
+ * I : Material Preset index (if material presets are defined)
+ * T : Tool index. If omitted, applies to the active tool
+ * S : The target temperature in current units. Wait for heating only.
+ * R : The target temperature in current units. Wait for heating and cooling.
+ *
+ * With AUTOTEMP...
+ * F : Autotemp Scaling Factor. Set non-zero to enable Auto-temp.
+ * S : Minimum temperature, in current units.
+ * B : Maximum temperature, in current units.
+ *
+ * Examples
+ * M109 S100 : Set target to 100°. Wait until the hotend is at or above 100°.
+ * M109 R150 : Set target to 150°. Wait until the hotend gets close to 150°.
+ *
+ * With PRINTJOB_TIMER_AUTOSTART turning on heaters will start the print job timer
+ * (used by printingIsActive, etc.) and turning off heaters will stop the timer.
*/
void GcodeSuite::M109() {
@@ -109,11 +144,28 @@ void GcodeSuite::M109() {
if (target_extruder < 0) return;
#endif
- const bool no_wait_for_cooling = parser.seenval('S'),
- set_temp = no_wait_for_cooling || parser.seenval('R');
- if (set_temp) {
- const int16_t temp = parser.value_celsius();
- #if ENABLED(SINGLENOZZLE)
+ bool got_temp = false;
+ int16_t temp = 0;
+
+ // Accept 'I' if temperature presets are defined
+ #if PREHEAT_COUNT
+ got_temp = parser.seenval('I');
+ if (got_temp) {
+ const uint8_t index = parser.value_byte();
+ temp = ui.material_preset[_MIN(index, PREHEAT_COUNT - 1)].hotend_temp;
+ }
+ #endif
+
+ // Get the temperature from 'S' or 'R'
+ bool no_wait_for_cooling = false;
+ if (!got_temp) {
+ no_wait_for_cooling = parser.seenval('S');
+ got_temp = no_wait_for_cooling || parser.seenval('R');
+ if (got_temp) temp = int16_t(parser.value_celsius());
+ }
+
+ if (got_temp) {
+ #if ENABLED(SINGLENOZZLE_STANDBY_TEMP)
singlenozzle_temp[target_extruder] = temp;
if (target_extruder != active_extruder) return;
#endif
@@ -139,11 +191,9 @@ void GcodeSuite::M109() {
#endif
}
- #if ENABLED(AUTOTEMP)
- planner.autotemp_M104_M109();
- #endif
+ TERN_(AUTOTEMP, planner.autotemp_M104_M109());
- if (set_temp)
+ if (got_temp)
(void)thermalManager.wait_for_hotend(target_extruder, no_wait_for_cooling);
}
diff --git a/Marlin/src/gcode/temp/M105.cpp b/Marlin/src/gcode/temp/M105.cpp
index 7d68ccadc..eefc3ae9f 100644
--- a/Marlin/src/gcode/temp/M105.cpp
+++ b/Marlin/src/gcode/temp/M105.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/temp/M106_M107.cpp b/Marlin/src/gcode/temp/M106_M107.cpp
index 2415484d5..17ff8c3c8 100644
--- a/Marlin/src/gcode/temp/M106_M107.cpp
+++ b/Marlin/src/gcode/temp/M106_M107.cpp
@@ -16,18 +16,22 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#include "../../inc/MarlinConfig.h"
-#if FAN_COUNT > 0
+#if HAS_FAN
#include "../gcode.h"
#include "../../module/motion.h"
#include "../../module/temperature.h"
+#if PREHEAT_COUNT
+ #include "../../lcd/ultralcd.h"
+#endif
+
#if ENABLED(SINGLENOZZLE)
#define _ALT_P active_extruder
#define _CNT_P EXTRUDERS
@@ -39,6 +43,7 @@
/**
* M106: Set Fan Speed
*
+ * I Material Preset index (if material presets are defined)
* S Speed between 0-255
* P Fan index, if more than one fan
*
@@ -50,19 +55,32 @@
* 3-255 = Set the speed for use with T2
*/
void GcodeSuite::M106() {
- const uint8_t p = parser.byteval('P', _ALT_P);
+ const uint8_t pfan = parser.byteval('P', _ALT_P);
- if (p < _CNT_P) {
+ if (pfan < _CNT_P) {
#if ENABLED(EXTRA_FAN_SPEED)
const uint16_t t = parser.intval('T');
- if (t > 0) return thermalManager.set_temp_fan_speed(p, t);
+ if (t > 0) return thermalManager.set_temp_fan_speed(pfan, t);
#endif
- uint16_t d = parser.seen('A') ? thermalManager.fan_speed[active_extruder] : 255;
- uint16_t s = parser.ushortval('S', d);
- NOMORE(s, 255U);
- thermalManager.set_fan_speed(p, s);
+ const uint16_t dspeed = parser.seen('A') ? thermalManager.fan_speed[active_extruder] : 255;
+
+ uint16_t speed = dspeed;
+
+ // Accept 'I' if temperature presets are defined
+ #if PREHEAT_COUNT
+ const bool got_preset = parser.seenval('I');
+ if (got_preset) speed = ui.material_preset[_MIN(parser.value_byte(), PREHEAT_COUNT - 1)].fan_speed;
+ #else
+ constexpr bool got_preset = false;
+ #endif
+
+ if (!got_preset && parser.seenval('S'))
+ speed = parser.value_ushort();
+
+ // Set speed, with constraint
+ thermalManager.set_fan_speed(pfan, speed);
}
}
@@ -74,4 +92,4 @@ void GcodeSuite::M107() {
thermalManager.set_fan_speed(p, 0);
}
-#endif // FAN_COUNT > 0
+#endif // HAS_FAN
diff --git a/Marlin/src/gcode/temp/M140_M190.cpp b/Marlin/src/gcode/temp/M140_M190.cpp
index 2da438707..9438b9e0c 100644
--- a/Marlin/src/gcode/temp/M140_M190.cpp
+++ b/Marlin/src/gcode/temp/M140_M190.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -47,38 +47,88 @@
/**
* M140: Set bed temperature
+ *
+ * I : Preset index (if material presets are defined)
+ * S : The target temperature in current units
*/
void GcodeSuite::M140() {
if (DEBUGGING(DRYRUN)) return;
- if (parser.seenval('S')) thermalManager.setTargetBed(parser.value_celsius());
- #if ENABLED(PRINTJOB_TIMER_AUTOSTART)
- /**
- * Stop the timer at the end of print. Both hotend and bed target
- * temperatures need to be set below mintemp. Order of M140 and M104
- * at the end of the print does not matter.
- */
- thermalManager.check_timer_autostart(false, true);
+ bool got_temp = false;
+ int16_t temp = 0;
+
+ // Accept 'I' if temperature presets are defined
+ #if PREHEAT_COUNT
+ got_temp = parser.seenval('I');
+ if (got_temp) {
+ const uint8_t index = parser.value_byte();
+ temp = ui.material_preset[_MIN(index, PREHEAT_COUNT - 1)].bed_temp;
+ }
#endif
+
+ // If no 'I' get the temperature from 'S'
+ if (!got_temp) {
+ got_temp = parser.seenval('S');
+ if (got_temp) temp = parser.value_celsius();
+ }
+
+ if (got_temp) {
+ thermalManager.setTargetBed(temp);
+
+ #if ENABLED(PRINTJOB_TIMER_AUTOSTART)
+ /**
+ * Stop the timer at the end of print. Hotend, bed target, and chamber
+ * temperatures need to be set below mintemp. Order of M140, M104, and M141
+ * at the end of the print does not matter.
+ */
+ thermalManager.check_timer_autostart(false, true);
+ #endif
+ }
}
/**
- * M190: Sxxx Wait for bed current temp to reach target temp. Waits only when heating
- * Rxxx Wait for bed current temp to reach target temp. Waits when heating and cooling
+ * M190 - Set Bed Temperature target and wait
*
- * With PRINTJOB_TIMER_AUTOSTART also start the job timer on heating.
+ * Parameters:
+ * I : Preset index (if material presets are defined)
+ * S : The target temperature in current units. Wait for heating only.
+ * R : The target temperature in current units. Wait for heating and cooling.
+ *
+ * Examples:
+ * M190 S60 : Set target to 60°. Wait until the bed is at or above 60°.
+ * M190 R40 : Set target to 40°. Wait until the bed gets close to 40°.
+ *
+ * With PRINTJOB_TIMER_AUTOSTART turning on heaters will start the print job timer
+ * (used by printingIsActive, etc.) and turning off heaters will stop the timer.
*/
void GcodeSuite::M190() {
if (DEBUGGING(DRYRUN)) return;
- const bool no_wait_for_cooling = parser.seenval('S');
- if (no_wait_for_cooling || parser.seenval('R')) {
- thermalManager.setTargetBed(parser.value_celsius());
- #if ENABLED(PRINTJOB_TIMER_AUTOSTART)
- thermalManager.check_timer_autostart(true, false);
- #endif
+ bool got_temp = false;
+ int16_t temp = 0;
+
+ // Accept 'I' if temperature presets are defined
+ #if PREHEAT_COUNT
+ got_temp = parser.seenval('I');
+ if (got_temp) {
+ const uint8_t index = parser.value_byte();
+ temp = ui.material_preset[_MIN(index, PREHEAT_COUNT - 1)].bed_temp;
+ }
+ #endif
+
+ // Get the temperature from 'S' or 'R'
+ bool no_wait_for_cooling = false;
+ if (!got_temp) {
+ no_wait_for_cooling = parser.seenval('S');
+ got_temp = no_wait_for_cooling || parser.seenval('R');
+ if (got_temp) temp = int16_t(parser.value_celsius());
}
- else return;
+
+ if (!got_temp) return;
+
+ thermalManager.setTargetBed(temp);
+
+ TERN_(PRINTJOB_TIMER_AUTOSTART, thermalManager.check_timer_autostart(true, false));
ui.set_status_P(thermalManager.isHeatingBed() ? GET_TEXT(MSG_BED_HEATING) : GET_TEXT(MSG_BED_COOLING));
diff --git a/Marlin/src/gcode/temp/M141_M191.cpp b/Marlin/src/gcode/temp/M141_M191.cpp
index 3f0283647..41a79825a 100644
--- a/Marlin/src/gcode/temp/M141_M191.cpp
+++ b/Marlin/src/gcode/temp/M141_M191.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -51,7 +51,18 @@
*/
void GcodeSuite::M141() {
if (DEBUGGING(DRYRUN)) return;
- if (parser.seenval('S')) thermalManager.setTargetChamber(parser.value_celsius());
+ if (parser.seenval('S')) {
+ thermalManager.setTargetChamber(parser.value_celsius());
+
+ #if ENABLED(PRINTJOB_TIMER_AUTOSTART)
+ /**
+ * Stop the timer at the end of print. Hotend, bed target, and chamber
+ * temperatures need to be set below mintemp. Order of M140, M104, and M141
+ * at the end of the print does not matter.
+ */
+ thermalManager.check_timer_autostart(false, true);
+ #endif
+ }
}
/**
@@ -64,9 +75,7 @@ void GcodeSuite::M191() {
const bool no_wait_for_cooling = parser.seenval('S');
if (no_wait_for_cooling || parser.seenval('R')) {
thermalManager.setTargetChamber(parser.value_celsius());
- #if ENABLED(PRINTJOB_TIMER_AUTOSTART)
- thermalManager.check_timer_autostart(true, false);
- #endif
+ TERN_(PRINTJOB_TIMER_AUTOSTART, thermalManager.check_timer_autostart(true, false));
}
else return;
diff --git a/Marlin/src/gcode/temp/M155.cpp b/Marlin/src/gcode/temp/M155.cpp
index 52f9ef2be..30129a0e6 100644
--- a/Marlin/src/gcode/temp/M155.cpp
+++ b/Marlin/src/gcode/temp/M155.cpp
@@ -16,13 +16,13 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#include "../../inc/MarlinConfig.h"
-#if ENABLED(AUTO_REPORT_TEMPERATURES) && HAS_TEMP_SENSOR
+#if BOTH(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR)
#include "../gcode.h"
#include "../../module/temperature.h"
diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp
index 358a1436b..3340e4fa4 100644
--- a/Marlin/src/gcode/temp/M303.cpp
+++ b/Marlin/src/gcode/temp/M303.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -25,6 +25,7 @@
#if HAS_PID_HEATING
#include "../gcode.h"
+#include "../../lcd/ultralcd.h"
#include "../../module/temperature.h"
#if ENABLED(EXTENSIBLE_UI)
@@ -59,34 +60,26 @@ void GcodeSuite::M303() {
}
#endif
- #if ENABLED(PIDTEMPBED)
- #define SI H_BED
- #else
- #define SI H_E0
- #endif
- #if ENABLED(PIDTEMP)
- #define EI HOTENDS - 1
- #else
- #define EI H_BED
- #endif
+ #define SI TERN(PIDTEMPBED, H_BED, H_E0)
+ #define EI TERN(PIDTEMP, HOTENDS - 1, H_BED)
const heater_ind_t e = (heater_ind_t)parser.intval('E');
if (!WITHIN(e, SI, EI)) {
SERIAL_ECHOLNPGM(STR_PID_BAD_EXTRUDER_NUM);
- #if ENABLED(EXTENSIBLE_UI)
- ExtUI::onPidTuning(ExtUI::result_t::PID_BAD_EXTRUDER_NUM);
- #endif
+ TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_BAD_EXTRUDER_NUM));
return;
}
const int c = parser.intval('C', 5);
const bool u = parser.boolval('U');
- const int16_t temp = parser.celsiusval('S', e < 0 ? 70 : 150);
+ const int16_t temp = parser.celsiusval('S', e < 0 ? PREHEAT_1_TEMP_BED : PREHEAT_1_TEMP_HOTEND);
#if DISABLED(BUSY_WHILE_HEATING)
KEEPALIVE_STATE(NOT_BUSY);
#endif
+ ui.set_status(GET_TEXT(MSG_PID_AUTOTUNE));
thermalManager.PID_autotune(temp, e, c, u);
+ ui.reset_status();
}
#endif // HAS_PID_HEATING
diff --git a/Marlin/src/gcode/units/G20_G21.cpp b/Marlin/src/gcode/units/G20_G21.cpp
index 4961ae160..6f1d5adbc 100644
--- a/Marlin/src/gcode/units/G20_G21.cpp
+++ b/Marlin/src/gcode/units/G20_G21.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/units/M149.cpp b/Marlin/src/gcode/units/M149.cpp
index d8d962c5b..5d9f83206 100644
--- a/Marlin/src/gcode/units/M149.cpp
+++ b/Marlin/src/gcode/units/M149.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/gcode/units/M82_M83.cpp b/Marlin/src/gcode/units/M82_M83.cpp
index bf5aff0b8..d93f0ea5a 100644
--- a/Marlin/src/gcode/units/M82_M83.cpp
+++ b/Marlin/src/gcode/units/M82_M83.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h
index dd1f13fae..66e83c529 100644
--- a/Marlin/src/inc/Conditionals_LCD.h
+++ b/Marlin/src/inc/Conditionals_LCD.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -35,7 +35,15 @@
#define IS_CARTESIAN 1
#endif
-#if ENABLED(CARTESIO_UI)
+#if ENABLED(MKS_LCD12864)
+ #define MKS_MINI_12864
+#endif
+
+#if EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY)
+
+ #define MINIPANEL
+
+#elif ENABLED(CARTESIO_UI)
#define DOGLCD
#define IS_ULTIPANEL
@@ -98,15 +106,9 @@
#elif ENABLED(CR10_STOCKDISPLAY)
#define IS_RRD_FG_SC
- #ifndef ST7920_DELAY_1
- #define ST7920_DELAY_1 DELAY_NS(125)
- #endif
- #ifndef ST7920_DELAY_2
- #define ST7920_DELAY_2 DELAY_NS(125)
- #endif
- #ifndef ST7920_DELAY_3
- #define ST7920_DELAY_3 DELAY_NS(125)
- #endif
+ #define BOARD_ST7920_DELAY_1 DELAY_NS(125)
+ #define BOARD_ST7920_DELAY_2 DELAY_NS(125)
+ #define BOARD_ST7920_DELAY_3 DELAY_NS(125)
#elif ENABLED(MKS_12864OLED)
@@ -118,9 +120,26 @@
#define IS_RRD_SC
#define IS_U8GLIB_SSD1306
-#elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY)
+#elif ENABLED(FYSETC_242_OLED_12864)
- #define MINIPANEL
+ #define IS_RRD_SC
+ #define U8GLIB_SH1106
+
+ #define LED_CONTROL_MENU
+ #define NEOPIXEL_LED
+ #undef NEOPIXEL_TYPE
+ #define NEOPIXEL_TYPE NEO_RGB
+ #if NEOPIXEL_PIXELS < 3
+ #undef NEOPIXELS_PIXELS
+ #define NEOPIXEL_PIXELS 3
+ #endif
+ #ifndef NEOPIXEL_BRIGHTNESS
+ #define NEOPIXEL_BRIGHTNESS 127
+ #endif
+
+ #if ENABLED(PSU_CONTROL)
+ #define LED_BACKLIGHT_TIMEOUT 10000
+ #endif
#elif ANY(FYSETC_MINI_12864_X_X, FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0, FYSETC_MINI_12864_2_1, FYSETC_GENERIC_12864_1_1)
@@ -236,11 +255,18 @@
#define IS_ULTIPANEL
#endif
+// LVGL UI, SPI or FSMC
+#if EITHER(TFT_LVGL_UI_SPI, TFT_LVGL_UI_FSMC)
+ #define HAS_TFT_LVGL_UI 1
+#endif
+
// FSMC/SPI TFT Panels
#if ENABLED(FSMC_GRAPHICAL_TFT)
#define DOGLCD
#define IS_ULTIPANEL
#define DELAYED_BACKLIGHT_INIT
+#elif ENABLED(TFT_LVGL_UI_SPI)
+ #define DELAYED_BACKLIGHT_INIT
#endif
/**
@@ -335,9 +361,7 @@
#endif
#if ENABLED(ULTIPANEL)
#define IS_ULTRA_LCD
- #ifndef NEWPANEL
- #define NEWPANEL
- #endif
+ #define NEWPANEL
#endif
#if ENABLED(IS_ULTRA_LCD)
@@ -361,7 +385,7 @@
#define HAS_DGUS_LCD 1
#endif
-// Extensible UI serial touch screens. (See src/lcd/extensible_ui)
+// Extensible UI serial touch screens. (See src/lcd/extui)
#if ANY(HAS_DGUS_LCD, MALYAN_LCD, TOUCH_UI_FTDI_EVE)
#define IS_EXTUI
#define EXTENSIBLE_UI
@@ -380,6 +404,14 @@
#endif
#endif
+#if ENABLED(SR_LCD_3W_NL)
+ // Feature checks for SR_LCD_3W_NL
+#elif EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008)
+ #define USES_LIQUIDTWI2
+#elif ANY(HAS_CHARACTER_LCD, LCD_I2C_TYPE_PCF8575, LCD_I2C_TYPE_PCA8574, SR_LCD_2W_NL, LCM1602)
+ #define USES_LIQUIDCRYSTAL
+#endif
+
#if ENABLED(ULTIPANEL) && DISABLED(NO_LCD_MENUS)
#define HAS_LCD_MENU 1
#endif
@@ -408,13 +440,15 @@
*/
#if EXTRUDERS == 0
- #undef DISTINCT_E_FACTORS
+ #undef EXTRUDERS
+ #define EXTRUDERS 0
#undef SINGLENOZZLE
#undef SWITCHING_EXTRUDER
#undef SWITCHING_NOZZLE
#undef MIXING_EXTRUDER
#undef MK2_MULTIPLEXER
#undef PRUSA_MMU2
+ #undef HOTEND_IDLE_TIMEOUT
#endif
#if ENABLED(SWITCHING_EXTRUDER) // One stepper for every two EXTRUDERS
@@ -431,7 +465,9 @@
#elif ENABLED(MIXING_EXTRUDER)
#define E_STEPPERS MIXING_STEPPERS
#define E_MANUAL 1
- #define DUAL_MIXING_EXTRUDER (MIXING_STEPPERS == 2)
+ #if MIXING_STEPPERS == 2
+ #define HAS_DUAL_MIXING 1
+ #endif
#elif ENABLED(SWITCHING_TOOLHEAD)
#define E_STEPPERS EXTRUDERS
#define E_MANUAL EXTRUDERS
@@ -466,6 +502,19 @@
#define E_MANUAL EXTRUDERS
#endif
+#if HOTENDS
+ #define HAS_HOTEND 1
+ #ifndef HOTEND_OVERSHOOT
+ #define HOTEND_OVERSHOOT 15
+ #endif
+ #if HOTENDS > 1
+ #define HAS_MULTI_HOTEND 1
+ #define HAS_HOTEND_OFFSET 1
+ #endif
+#else
+ #undef PID_PARAMS_PER_HOTEND
+#endif
+
// Helper macros for extruder and hotend arrays
#define HOTEND_LOOP() for (int8_t e = 0; e < HOTENDS; e++)
#define ARRAY_BY_EXTRUDERS(V...) ARRAY_N(EXTRUDERS, V)
@@ -481,10 +530,6 @@
#define SWITCHING_NOZZLE_TWO_SERVOS 1
#endif
-#if HOTENDS > 1
- #define HAS_HOTEND_OFFSET 1
-#endif
-
/**
* Default hotend offsets, if not defined
*/
@@ -504,16 +549,29 @@
* DISTINCT_E_FACTORS affects how some E factors are accessed
*/
#if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1
+ #define DISTINCT_E E_STEPPERS
#define XYZE_N (XYZ + E_STEPPERS)
+ #define E_INDEX_N(E) (E)
#define E_AXIS_N(E) AxisEnum(E_AXIS + E)
#define UNUSED_E(E) NOOP
#else
#undef DISTINCT_E_FACTORS
+ #define DISTINCT_E 1
#define XYZE_N XYZE
+ #define E_INDEX_N(E) 0
#define E_AXIS_N(E) E_AXIS
#define UNUSED_E(E) UNUSED(E)
#endif
+#if ENABLED(DWIN_CREALITY_LCD)
+ #define SERIAL_CATCHALL 0
+#endif
+
+// Pressure sensor with a BLTouch-like interface
+#if ENABLED(CREALITY_TOUCH)
+ #define BLTOUCH
+#endif
+
/**
* The BLTouch Probe emulates a servo probe
* and uses "special" angles for its state.
@@ -544,21 +602,13 @@
#define NUM_SERVOS 0
#endif
-#ifndef PREHEAT_1_LABEL
- #define PREHEAT_1_LABEL "PLA"
-#endif
-
-#ifndef PREHEAT_2_LABEL
- #define PREHEAT_2_LABEL "ABS"
-#endif
-
/**
* Set a flag for a servo probe (or BLTouch)
*/
#if defined(Z_PROBE_SERVO_NR) && Z_PROBE_SERVO_NR >= 0
#define HAS_Z_SERVO_PROBE 1
#endif
-#if HAS_Z_SERVO_PROBE || EITHER(SWITCHING_EXTRUDER, SWITCHING_NOZZLE)
+#if ANY(HAS_Z_SERVO_PROBE, SWITCHING_EXTRUDER, SWITCHING_NOZZLE)
#define HAS_SERVO_ANGLES 1
#endif
#if !HAS_SERVO_ANGLES
@@ -572,7 +622,7 @@
#define HAS_BED_PROBE 1
#endif
-#if HAS_BED_PROBE || EITHER(PROBE_MANUALLY, MESH_BED_LEVELING)
+#if ANY(HAS_BED_PROBE, PROBE_MANUALLY, MESH_BED_LEVELING)
#define PROBE_SELECTED 1
#endif
@@ -583,7 +633,7 @@
#if DISABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
#define HAS_CUSTOM_PROBE_PIN 1
#endif
- #if Z_HOME_DIR < 0 && !HAS_CUSTOM_PROBE_PIN
+ #if Z_HOME_DIR < 0 && (!HAS_CUSTOM_PROBE_PIN || ENABLED(USE_PROBE_FOR_Z_HOMING))
#define HOMING_Z_WITH_PROBE 1
#endif
#ifndef Z_PROBE_LOW_POINT
@@ -593,7 +643,7 @@
#define PROBE_TRIGGERED_WHEN_STOWED_TEST 1 // Extra test for Allen Key Probe
#endif
#if MULTIPLE_PROBING > 1
- #if EXTRA_PROBING
+ #if EXTRA_PROBING > 0
#define TOTAL_PROBING (MULTIPLE_PROBING + EXTRA_PROBING)
#else
#define TOTAL_PROBING MULTIPLE_PROBING
@@ -670,10 +720,14 @@
#endif
// This flag indicates some kind of jerk storage is needed
-#if ENABLED(CLASSIC_JERK) || IS_KINEMATIC
+#if EITHER(CLASSIC_JERK, IS_KINEMATIC)
#define HAS_CLASSIC_JERK 1
#endif
+#if DISABLED(CLASSIC_JERK)
+ #define HAS_JUNCTION_DEVIATION 1
+#endif
+
// E jerk exists with JD disabled (of course) but also when Linear Advance is disabled on Delta/SCARA
#if ENABLED(CLASSIC_JERK) || (IS_KINEMATIC && DISABLED(LIN_ADVANCE))
#define HAS_CLASSIC_E_JERK 1
@@ -694,3 +748,10 @@
#ifndef EXTRUDE_MINTEMP
#define EXTRUDE_MINTEMP 170
#endif
+
+/**
+ * To check if we need the folder src/features/leds
+ */
+#if ANY(TEMP_STAT_LEDS, HAS_COLOR_LEDS, HAS_CASE_LIGHT, PRINTER_EVENT_LEDS, LED_BACKLIGHT_TIMEOUT, PCA9632_BUZZER, LED_CONTROL_MENU)
+ #define HAS_LED_FEATURE 1
+#endif
diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h
index a52ae1af2..85cb26dad 100644
--- a/Marlin/src/inc/Conditionals_adv.h
+++ b/Marlin/src/inc/Conditionals_adv.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -56,6 +56,10 @@
#undef SHOW_TEMP_ADC_VALUES
#endif
+#if ENABLED(MIXING_EXTRUDER) && (ENABLED(RETRACT_SYNC_MIXING) || BOTH(FILAMENT_LOAD_UNLOAD_GCODES, FILAMENT_UNLOAD_ALL_EXTRUDERS))
+ #define HAS_MIXER_SYNC_CHANNEL 1
+#endif
+
#if EITHER(DUAL_X_CARRIAGE, MULTI_NOZZLE_DUPLICATION)
#define HAS_DUPLICATION_MODE 1
#endif
@@ -66,6 +70,18 @@
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define HAS_FILAMENT_SENSOR 1
+ #ifdef FILAMENT_RUNOUT_DISTANCE_MM
+ #define HAS_FILAMENT_RUNOUT_DISTANCE 1
+ #endif
+#endif
+
+// Let SD_FINISHED_RELEASECOMMAND stand in for SD_FINISHED_STEPPERRELEASE
+#if ENABLED(SD_FINISHED_STEPPERRELEASE)
+ #ifndef SD_FINISHED_RELEASECOMMAND
+ #define SD_FINISHED_RELEASECOMMAND "M84" // planner.finish_and_disable()
+ #endif
+#else
+ #undef SD_FINISHED_RELEASECOMMAND
#endif
#if EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY)
@@ -93,7 +109,7 @@
#if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS)
#define HAS_SOFTWARE_ENDSTOPS 1
#endif
-#if ANY(EXTENSIBLE_UI, NEWPANEL, EMERGENCY_PARSER, HAS_ADC_BUTTONS)
+#if ANY(EXTENSIBLE_UI, NEWPANEL, EMERGENCY_PARSER, HAS_ADC_BUTTONS, DWIN_CREALITY_LCD)
#define HAS_RESUME_CONTINUE 1
#endif
@@ -104,6 +120,10 @@
#define HAS_LEDS_OFF_FLAG 1
#endif
+#if EITHER(DIGIPOT_MCP4018, DIGIPOT_MCP4451)
+ #define HAS_I2C_DIGIPOT 1
+#endif
+
// Multiple Z steppers
#ifndef NUM_Z_STEPPER_DRIVERS
#define NUM_Z_STEPPER_DRIVERS 1
@@ -116,7 +136,23 @@
#define Z_STEPPER_ALIGN_AMP 1.0
#endif
-#define HAS_CUTTER EITHER(SPINDLE_FEATURE, LASER_FEATURE)
+//
+// Spindle/Laser power display types
+// Defined here so sanity checks can use them
+//
+#if EITHER(SPINDLE_FEATURE, LASER_FEATURE)
+ #define HAS_CUTTER 1
+ #define _CUTTER_POWER_PWM255 1
+ #define _CUTTER_POWER_PERCENT 2
+ #define _CUTTER_POWER_RPM 3
+ #define _CUTTER_POWER(V) _CAT(_CUTTER_POWER_, V)
+ #define CUTTER_UNIT_IS(V) (_CUTTER_POWER(CUTTER_POWER_UNIT) == _CUTTER_POWER(V))
+#endif
+
+// Add features that need hardware PWM here
+#if ANY(FAST_PWM_FAN, SPINDLE_LASER_PWM)
+ #define NEEDS_HARDWARE_PWM 1
+#endif
#if !defined(__AVR__) || !defined(USBCON)
// Define constants and variables for buffering serial data.
@@ -172,7 +208,7 @@
#endif
#endif
-#if ENABLED(FYSETC_MINI_12864_2_1)
+#if EITHER(FYSETC_MINI_12864_2_1, FYSETC_242_OLED_12864)
#define LED_CONTROL_MENU
#define LED_USER_PRESET_STARTUP
#define LED_COLOR_PRESETS
@@ -226,11 +262,10 @@
#endif
/**
- * Driver Timings
+ * Driver Timings (in nanoseconds)
* NOTE: Driver timing order is longest-to-shortest duration.
* Preserve this ordering when adding new drivers.
*/
-
#ifndef MINIMUM_STEPPER_POST_DIR_DELAY
#if HAS_DRIVER(TB6560)
#define MINIMUM_STEPPER_POST_DIR_DELAY 15000
@@ -245,7 +280,7 @@
#elif HAS_DRIVER(A4988)
#define MINIMUM_STEPPER_POST_DIR_DELAY 200
#elif HAS_TRINAMIC_CONFIG || HAS_TRINAMIC_STANDALONE
- #define MINIMUM_STEPPER_POST_DIR_DELAY 20
+ #define MINIMUM_STEPPER_POST_DIR_DELAY 60
#else
#define MINIMUM_STEPPER_POST_DIR_DELAY 0 // Expect at least 10µS since one Stepper ISR must transpire
#endif
@@ -290,3 +325,45 @@
#define MAXIMUM_STEPPER_RATE 250000
#endif
#endif
+
+#if ENABLED(DIRECT_STEPPING)
+ #ifndef STEPPER_PAGES
+ #define STEPPER_PAGES 16
+ #endif
+ #ifndef STEPPER_PAGE_FORMAT
+ #define STEPPER_PAGE_FORMAT SP_4x2_256
+ #endif
+ #ifndef PAGE_MANAGER
+ #define PAGE_MANAGER SerialPageManager
+ #endif
+#endif
+
+//
+// SD Card connection methods
+// Defined here so pins and sanity checks can use them
+//
+#if ENABLED(SDSUPPORT)
+ #define _SDCARD_LCD 1
+ #define _SDCARD_ONBOARD 2
+ #define _SDCARD_CUSTOM_CABLE 3
+ #define _SDCARD_ID(V) _CAT(_SDCARD_, V)
+ #define SD_CONNECTION_IS(V) (_SDCARD_ID(SDCARD_CONNECTION) == _SDCARD_ID(V))
+#else
+ #define SD_CONNECTION_IS(...) 0
+#endif
+
+// Power Monitor sensors
+#if EITHER(POWER_MONITOR_CURRENT, POWER_MONITOR_VOLTAGE)
+ #define HAS_POWER_MONITOR 1
+#endif
+#if ENABLED(POWER_MONITOR_CURRENT) && defined(POWER_MONITOR_FIXED_VOLTAGE)
+ #define HAS_POWER_MONITOR_VREF 1
+#endif
+#if BOTH(HAS_POWER_MONITOR_VREF, POWER_MONITOR_CURRENT)
+ #define HAS_POWER_MONITOR_WATTS 1
+#endif
+
+// Flag if an EEPROM type is pre-selected
+#if ENABLED(EEPROM_SETTINGS) && NONE(I2C_EEPROM, SPI_EEPROM, QSPI_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION)
+ #define NO_EEPROM_SELECTED 1
+#endif
diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h
index 9ea298f02..e12310e07 100644
--- a/Marlin/src/inc/Conditionals_post.h
+++ b/Marlin/src/inc/Conditionals_post.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -30,8 +30,15 @@
// Extras for CI testing
#endif
+// ADC
+#ifdef BOARD_ADC_VREF
+ #define ADC_VREF BOARD_ADC_VREF
+#else
+ #define ADC_VREF HAL_ADC_VREF
+#endif
+
// Linear advance uses Jerk since E is an isolated axis
-#if DISABLED(CLASSIC_JERK) && ENABLED(LIN_ADVANCE)
+#if BOTH(HAS_JUNCTION_DEVIATION, LIN_ADVANCE)
#define HAS_LINEAR_E_JERK 1
#endif
@@ -39,8 +46,12 @@
#if ENABLED(EEPROM_SETTINGS)
// EEPROM type may be defined by compile flags, configs, HALs, or pins
// Set additional flags to let HALs choose in their Conditionals_post.h
- #if NONE(FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) && ANY(I2C_EEPROM, SPI_EEPROM, QSPI_EEPROM)
+ #if ANY(FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION, QSPI_EEPROM)
+ #define USE_EMULATED_EEPROM 1
+ #elif ANY(I2C_EEPROM, SPI_EEPROM)
#define USE_WIRED_EEPROM 1
+ #elif ENABLED(IIC_BL24CXX_EEPROM)
+ // nothing
#else
#define USE_FALLBACK_EEPROM 1
#endif
@@ -51,6 +62,7 @@
#undef SDCARD_EEPROM_EMULATION
#undef SRAM_EEPROM_EMULATION
#undef FLASH_EEPROM_EMULATION
+ #undef IIC_BL24CXX_EEPROM
#endif
#ifdef TEENSYDUINO
@@ -147,7 +159,7 @@
#define Z_AXIS_INDEX 2
#define CAN_CALIBRATE(A,B) (A##_AXIS_INDEX == B##_INDEX)
#else
- #define CAN_CALIBRATE(...) 1
+ #define CAN_CALIBRATE(A,B) 1
#endif
#endif
#define AXIS_CAN_CALIBRATE(A) CAN_CALIBRATE(A,NORMAL_AXIS)
@@ -258,6 +270,13 @@
#define MAX_AUTORETRACT 99
#endif
+/**
+ * Provide a DEFAULT_VOLUMETRIC_EXTRUDER_LIMIT in case NO_VOLUMETRICS is enabled
+ */
+#ifndef DEFAULT_VOLUMETRIC_EXTRUDER_LIMIT
+ #define DEFAULT_VOLUMETRIC_EXTRUDER_LIMIT 0.00
+#endif
+
/**
* LCD Contrast for Graphical Displays
*/
@@ -278,7 +297,7 @@
#elif ENABLED(AZSMZ_12864)
#define _LCD_CONTRAST_MIN 120
#define _LCD_CONTRAST_INIT 190
-#elif ENABLED(MKS_LCD12864B)
+#elif ENABLED(MKS_LCD12864)
#define _LCD_CONTRAST_MIN 120
#define _LCD_CONTRAST_INIT 205
#elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY)
@@ -289,8 +308,10 @@
#elif ENABLED(ULTI_CONTROLLER)
#define _LCD_CONTRAST_INIT 127
#define _LCD_CONTRAST_MAX 254
-#elif EITHER(MAKRPANEL, MINIPANEL)
+#elif ENABLED(MAKRPANEL)
#define _LCD_CONTRAST_INIT 17
+#elif ENABLED(MINIPANEL)
+ #define _LCD_CONTRAST_INIT 150
#endif
#ifdef _LCD_CONTRAST_INIT
@@ -324,17 +345,36 @@
/**
* Override the SD_DETECT_STATE set in Configuration_adv.h
+ * and enable sharing of onboard SD host drives (all platforms but AGCM4)
*/
#if ENABLED(SDSUPPORT)
- #if HAS_LCD_MENU && (SD_CONNECTION_IS(LCD) || !defined(SDCARD_CONNECTION))
- #undef SD_DETECT_STATE
- #if ENABLED(ELB_FULL_GRAPHIC_CONTROLLER)
- #define SD_DETECT_STATE HIGH
+
+ #if SD_CONNECTION_IS(ONBOARD) && DISABLED(NO_SD_HOST_DRIVE) && !defined(ARDUINO_GRAND_CENTRAL_M4)
+ //
+ // The external SD card is not used. Hardware SPI is used to access the card.
+ // When sharing the SD card with a PC we want the menu options to
+ // mount/unmount the card and refresh it. So we disable card detect.
+ //
+ #undef SD_DETECT_PIN
+ #define HAS_SHARED_MEDIA 1
+ #endif
+
+ #if PIN_EXISTS(SD_DETECT)
+ #if HAS_LCD_MENU && (SD_CONNECTION_IS(LCD) || !defined(SDCARD_CONNECTION))
+ #undef SD_DETECT_STATE
+ #if ENABLED(ELB_FULL_GRAPHIC_CONTROLLER)
+ #define SD_DETECT_STATE HIGH
+ #endif
+ #endif
+ #ifndef SD_DETECT_STATE
+ #define SD_DETECT_STATE LOW
#endif
#endif
- #ifndef SD_DETECT_STATE
- #define SD_DETECT_STATE LOW
- #endif
+
+#endif
+
+#if EITHER(LCD_USE_DMA_FSMC, FSMC_GRAPHICAL_TFT) || !PIN_EXISTS(SD_DETECT)
+ #define NO_LCD_REINIT 1 // Suppress LCD re-initialization
#endif
/**
@@ -367,7 +407,7 @@
#endif
#if !defined(PSU_POWERUP_DELAY) && ENABLED(PSU_CONTROL)
- #define PSU_POWERUP_DELAY 100
+ #define PSU_POWERUP_DELAY 250
#endif
/**
@@ -376,7 +416,9 @@
#define ANY_TEMP_SENSOR_IS(n) (TEMP_SENSOR_0 == (n) || TEMP_SENSOR_1 == (n) || TEMP_SENSOR_2 == (n) || TEMP_SENSOR_3 == (n) || TEMP_SENSOR_4 == (n) || TEMP_SENSOR_5 == (n) || TEMP_SENSOR_6 == (n) || TEMP_SENSOR_7 == (n) || TEMP_SENSOR_BED == (n) || TEMP_SENSOR_PROBE == (n) || TEMP_SENSOR_CHAMBER == (n))
-#define HAS_USER_THERMISTORS ANY_TEMP_SENSOR_IS(1000)
+#if ANY_TEMP_SENSOR_IS(1000)
+ #define HAS_USER_THERMISTORS 1
+#endif
#if TEMP_SENSOR_0 == -5 || TEMP_SENSOR_0 == -3 || TEMP_SENSOR_0 == -2
#define HEATER_0_USES_MAX6675
@@ -617,20 +659,22 @@
*/
#if ENABLED(X_DUAL_ENDSTOPS)
#if X_HOME_DIR > 0
- #if X2_USE_ENDSTOP == _XMIN_
- #define X2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
- #elif X2_USE_ENDSTOP == _XMAX_
- #define X2_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
- #elif X2_USE_ENDSTOP == _YMIN_
- #define X2_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
- #elif X2_USE_ENDSTOP == _YMAX_
- #define X2_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
- #elif X2_USE_ENDSTOP == _ZMIN_
- #define X2_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
- #elif X2_USE_ENDSTOP == _ZMAX_
- #define X2_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
- #else
- #define X2_MAX_ENDSTOP_INVERTING false
+ #ifndef X2_MAX_ENDSTOP_INVERTING
+ #if X2_USE_ENDSTOP == _XMIN_
+ #define X2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
+ #elif X2_USE_ENDSTOP == _XMAX_
+ #define X2_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
+ #elif X2_USE_ENDSTOP == _YMIN_
+ #define X2_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
+ #elif X2_USE_ENDSTOP == _YMAX_
+ #define X2_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
+ #elif X2_USE_ENDSTOP == _ZMIN_
+ #define X2_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
+ #elif X2_USE_ENDSTOP == _ZMAX_
+ #define X2_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
+ #else
+ #define X2_MAX_ENDSTOP_INVERTING false
+ #endif
#endif
#ifndef X2_MAX_PIN
#if X2_USE_ENDSTOP == _XMIN_
@@ -669,23 +713,27 @@
#define X2_MAX_PIN E7_DIAG_PIN
#endif
#endif
- #define X2_MIN_ENDSTOP_INVERTING false
- #else
- #if X2_USE_ENDSTOP == _XMIN_
- #define X2_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
- #elif X2_USE_ENDSTOP == _XMAX_
- #define X2_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
- #elif X2_USE_ENDSTOP == _YMIN_
- #define X2_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
- #elif X2_USE_ENDSTOP == _YMAX_
- #define X2_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
- #elif X2_USE_ENDSTOP == _ZMIN_
- #define X2_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
- #elif X2_USE_ENDSTOP == _ZMAX_
- #define X2_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
- #else
+ #ifndef X2_MIN_ENDSTOP_INVERTING
#define X2_MIN_ENDSTOP_INVERTING false
#endif
+ #else
+ #ifndef X2_MIN_ENDSTOP_INVERTING
+ #if X2_USE_ENDSTOP == _XMIN_
+ #define X2_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
+ #elif X2_USE_ENDSTOP == _XMAX_
+ #define X2_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
+ #elif X2_USE_ENDSTOP == _YMIN_
+ #define X2_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
+ #elif X2_USE_ENDSTOP == _YMAX_
+ #define X2_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
+ #elif X2_USE_ENDSTOP == _ZMIN_
+ #define X2_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
+ #elif X2_USE_ENDSTOP == _ZMAX_
+ #define X2_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
+ #else
+ #define X2_MIN_ENDSTOP_INVERTING false
+ #endif
+ #endif
#ifndef X2_MIN_PIN
#if X2_USE_ENDSTOP == _XMIN_
#define X2_MIN_PIN X_MIN_PIN
@@ -723,7 +771,9 @@
#define X2_MIN_PIN E7_DIAG_PIN
#endif
#endif
- #define X2_MAX_ENDSTOP_INVERTING false
+ #ifndef X2_MAX_ENDSTOP_INVERTING
+ #define X2_MAX_ENDSTOP_INVERTING false
+ #endif
#endif
#endif
@@ -732,20 +782,22 @@
*/
#if ENABLED(Y_DUAL_ENDSTOPS)
#if Y_HOME_DIR > 0
- #if Y2_USE_ENDSTOP == _XMIN_
- #define Y2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
- #elif Y2_USE_ENDSTOP == _XMAX_
- #define Y2_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
- #elif Y2_USE_ENDSTOP == _YMIN_
- #define Y2_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
- #elif Y2_USE_ENDSTOP == _YMAX_
- #define Y2_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
- #elif Y2_USE_ENDSTOP == _ZMIN_
- #define Y2_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
- #elif Y2_USE_ENDSTOP == _ZMAX_
- #define Y2_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
- #else
- #define Y2_MAX_ENDSTOP_INVERTING false
+ #ifndef Y2_MAX_ENDSTOP_INVERTING
+ #if Y2_USE_ENDSTOP == _XMIN_
+ #define Y2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
+ #elif Y2_USE_ENDSTOP == _XMAX_
+ #define Y2_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
+ #elif Y2_USE_ENDSTOP == _YMIN_
+ #define Y2_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
+ #elif Y2_USE_ENDSTOP == _YMAX_
+ #define Y2_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
+ #elif Y2_USE_ENDSTOP == _ZMIN_
+ #define Y2_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
+ #elif Y2_USE_ENDSTOP == _ZMAX_
+ #define Y2_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
+ #else
+ #define Y2_MAX_ENDSTOP_INVERTING false
+ #endif
#endif
#ifndef Y2_MAX_PIN
#if Y2_USE_ENDSTOP == _XMIN_
@@ -784,23 +836,27 @@
#define Y2_MAX_PIN E7_DIAG_PIN
#endif
#endif
- #define Y2_MIN_ENDSTOP_INVERTING false
- #else
- #if Y2_USE_ENDSTOP == _XMIN_
- #define Y2_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
- #elif Y2_USE_ENDSTOP == _XMAX_
- #define Y2_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
- #elif Y2_USE_ENDSTOP == _YMIN_
- #define Y2_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
- #elif Y2_USE_ENDSTOP == _YMAX_
- #define Y2_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
- #elif Y2_USE_ENDSTOP == _ZMIN_
- #define Y2_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
- #elif Y2_USE_ENDSTOP == _ZMAX_
- #define Y2_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
- #else
+ #ifndef Y2_MIN_ENDSTOP_INVERTING
#define Y2_MIN_ENDSTOP_INVERTING false
#endif
+ #else
+ #ifndef Y2_MIN_ENDSTOP_INVERTING
+ #if Y2_USE_ENDSTOP == _XMIN_
+ #define Y2_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
+ #elif Y2_USE_ENDSTOP == _XMAX_
+ #define Y2_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
+ #elif Y2_USE_ENDSTOP == _YMIN_
+ #define Y2_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
+ #elif Y2_USE_ENDSTOP == _YMAX_
+ #define Y2_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
+ #elif Y2_USE_ENDSTOP == _ZMIN_
+ #define Y2_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
+ #elif Y2_USE_ENDSTOP == _ZMAX_
+ #define Y2_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
+ #else
+ #define Y2_MIN_ENDSTOP_INVERTING false
+ #endif
+ #endif
#ifndef Y2_MIN_PIN
#if Y2_USE_ENDSTOP == _XMIN_
#define Y2_MIN_PIN X_MIN_PIN
@@ -838,7 +894,9 @@
#define Y2_MIN_PIN E7_DIAG_PIN
#endif
#endif
- #define Y2_MAX_ENDSTOP_INVERTING false
+ #ifndef Y2_MAX_ENDSTOP_INVERTING
+ #define Y2_MAX_ENDSTOP_INVERTING false
+ #endif
#endif
#endif
@@ -848,20 +906,22 @@
#if ENABLED(Z_MULTI_ENDSTOPS)
#if Z_HOME_DIR > 0
- #if Z2_USE_ENDSTOP == _XMIN_
- #define Z2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
- #elif Z2_USE_ENDSTOP == _XMAX_
- #define Z2_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
- #elif Z2_USE_ENDSTOP == _YMIN_
- #define Z2_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
- #elif Z2_USE_ENDSTOP == _YMAX_
- #define Z2_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
- #elif Z2_USE_ENDSTOP == _ZMIN_
- #define Z2_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
- #elif Z2_USE_ENDSTOP == _ZMAX_
- #define Z2_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
- #else
- #define Z2_MAX_ENDSTOP_INVERTING false
+ #ifndef Z2_MAX_ENDSTOP_INVERTING
+ #if Z2_USE_ENDSTOP == _XMIN_
+ #define Z2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
+ #elif Z2_USE_ENDSTOP == _XMAX_
+ #define Z2_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
+ #elif Z2_USE_ENDSTOP == _YMIN_
+ #define Z2_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
+ #elif Z2_USE_ENDSTOP == _YMAX_
+ #define Z2_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
+ #elif Z2_USE_ENDSTOP == _ZMIN_
+ #define Z2_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
+ #elif Z2_USE_ENDSTOP == _ZMAX_
+ #define Z2_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
+ #else
+ #define Z2_MAX_ENDSTOP_INVERTING false
+ #endif
#endif
#ifndef Z2_MAX_PIN
#if Z2_USE_ENDSTOP == _XMIN_
@@ -900,23 +960,27 @@
#define Z2_MAX_PIN E7_DIAG_PIN
#endif
#endif
- #define Z2_MIN_ENDSTOP_INVERTING false
- #else
- #if Z2_USE_ENDSTOP == _XMIN_
- #define Z2_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
- #elif Z2_USE_ENDSTOP == _XMAX_
- #define Z2_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
- #elif Z2_USE_ENDSTOP == _YMIN_
- #define Z2_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
- #elif Z2_USE_ENDSTOP == _YMAX_
- #define Z2_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
- #elif Z2_USE_ENDSTOP == _ZMIN_
- #define Z2_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
- #elif Z2_USE_ENDSTOP == _ZMAX_
- #define Z2_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
- #else
+ #ifndef Z2_MIN_ENDSTOP_INVERTING
#define Z2_MIN_ENDSTOP_INVERTING false
#endif
+ #else
+ #ifndef Z2_MIN_ENDSTOP_INVERTING
+ #if Z2_USE_ENDSTOP == _XMIN_
+ #define Z2_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
+ #elif Z2_USE_ENDSTOP == _XMAX_
+ #define Z2_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
+ #elif Z2_USE_ENDSTOP == _YMIN_
+ #define Z2_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
+ #elif Z2_USE_ENDSTOP == _YMAX_
+ #define Z2_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
+ #elif Z2_USE_ENDSTOP == _ZMIN_
+ #define Z2_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
+ #elif Z2_USE_ENDSTOP == _ZMAX_
+ #define Z2_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
+ #else
+ #define Z2_MIN_ENDSTOP_INVERTING false
+ #endif
+ #endif
#ifndef Z2_MIN_PIN
#if Z2_USE_ENDSTOP == _XMIN_
#define Z2_MIN_PIN X_MIN_PIN
@@ -954,25 +1018,29 @@
#define Z2_MIN_PIN E7_DIAG_PIN
#endif
#endif
- #define Z2_MAX_ENDSTOP_INVERTING false
+ #ifndef Z2_MAX_ENDSTOP_INVERTING
+ #define Z2_MAX_ENDSTOP_INVERTING false
+ #endif
#endif
#if NUM_Z_STEPPER_DRIVERS >= 3
#if Z_HOME_DIR > 0
- #if Z3_USE_ENDSTOP == _XMIN_
- #define Z3_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
- #elif Z3_USE_ENDSTOP == _XMAX_
- #define Z3_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
- #elif Z3_USE_ENDSTOP == _YMIN_
- #define Z3_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
- #elif Z3_USE_ENDSTOP == _YMAX_
- #define Z3_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
- #elif Z3_USE_ENDSTOP == _ZMIN_
- #define Z3_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
- #elif Z3_USE_ENDSTOP == _ZMAX_
- #define Z3_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
- #else
- #define Z3_MAX_ENDSTOP_INVERTING false
+ #ifndef Z3_MAX_ENDSTOP_INVERTING
+ #if Z3_USE_ENDSTOP == _XMIN_
+ #define Z3_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
+ #elif Z3_USE_ENDSTOP == _XMAX_
+ #define Z3_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
+ #elif Z3_USE_ENDSTOP == _YMIN_
+ #define Z3_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
+ #elif Z3_USE_ENDSTOP == _YMAX_
+ #define Z3_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
+ #elif Z3_USE_ENDSTOP == _ZMIN_
+ #define Z3_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
+ #elif Z3_USE_ENDSTOP == _ZMAX_
+ #define Z3_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
+ #else
+ #define Z3_MAX_ENDSTOP_INVERTING false
+ #endif
#endif
#ifndef Z3_MAX_PIN
#if Z3_USE_ENDSTOP == _XMIN_
@@ -1011,23 +1079,27 @@
#define Z3_MAX_PIN E7_DIAG_PIN
#endif
#endif
- #define Z3_MIN_ENDSTOP_INVERTING false
- #else
- #if Z3_USE_ENDSTOP == _XMIN_
- #define Z3_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
- #elif Z3_USE_ENDSTOP == _XMAX_
- #define Z3_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
- #elif Z3_USE_ENDSTOP == _YMIN_
- #define Z3_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
- #elif Z3_USE_ENDSTOP == _YMAX_
- #define Z3_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
- #elif Z3_USE_ENDSTOP == _ZMIN_
- #define Z3_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
- #elif Z3_USE_ENDSTOP == _ZMAX_
- #define Z3_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
- #else
+ #ifndef Z3_MIN_ENDSTOP_INVERTING
#define Z3_MIN_ENDSTOP_INVERTING false
#endif
+ #else
+ #ifndef Z3_MIN_ENDSTOP_INVERTING
+ #if Z3_USE_ENDSTOP == _XMIN_
+ #define Z3_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
+ #elif Z3_USE_ENDSTOP == _XMAX_
+ #define Z3_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
+ #elif Z3_USE_ENDSTOP == _YMIN_
+ #define Z3_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
+ #elif Z3_USE_ENDSTOP == _YMAX_
+ #define Z3_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
+ #elif Z3_USE_ENDSTOP == _ZMIN_
+ #define Z3_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
+ #elif Z3_USE_ENDSTOP == _ZMAX_
+ #define Z3_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
+ #else
+ #define Z3_MIN_ENDSTOP_INVERTING false
+ #endif
+ #endif
#ifndef Z3_MIN_PIN
#if Z3_USE_ENDSTOP == _XMIN_
#define Z3_MIN_PIN X_MIN_PIN
@@ -1065,26 +1137,30 @@
#define Z3_MIN_PIN E7_DIAG_PIN
#endif
#endif
- #define Z3_MAX_ENDSTOP_INVERTING false
+ #ifndef Z3_MAX_ENDSTOP_INVERTING
+ #define Z3_MAX_ENDSTOP_INVERTING false
+ #endif
#endif
#endif
#if NUM_Z_STEPPER_DRIVERS >= 4
#if Z_HOME_DIR > 0
- #if Z4_USE_ENDSTOP == _XMIN_
- #define Z4_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
- #elif Z4_USE_ENDSTOP == _XMAX_
- #define Z4_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
- #elif Z4_USE_ENDSTOP == _YMIN_
- #define Z4_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
- #elif Z4_USE_ENDSTOP == _YMAX_
- #define Z4_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
- #elif Z4_USE_ENDSTOP == _ZMIN_
- #define Z4_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
- #elif Z4_USE_ENDSTOP == _ZMAX_
- #define Z4_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
- #else
- #define Z4_MAX_ENDSTOP_INVERTING false
+ #ifndef Z4_MAX_ENDSTOP_INVERTING
+ #if Z4_USE_ENDSTOP == _XMIN_
+ #define Z4_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
+ #elif Z4_USE_ENDSTOP == _XMAX_
+ #define Z4_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
+ #elif Z4_USE_ENDSTOP == _YMIN_
+ #define Z4_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
+ #elif Z4_USE_ENDSTOP == _YMAX_
+ #define Z4_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
+ #elif Z4_USE_ENDSTOP == _ZMIN_
+ #define Z4_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
+ #elif Z4_USE_ENDSTOP == _ZMAX_
+ #define Z4_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
+ #else
+ #define Z4_MAX_ENDSTOP_INVERTING false
+ #endif
#endif
#ifndef Z4_MAX_PIN
#if Z4_USE_ENDSTOP == _XMIN_
@@ -1123,23 +1199,27 @@
#define Z4_MAX_PIN E7_DIAG_PIN
#endif
#endif
- #define Z4_MIN_ENDSTOP_INVERTING false
- #else
- #if Z4_USE_ENDSTOP == _XMIN_
- #define Z4_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
- #elif Z4_USE_ENDSTOP == _XMAX_
- #define Z4_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
- #elif Z4_USE_ENDSTOP == _YMIN_
- #define Z4_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
- #elif Z4_USE_ENDSTOP == _YMAX_
- #define Z4_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
- #elif Z4_USE_ENDSTOP == _ZMIN_
- #define Z4_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
- #elif Z4_USE_ENDSTOP == _ZMAX_
- #define Z4_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
- #else
+ #ifndef Z4_MIN_ENDSTOP_INVERTING
#define Z4_MIN_ENDSTOP_INVERTING false
#endif
+ #else
+ #ifndef Z4_MIN_ENDSTOP_INVERTING
+ #if Z4_USE_ENDSTOP == _XMIN_
+ #define Z4_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
+ #elif Z4_USE_ENDSTOP == _XMAX_
+ #define Z4_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
+ #elif Z4_USE_ENDSTOP == _YMIN_
+ #define Z4_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
+ #elif Z4_USE_ENDSTOP == _YMAX_
+ #define Z4_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
+ #elif Z4_USE_ENDSTOP == _ZMIN_
+ #define Z4_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
+ #elif Z4_USE_ENDSTOP == _ZMAX_
+ #define Z4_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
+ #else
+ #define Z4_MIN_ENDSTOP_INVERTING false
+ #endif
+ #endif
#ifndef Z4_MIN_PIN
#if Z4_USE_ENDSTOP == _XMIN_
#define Z4_MIN_PIN X_MIN_PIN
@@ -1177,7 +1257,9 @@
#define Z4_MIN_PIN E7_DIAG_PIN
#endif
#endif
- #define Z4_MAX_ENDSTOP_INVERTING false
+ #ifndef Z4_MAX_ENDSTOP_INVERTING
+ #define Z4_MAX_ENDSTOP_INVERTING false
+ #endif
#endif
#endif
@@ -1236,96 +1318,243 @@
*/
// Steppers
-#define HAS_X_ENABLE (PIN_EXISTS(X_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(X)))
-#define HAS_X_DIR (PIN_EXISTS(X_DIR))
-#define HAS_X_STEP (PIN_EXISTS(X_STEP))
-#define HAS_X_MICROSTEPS (PIN_EXISTS(X_MS1))
+#if PIN_EXISTS(X_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(X))
+ #define HAS_X_ENABLE 1
+#endif
+#if PIN_EXISTS(X_DIR)
+ #define HAS_X_DIR 1
+#endif
+#if PIN_EXISTS(X_STEP)
+ #define HAS_X_STEP 1
+#endif
+#if PIN_EXISTS(X_MS1)
+ #define HAS_X_MS_PINS 1
+#endif
-#define HAS_X2_ENABLE (PIN_EXISTS(X2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(X2)))
-#define HAS_X2_DIR (PIN_EXISTS(X2_DIR))
-#define HAS_X2_STEP (PIN_EXISTS(X2_STEP))
-#define HAS_X2_MICROSTEPS (PIN_EXISTS(X2_MS1))
+#if PIN_EXISTS(X2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(X2))
+ #define HAS_X2_ENABLE 1
+#endif
+#if PIN_EXISTS(X2_DIR)
+ #define HAS_X2_DIR 1
+#endif
+#if PIN_EXISTS(X2_STEP)
+ #define HAS_X2_STEP 1
+#endif
+#if PIN_EXISTS(X2_MS1)
+ #define HAS_X2_MS_PINS 1
+#endif
-#define HAS_Y_ENABLE (PIN_EXISTS(Y_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y)))
-#define HAS_Y_DIR (PIN_EXISTS(Y_DIR))
-#define HAS_Y_STEP (PIN_EXISTS(Y_STEP))
-#define HAS_Y_MICROSTEPS (PIN_EXISTS(Y_MS1))
+#if PIN_EXISTS(Y_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y))
+ #define HAS_Y_ENABLE 1
+#endif
+#if PIN_EXISTS(Y_DIR)
+ #define HAS_Y_DIR 1
+#endif
+#if PIN_EXISTS(Y_STEP)
+ #define HAS_Y_STEP 1
+#endif
+#if PIN_EXISTS(Y_MS1)
+ #define HAS_Y_MS_PINS 1
+#endif
-#define HAS_Y2_ENABLE (PIN_EXISTS(Y2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2)))
-#define HAS_Y2_DIR (PIN_EXISTS(Y2_DIR))
-#define HAS_Y2_STEP (PIN_EXISTS(Y2_STEP))
-#define HAS_Y2_MICROSTEPS (PIN_EXISTS(Y2_MS1))
+#if PIN_EXISTS(Y2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2))
+ #define HAS_Y2_ENABLE 1
+#endif
+#if PIN_EXISTS(Y2_DIR)
+ #define HAS_Y2_DIR 1
+#endif
+#if PIN_EXISTS(Y2_STEP)
+ #define HAS_Y2_STEP 1
+#endif
+#if PIN_EXISTS(Y2_MS1)
+ #define HAS_Y2_MS_PINS 1
+#endif
-#define HAS_Z_ENABLE (PIN_EXISTS(Z_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z)))
-#define HAS_Z_DIR (PIN_EXISTS(Z_DIR))
-#define HAS_Z_STEP (PIN_EXISTS(Z_STEP))
-#define HAS_Z_MICROSTEPS (PIN_EXISTS(Z_MS1))
+#if PIN_EXISTS(Z_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z))
+ #define HAS_Z_ENABLE 1
+#endif
+#if PIN_EXISTS(Z_DIR)
+ #define HAS_Z_DIR 1
+#endif
+#if PIN_EXISTS(Z_STEP)
+ #define HAS_Z_STEP 1
+#endif
+#if PIN_EXISTS(Z_MS1)
+ #define HAS_Z_MS_PINS 1
+#endif
-#define HAS_Z2_ENABLE (PIN_EXISTS(Z2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2)))
-#define HAS_Z2_DIR (PIN_EXISTS(Z2_DIR))
-#define HAS_Z2_STEP (PIN_EXISTS(Z2_STEP))
-#define HAS_Z2_MICROSTEPS (PIN_EXISTS(Z2_MS1))
+#if PIN_EXISTS(Z2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2))
+ #define HAS_Z2_ENABLE 1
+#endif
+#if PIN_EXISTS(Z2_DIR)
+ #define HAS_Z2_DIR 1
+#endif
+#if PIN_EXISTS(Z2_STEP)
+ #define HAS_Z2_STEP 1
+#endif
+#if PIN_EXISTS(Z2_MS1)
+ #define HAS_Z2_MS_PINS 1
+#endif
-#define HAS_Z3_ENABLE (PIN_EXISTS(Z3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3)))
-#define HAS_Z3_DIR (PIN_EXISTS(Z3_DIR))
-#define HAS_Z3_STEP (PIN_EXISTS(Z3_STEP))
-#define HAS_Z3_MICROSTEPS (PIN_EXISTS(Z3_MS1))
+#if PIN_EXISTS(Z3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3))
+ #define HAS_Z3_ENABLE 1
+#endif
+#if PIN_EXISTS(Z3_DIR)
+ #define HAS_Z3_DIR 1
+#endif
+#if PIN_EXISTS(Z3_STEP)
+ #define HAS_Z3_STEP 1
+#endif
+#if PIN_EXISTS(Z3_MS1)
+ #define HAS_Z3_MS_PINS 1
+#endif
-#define HAS_Z4_ENABLE (PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4)))
-#define HAS_Z4_DIR (PIN_EXISTS(Z4_DIR))
-#define HAS_Z4_STEP (PIN_EXISTS(Z4_STEP))
-#define HAS_Z4_MICROSTEPS (PIN_EXISTS(Z4_MS1))
+#if PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4))
+ #define HAS_Z4_ENABLE 1
+#endif
+#if PIN_EXISTS(Z4_DIR)
+ #define HAS_Z4_DIR 1
+#endif
+#if PIN_EXISTS(Z4_STEP)
+ #define HAS_Z4_STEP 1
+#endif
+#if PIN_EXISTS(Z4_MS1)
+ #define HAS_Z4_MS_PINS 1
+#endif
// Extruder steppers and solenoids
-#define HAS_E0_ENABLE (PIN_EXISTS(E0_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0)))
-#define HAS_E0_DIR (PIN_EXISTS(E0_DIR))
-#define HAS_E0_STEP (PIN_EXISTS(E0_STEP))
-#define HAS_E0_MICROSTEPS (PIN_EXISTS(E0_MS1))
-#define HAS_SOLENOID_0 (PIN_EXISTS(SOL0))
+#if PIN_EXISTS(E0_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0))
+ #define HAS_E0_ENABLE 1
+#endif
+#if PIN_EXISTS(E0_DIR)
+ #define HAS_E0_DIR 1
+#endif
+#if PIN_EXISTS(E0_STEP)
+ #define HAS_E0_STEP 1
+#endif
+#if PIN_EXISTS(E0_MS1)
+ #define HAS_E0_MS_PINS 1
+#endif
+#if PIN_EXISTS(SOL0)
+ #define HAS_SOLENOID_0 1
+#endif
-#define HAS_E1_ENABLE (PIN_EXISTS(E1_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E1)))
-#define HAS_E1_DIR (PIN_EXISTS(E1_DIR))
-#define HAS_E1_STEP (PIN_EXISTS(E1_STEP))
-#define HAS_E1_MICROSTEPS (PIN_EXISTS(E1_MS1))
-#define HAS_SOLENOID_1 (PIN_EXISTS(SOL1))
+#if PIN_EXISTS(E1_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E1))
+ #define HAS_E1_ENABLE 1
+#endif
+#if PIN_EXISTS(E1_DIR)
+ #define HAS_E1_DIR 1
+#endif
+#if PIN_EXISTS(E1_STEP)
+ #define HAS_E1_STEP 1
+#endif
+#if PIN_EXISTS(E1_MS1)
+ #define HAS_E1_MS_PINS 1
+#endif
+#if PIN_EXISTS(SOL1)
+ #define HAS_SOLENOID_1 1
+#endif
-#define HAS_E2_ENABLE (PIN_EXISTS(E2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E2)))
-#define HAS_E2_DIR (PIN_EXISTS(E2_DIR))
-#define HAS_E2_STEP (PIN_EXISTS(E2_STEP))
-#define HAS_E2_MICROSTEPS (PIN_EXISTS(E2_MS1))
-#define HAS_SOLENOID_2 (PIN_EXISTS(SOL2))
+#if PIN_EXISTS(E2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E2))
+ #define HAS_E2_ENABLE 1
+#endif
+#if PIN_EXISTS(E2_DIR)
+ #define HAS_E2_DIR 1
+#endif
+#if PIN_EXISTS(E2_STEP)
+ #define HAS_E2_STEP 1
+#endif
+#if PIN_EXISTS(E2_MS1)
+ #define HAS_E2_MS_PINS 1
+#endif
+#if PIN_EXISTS(SOL2)
+ #define HAS_SOLENOID_2 1
+#endif
-#define HAS_E3_ENABLE (PIN_EXISTS(E3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E3)))
-#define HAS_E3_DIR (PIN_EXISTS(E3_DIR))
-#define HAS_E3_STEP (PIN_EXISTS(E3_STEP))
-#define HAS_E3_MICROSTEPS (PIN_EXISTS(E3_MS1))
-#define HAS_SOLENOID_3 (PIN_EXISTS(SOL3))
+#if PIN_EXISTS(E3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E3))
+ #define HAS_E3_ENABLE 1
+#endif
+#if PIN_EXISTS(E3_DIR)
+ #define HAS_E3_DIR 1
+#endif
+#if PIN_EXISTS(E3_STEP)
+ #define HAS_E3_STEP 1
+#endif
+#if PIN_EXISTS(E3_MS1)
+ #define HAS_E3_MS_PINS 1
+#endif
+#if PIN_EXISTS(SOL3)
+ #define HAS_SOLENOID_3 1
+#endif
-#define HAS_E4_ENABLE (PIN_EXISTS(E4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E4)))
-#define HAS_E4_DIR (PIN_EXISTS(E4_DIR))
-#define HAS_E4_STEP (PIN_EXISTS(E4_STEP))
-#define HAS_E4_MICROSTEPS (PIN_EXISTS(E4_MS1))
-#define HAS_SOLENOID_4 (PIN_EXISTS(SOL4))
+#if PIN_EXISTS(E4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E4))
+ #define HAS_E4_ENABLE 1
+#endif
+#if PIN_EXISTS(E4_DIR)
+ #define HAS_E4_DIR 1
+#endif
+#if PIN_EXISTS(E4_STEP)
+ #define HAS_E4_STEP 1
+#endif
+#if PIN_EXISTS(E4_MS1)
+ #define HAS_E4_MS_PINS 1
+#endif
+#if PIN_EXISTS(SOL4)
+ #define HAS_SOLENOID_4 1
+#endif
-#define HAS_E5_ENABLE (PIN_EXISTS(E5_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E5)))
-#define HAS_E5_DIR (PIN_EXISTS(E5_DIR))
-#define HAS_E5_STEP (PIN_EXISTS(E5_STEP))
-#define HAS_E5_MICROSTEPS (PIN_EXISTS(E5_MS1))
-#define HAS_SOLENOID_5 (PIN_EXISTS(SOL5))
+#if PIN_EXISTS(E5_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E5))
+ #define HAS_E5_ENABLE 1
+#endif
+#if PIN_EXISTS(E5_DIR)
+ #define HAS_E5_DIR 1
+#endif
+#if PIN_EXISTS(E5_STEP)
+ #define HAS_E5_STEP 1
+#endif
+#if PIN_EXISTS(E5_MS1)
+ #define HAS_E5_MS_PINS 1
+#endif
+#if PIN_EXISTS(SOL5)
+ #define HAS_SOLENOID_5 1
+#endif
-#define HAS_E6_ENABLE (PIN_EXISTS(E6_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6)))
-#define HAS_E6_DIR (PIN_EXISTS(E6_DIR))
-#define HAS_E6_STEP (PIN_EXISTS(E6_STEP))
-#define HAS_E6_MICROSTEPS (PIN_EXISTS(E6_MS1))
-#define HAS_SOLENOID_6 (PIN_EXISTS(SOL6))
+#if PIN_EXISTS(E6_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6))
+ #define HAS_E6_ENABLE 1
+#endif
+#if PIN_EXISTS(E6_DIR)
+ #define HAS_E6_DIR 1
+#endif
+#if PIN_EXISTS(E6_STEP)
+ #define HAS_E6_STEP 1
+#endif
+#if PIN_EXISTS(E6_MS1)
+ #define HAS_E6_MS_PINS 1
+#endif
+#if PIN_EXISTS(SOL6)
+ #define HAS_SOLENOID_6 1
+#endif
-#define HAS_E7_ENABLE (PIN_EXISTS(E7_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7)))
-#define HAS_E7_DIR (PIN_EXISTS(E7_DIR))
-#define HAS_E7_STEP (PIN_EXISTS(E7_STEP))
-#define HAS_E7_MICROSTEPS (PIN_EXISTS(E7_MS1))
-#define HAS_SOLENOID_7 (PIN_EXISTS(SOL7))
+#if PIN_EXISTS(E7_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7))
+ #define HAS_E7_ENABLE 1
+#endif
+#if PIN_EXISTS(E7_DIR)
+ #define HAS_E7_DIR 1
+#endif
+#if PIN_EXISTS(E7_STEP)
+ #define HAS_E7_STEP 1
+#endif
+#if PIN_EXISTS(E7_MS1)
+ #define HAS_E7_MS_PINS 1
+#endif
+#if PIN_EXISTS(SOL7)
+ #define HAS_SOLENOID_7 1
+#endif
+//
// Trinamic Stepper Drivers
+//
+
#if HAS_TRINAMIC_CONFIG
#if ANY(STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_E)
#define STEALTHCHOP_ENABLED 1
@@ -1336,6 +1565,9 @@
// Disable Z axis sensorless homing if a probe is used to home the Z axis
#if HOMING_Z_WITH_PROBE
#undef Z_STALL_SENSITIVITY
+ #undef Z2_STALL_SENSITIVITY
+ #undef Z3_STALL_SENSITIVITY
+ #undef Z4_STALL_SENSITIVITY
#endif
#if defined(X_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(X)
#define X_SENSORLESS 1
@@ -1368,10 +1600,18 @@
#endif
#endif
-#define HAS_E_STEPPER_ENABLE (HAS_E_DRIVER(TMC2660) \
+#if (HAS_E_DRIVER(TMC2660) \
|| ( E0_ENABLE_PIN != X_ENABLE_PIN && E1_ENABLE_PIN != X_ENABLE_PIN \
- && E0_ENABLE_PIN != Y_ENABLE_PIN && E1_ENABLE_PIN != Y_ENABLE_PIN ) \
-)
+ && E0_ENABLE_PIN != Y_ENABLE_PIN && E1_ENABLE_PIN != Y_ENABLE_PIN ) )
+ #define HAS_E_STEPPER_ENABLE 1
+#endif
+
+#if ANY_AXIS_HAS(HW_SERIAL)
+ #define HAS_TMC_HW_SERIAL 1
+#endif
+#if ANY_AXIS_HAS(SW_SERIAL)
+ #define HAS_TMC_SW_SERIAL 1
+#endif
//
// Endstops and bed probe
@@ -1386,66 +1626,163 @@
#define IS_Z4_ENDSTOP(A,M) (ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 && Z4_USE_ENDSTOP == _##A##M##_)
#define _HAS_STOP(A,M) (PIN_EXISTS(A##_##M) && !IS_PROBE_PIN(A,M) && !IS_X2_ENDSTOP(A,M) && !IS_Y2_ENDSTOP(A,M) && !IS_Z2_ENDSTOP(A,M) && !IS_Z3_ENDSTOP(A,M) && !IS_Z4_ENDSTOP(A,M))
-#define HAS_X_MIN _HAS_STOP(X,MIN)
-#define HAS_X_MAX _HAS_STOP(X,MAX)
-#define HAS_Y_MIN _HAS_STOP(Y,MIN)
-#define HAS_Y_MAX _HAS_STOP(Y,MAX)
-#define HAS_Z_MIN _HAS_STOP(Z,MIN)
-#define HAS_Z_MAX _HAS_STOP(Z,MAX)
-#define HAS_X2_MIN (PIN_EXISTS(X2_MIN))
-#define HAS_X2_MAX (PIN_EXISTS(X2_MAX))
-#define HAS_Y2_MIN (PIN_EXISTS(Y2_MIN))
-#define HAS_Y2_MAX (PIN_EXISTS(Y2_MAX))
-#define HAS_Z2_MIN (PIN_EXISTS(Z2_MIN))
-#define HAS_Z2_MAX (PIN_EXISTS(Z2_MAX))
-#define HAS_Z3_MIN (PIN_EXISTS(Z3_MIN))
-#define HAS_Z3_MAX (PIN_EXISTS(Z3_MAX))
-#define HAS_Z4_MIN (PIN_EXISTS(Z4_MIN))
-#define HAS_Z4_MAX (PIN_EXISTS(Z4_MAX))
-#define HAS_Z_MIN_PROBE_PIN (HAS_CUSTOM_PROBE_PIN && PIN_EXISTS(Z_MIN_PROBE))
+#if _HAS_STOP(X,MIN)
+ #define HAS_X_MIN 1
+#endif
+#if _HAS_STOP(X,MAX)
+ #define HAS_X_MAX 1
+#endif
+#if _HAS_STOP(Y,MIN)
+ #define HAS_Y_MIN 1
+#endif
+#if _HAS_STOP(Y,MAX)
+ #define HAS_Y_MAX 1
+#endif
+#if _HAS_STOP(Z,MIN)
+ #define HAS_Z_MIN 1
+#endif
+#if _HAS_STOP(Z,MAX)
+ #define HAS_Z_MAX 1
+#endif
+#if _HAS_STOP(X,STOP)
+ #define HAS_X_STOP 1
+#endif
+#if _HAS_STOP(Y,STOP)
+ #define HAS_Y_STOP 1
+#endif
+#if _HAS_STOP(Z,STOP)
+ #define HAS_Z_STOP 1
+#endif
+#if PIN_EXISTS(X2_MIN)
+ #define HAS_X2_MIN 1
+#endif
+#if PIN_EXISTS(X2_MAX)
+ #define HAS_X2_MAX 1
+#endif
+#if PIN_EXISTS(Y2_MIN)
+ #define HAS_Y2_MIN 1
+#endif
+#if PIN_EXISTS(Y2_MAX)
+ #define HAS_Y2_MAX 1
+#endif
+#if PIN_EXISTS(Z2_MIN)
+ #define HAS_Z2_MIN 1
+#endif
+#if PIN_EXISTS(Z2_MAX)
+ #define HAS_Z2_MAX 1
+#endif
+#if PIN_EXISTS(Z3_MIN)
+ #define HAS_Z3_MIN 1
+#endif
+#if PIN_EXISTS(Z3_MAX)
+ #define HAS_Z3_MAX 1
+#endif
+#if PIN_EXISTS(Z4_MIN)
+ #define HAS_Z4_MIN 1
+#endif
+#if PIN_EXISTS(Z4_MAX)
+ #define HAS_Z4_MAX 1
+#endif
+#if HAS_CUSTOM_PROBE_PIN && PIN_EXISTS(Z_MIN_PROBE)
+ #define HAS_Z_MIN_PROBE_PIN 1
+#endif
//
// ADC Temp Sensors (Thermistor or Thermocouple with amplifier ADC interface)
//
#define HAS_ADC_TEST(P) (PIN_EXISTS(TEMP_##P) && TEMP_SENSOR_##P != 0 && DISABLED(HEATER_##P##_USES_MAX6675))
-#define HAS_TEMP_ADC_0 HAS_ADC_TEST(0)
-#define HAS_TEMP_ADC_1 HAS_ADC_TEST(1)
-#define HAS_TEMP_ADC_2 HAS_ADC_TEST(2)
-#define HAS_TEMP_ADC_3 HAS_ADC_TEST(3)
-#define HAS_TEMP_ADC_4 HAS_ADC_TEST(4)
-#define HAS_TEMP_ADC_5 HAS_ADC_TEST(5)
-#define HAS_TEMP_ADC_6 HAS_ADC_TEST(6)
-#define HAS_TEMP_ADC_7 HAS_ADC_TEST(7)
-#define HAS_TEMP_ADC_BED HAS_ADC_TEST(BED)
-#define HAS_TEMP_ADC_PROBE HAS_ADC_TEST(PROBE)
-#define HAS_TEMP_ADC_CHAMBER HAS_ADC_TEST(CHAMBER)
+#if HAS_ADC_TEST(0)
+ #define HAS_TEMP_ADC_0 1
+#endif
+#if HAS_ADC_TEST(1)
+ #define HAS_TEMP_ADC_1 1
+#endif
+#if HAS_ADC_TEST(2)
+ #define HAS_TEMP_ADC_2 1
+#endif
+#if HAS_ADC_TEST(3)
+ #define HAS_TEMP_ADC_3 1
+#endif
+#if HAS_ADC_TEST(4)
+ #define HAS_TEMP_ADC_4 1
+#endif
+#if HAS_ADC_TEST(5)
+ #define HAS_TEMP_ADC_5 1
+#endif
+#if HAS_ADC_TEST(6)
+ #define HAS_TEMP_ADC_6 1
+#endif
+#if HAS_ADC_TEST(7)
+ #define HAS_TEMP_ADC_7 1
+#endif
+#if HAS_ADC_TEST(BED)
+ #define HAS_TEMP_ADC_BED 1
+#endif
+#if HAS_ADC_TEST(PROBE)
+ #define HAS_TEMP_ADC_PROBE 1
+#endif
+#if HAS_ADC_TEST(CHAMBER)
+ #define HAS_TEMP_ADC_CHAMBER 1
+#endif
-#define HAS_TEMP_HOTEND ((HAS_TEMP_ADC_0 || ENABLED(HEATER_0_USES_MAX6675)) && HOTENDS)
+#if HAS_HOTEND && EITHER(HAS_TEMP_ADC_0, HEATER_0_USES_MAX6675)
+ #define HAS_TEMP_HOTEND 1
+#endif
#define HAS_TEMP_BED HAS_TEMP_ADC_BED
#define HAS_TEMP_PROBE HAS_TEMP_ADC_PROBE
#define HAS_TEMP_CHAMBER HAS_TEMP_ADC_CHAMBER
#if ENABLED(JOYSTICK)
- #define HAS_JOY_ADC_X PIN_EXISTS(JOY_X)
- #define HAS_JOY_ADC_Y PIN_EXISTS(JOY_Y)
- #define HAS_JOY_ADC_Z PIN_EXISTS(JOY_Z)
- #define HAS_JOY_ADC_EN PIN_EXISTS(JOY_EN)
+ #if PIN_EXISTS(JOY_X)
+ #define HAS_JOY_ADC_X 1
+ #endif
+ #if PIN_EXISTS(JOY_Y)
+ #define HAS_JOY_ADC_Y 1
+ #endif
+ #if PIN_EXISTS(JOY_Z)
+ #define HAS_JOY_ADC_Z 1
+ #endif
+ #if PIN_EXISTS(JOY_EN)
+ #define HAS_JOY_ADC_EN 1
+ #endif
#endif
// Heaters
-#define HAS_HEATER_0 (PIN_EXISTS(HEATER_0))
-#define HAS_HEATER_1 (PIN_EXISTS(HEATER_1))
-#define HAS_HEATER_2 (PIN_EXISTS(HEATER_2))
-#define HAS_HEATER_3 (PIN_EXISTS(HEATER_3))
-#define HAS_HEATER_4 (PIN_EXISTS(HEATER_4))
-#define HAS_HEATER_5 (PIN_EXISTS(HEATER_5))
-#define HAS_HEATER_6 (PIN_EXISTS(HEATER_6))
-#define HAS_HEATER_7 (PIN_EXISTS(HEATER_7))
-#define HAS_HEATER_BED (PIN_EXISTS(HEATER_BED))
+#if PIN_EXISTS(HEATER_0)
+ #define HAS_HEATER_0 1
+#endif
+#if PIN_EXISTS(HEATER_1)
+ #define HAS_HEATER_1 1
+#endif
+#if PIN_EXISTS(HEATER_2)
+ #define HAS_HEATER_2 1
+#endif
+#if PIN_EXISTS(HEATER_3)
+ #define HAS_HEATER_3 1
+#endif
+#if PIN_EXISTS(HEATER_4)
+ #define HAS_HEATER_4 1
+#endif
+#if PIN_EXISTS(HEATER_5)
+ #define HAS_HEATER_5 1
+#endif
+#if PIN_EXISTS(HEATER_6)
+ #define HAS_HEATER_6 1
+#endif
+#if PIN_EXISTS(HEATER_7)
+ #define HAS_HEATER_7 1
+#endif
+#if PIN_EXISTS(HEATER_BED)
+ #define HAS_HEATER_BED 1
+#endif
// Shorthand for common combinations
#if HAS_TEMP_BED && HAS_HEATER_BED
#define HAS_HEATED_BED 1
+ #ifndef BED_OVERSHOOT
+ #define BED_OVERSHOOT 10
+ #endif
+ #define BED_MAX_TARGET (BED_MAXTEMP - (BED_OVERSHOOT))
#endif
#if HAS_HEATED_BED || HAS_TEMP_CHAMBER
#define BED_OR_CHAMBER 1
@@ -1469,7 +1806,7 @@
#endif
// Thermal protection
-#if HAS_HEATED_BED && ENABLED(THERMAL_PROTECTION_BED)
+#if BOTH(HAS_HEATED_BED, THERMAL_PROTECTION_BED)
#define HAS_THERMALLY_PROTECTED_BED 1
#endif
#if ENABLED(THERMAL_PROTECTION_HOTENDS) && WATCH_TEMP_PERIOD > 0
@@ -1478,7 +1815,7 @@
#if HAS_THERMALLY_PROTECTED_BED && WATCH_BED_TEMP_PERIOD > 0
#define WATCH_BED 1
#endif
-#if HAS_HEATED_CHAMBER && ENABLED(THERMAL_PROTECTION_CHAMBER) && WATCH_CHAMBER_TEMP_PERIOD > 0
+#if BOTH(HAS_HEATED_CHAMBER, THERMAL_PROTECTION_CHAMBER) && WATCH_CHAMBER_TEMP_PERIOD > 0
#define WATCH_CHAMBER 1
#endif
#if (ENABLED(THERMAL_PROTECTION_HOTENDS) || !EXTRUDERS) \
@@ -1488,52 +1825,111 @@
#endif
// Auto fans
-#define HAS_AUTO_FAN_0 (HOTENDS > 0 && PIN_EXISTS(E0_AUTO_FAN))
-#define HAS_AUTO_FAN_1 (HOTENDS > 1 && PIN_EXISTS(E1_AUTO_FAN))
-#define HAS_AUTO_FAN_2 (HOTENDS > 2 && PIN_EXISTS(E2_AUTO_FAN))
-#define HAS_AUTO_FAN_3 (HOTENDS > 3 && PIN_EXISTS(E3_AUTO_FAN))
-#define HAS_AUTO_FAN_4 (HOTENDS > 4 && PIN_EXISTS(E4_AUTO_FAN))
-#define HAS_AUTO_FAN_5 (HOTENDS > 5 && PIN_EXISTS(E5_AUTO_FAN))
-#define HAS_AUTO_FAN_6 (HOTENDS > 6 && PIN_EXISTS(E6_AUTO_FAN))
-#define HAS_AUTO_FAN_7 (HOTENDS > 7 && PIN_EXISTS(E7_AUTO_FAN))
-#define HAS_AUTO_CHAMBER_FAN (HAS_TEMP_CHAMBER && PIN_EXISTS(CHAMBER_AUTO_FAN))
+#if HAS_HOTEND && PIN_EXISTS(E0_AUTO_FAN)
+ #define HAS_AUTO_FAN_0 1
+#endif
+#if HAS_MULTI_HOTEND && PIN_EXISTS(E1_AUTO_FAN)
+ #define HAS_AUTO_FAN_1 1
+#endif
+#if HOTENDS > 2 && PIN_EXISTS(E2_AUTO_FAN)
+ #define HAS_AUTO_FAN_2 1
+#endif
+#if HOTENDS > 3 && PIN_EXISTS(E3_AUTO_FAN)
+ #define HAS_AUTO_FAN_3 1
+#endif
+#if HOTENDS > 4 && PIN_EXISTS(E4_AUTO_FAN)
+ #define HAS_AUTO_FAN_4 1
+#endif
+#if HOTENDS > 5 && PIN_EXISTS(E5_AUTO_FAN)
+ #define HAS_AUTO_FAN_5 1
+#endif
+#if HOTENDS > 6 && PIN_EXISTS(E6_AUTO_FAN)
+ #define HAS_AUTO_FAN_6 1
+#endif
+#if HOTENDS > 7 && PIN_EXISTS(E7_AUTO_FAN)
+ #define HAS_AUTO_FAN_7 1
+#endif
+#if HAS_TEMP_CHAMBER && PIN_EXISTS(CHAMBER_AUTO_FAN)
+ #define HAS_AUTO_CHAMBER_FAN 1
+#endif
-#define HAS_AUTO_FAN (HAS_AUTO_FAN_0 || HAS_AUTO_FAN_1 || HAS_AUTO_FAN_2 || HAS_AUTO_FAN_3 || HAS_AUTO_FAN_4 || HAS_AUTO_FAN_5 || HAS_AUTO_FAN_6 || HAS_AUTO_FAN_7 || HAS_AUTO_CHAMBER_FAN)
+#if ANY(HAS_AUTO_FAN_0, HAS_AUTO_FAN_1, HAS_AUTO_FAN_2, HAS_AUTO_FAN_3, HAS_AUTO_FAN_4, HAS_AUTO_FAN_5, HAS_AUTO_FAN_6, HAS_AUTO_FAN_7, HAS_AUTO_CHAMBER_FAN)
+ #define HAS_AUTO_FAN 1
+#endif
#define _FANOVERLAP(A,B) (A##_AUTO_FAN_PIN == E##B##_AUTO_FAN_PIN)
-#if HAS_AUTO_FAN
- #define AUTO_CHAMBER_IS_E (_FANOVERLAP(CHAMBER,0) || _FANOVERLAP(CHAMBER,1) || _FANOVERLAP(CHAMBER,2) || _FANOVERLAP(CHAMBER,3) || _FANOVERLAP(CHAMBER,4) || _FANOVERLAP(CHAMBER,5) || _FANOVERLAP(CHAMBER,6) || _FANOVERLAP(CHAMBER,7))
+#if HAS_AUTO_FAN && (_FANOVERLAP(CHAMBER,0) || _FANOVERLAP(CHAMBER,1) || _FANOVERLAP(CHAMBER,2) || _FANOVERLAP(CHAMBER,3) || _FANOVERLAP(CHAMBER,4) || _FANOVERLAP(CHAMBER,5) || _FANOVERLAP(CHAMBER,6) || _FANOVERLAP(CHAMBER,7))
+ #define AUTO_CHAMBER_IS_E 1
#endif
#if !HAS_TEMP_SENSOR
#undef AUTO_REPORT_TEMPERATURES
#endif
-#define HAS_AUTO_REPORTING EITHER(AUTO_REPORT_TEMPERATURES, AUTO_REPORT_SD_STATUS)
+#if EITHER(AUTO_REPORT_TEMPERATURES, AUTO_REPORT_SD_STATUS)
+ #define HAS_AUTO_REPORTING 1
+#endif
#if !HAS_AUTO_CHAMBER_FAN || AUTO_CHAMBER_IS_E
#undef AUTO_POWER_CHAMBER_FAN
#endif
// Other fans
-#define HAS_FAN0 (PIN_EXISTS(FAN))
-#define _HAS_FAN(P) (PIN_EXISTS(FAN##P) && CONTROLLER_FAN_PIN != FAN##P##_PIN && E0_AUTO_FAN_PIN != FAN##P##_PIN && E1_AUTO_FAN_PIN != FAN##P##_PIN && E2_AUTO_FAN_PIN != FAN##P##_PIN && E3_AUTO_FAN_PIN != FAN##P##_PIN && E4_AUTO_FAN_PIN != FAN##P##_PIN && E5_AUTO_FAN_PIN != FAN##P##_PIN && E6_AUTO_FAN_PIN != FAN##P##_PIN && E7_AUTO_FAN_PIN != FAN##P##_PIN)
-#define HAS_FAN1 _HAS_FAN(1)
-#define HAS_FAN2 _HAS_FAN(2)
-#define HAS_FAN3 _HAS_FAN(3)
-#define HAS_FAN4 _HAS_FAN(4)
-#define HAS_FAN5 _HAS_FAN(5)
-#define HAS_FAN6 _HAS_FAN(6)
-#define HAS_FAN7 _HAS_FAN(7)
-#define HAS_CONTROLLER_FAN (PIN_EXISTS(CONTROLLER_FAN))
+#if PIN_EXISTS(FAN)
+ #define HAS_FAN0 1
+#endif
+#define _NOT_E_AUTO(N,F) (E##N##_AUTO_FAN_PIN != FAN##F##_PIN)
+#define _HAS_FAN(F) (PIN_EXISTS(FAN##F) && CONTROLLER_FAN_PIN != FAN##F##_PIN && _NOT_E_AUTO(0,F) && _NOT_E_AUTO(1,F) && _NOT_E_AUTO(2,F) && _NOT_E_AUTO(3,F) && _NOT_E_AUTO(4,F) && _NOT_E_AUTO(5,F) && _NOT_E_AUTO(6,F) && _NOT_E_AUTO(7,F))
+#if _HAS_FAN(1)
+ #define HAS_FAN1 1
+#endif
+#if _HAS_FAN(2)
+ #define HAS_FAN2 1
+#endif
+#if _HAS_FAN(3)
+ #define HAS_FAN3 1
+#endif
+#if _HAS_FAN(4)
+ #define HAS_FAN4 1
+#endif
+#if _HAS_FAN(5)
+ #define HAS_FAN5 1
+#endif
+#if _HAS_FAN(6)
+ #define HAS_FAN6 1
+#endif
+#if _HAS_FAN(7)
+ #define HAS_FAN7 1
+#endif
+#undef _NOT_E_AUTO
+#undef _HAS_FAN
+#if PIN_EXISTS(CONTROLLER_FAN)
+ #define HAS_CONTROLLER_FAN 1
+#endif
+
+#if BED_OR_CHAMBER || HAS_FAN0
+ #define BED_OR_CHAMBER_OR_FAN 1
+#endif
// Servos
-#define HAS_SERVO_0 (PIN_EXISTS(SERVO0) && NUM_SERVOS > 0)
-#define HAS_SERVO_1 (PIN_EXISTS(SERVO1) && NUM_SERVOS > 1)
-#define HAS_SERVO_2 (PIN_EXISTS(SERVO2) && NUM_SERVOS > 2)
-#define HAS_SERVO_3 (PIN_EXISTS(SERVO3) && NUM_SERVOS > 3)
-#define HAS_SERVOS (NUM_SERVOS > 0)
+#if PIN_EXISTS(SERVO0) && NUM_SERVOS > 0
+ #define HAS_SERVO_0 1
+#endif
+#if PIN_EXISTS(SERVO1) && NUM_SERVOS > 1
+ #define HAS_SERVO_1 1
+#endif
+#if PIN_EXISTS(SERVO2) && NUM_SERVOS > 2
+ #define HAS_SERVO_2 1
+#endif
+#if PIN_EXISTS(SERVO3) && NUM_SERVOS > 3
+ #define HAS_SERVO_3 1
+#endif
+#if NUM_SERVOS > 0
+ #define HAS_SERVOS 1
+#endif
// Sensors
-#define HAS_FILAMENT_WIDTH_SENSOR (PIN_EXISTS(FILWIDTH))
+#if PIN_EXISTS(FILWIDTH)
+ #define HAS_FILAMENT_WIDTH_SENSOR 1
+#endif
// User Interface
#if PIN_EXISTS(HOME)
@@ -1548,12 +1944,6 @@
#if PIN_EXISTS(PHOTOGRAPH)
#define HAS_PHOTOGRAPH 1
#endif
-#if PIN_EXISTS(BEEPER) || EITHER(LCD_USE_I2C_BUZZER, PCA9632_BUZZER)
- #define HAS_BUZZER 1
-#endif
-#if HAS_BUZZER && DISABLED(LCD_USE_I2C_BUZZER, PCA9632_BUZZER)
- #define USE_BEEPER 1
-#endif
#if PIN_EXISTS(CASE_LIGHT) && ENABLED(CASE_LIGHT_ENABLE)
#define HAS_CASE_LIGHT 1
#endif
@@ -1569,13 +1959,13 @@
#define HAS_MOTOR_CURRENT_PWM 1
#endif
-#if HAS_Z_MICROSTEPS || HAS_Z2_MICROSTEPS || HAS_Z3_MICROSTEPS || HAS_Z4_MICROSTEPS
- #define HAS_SOME_Z_MICROSTEPS 1
+#if ANY(HAS_Z_MS_PINS, HAS_Z2_MS_PINS, HAS_Z3_MS_PINS, HAS_Z4_MS_PINS)
+ #define HAS_SOME_Z_MS_PINS 1
#endif
-#if HAS_E0_MICROSTEPS || HAS_E1_MICROSTEPS || HAS_E2_MICROSTEPS || HAS_E3_MICROSTEPS || HAS_E4_MICROSTEPS || HAS_E5_MICROSTEPS || HAS_E6_MICROSTEPS || HAS_E7_MICROSTEPS
- #define HAS_SOME_E_MICROSTEPS 1
+#if ANY(HAS_E0_MS_PINS, HAS_E1_MS_PINS, HAS_E2_MS_PINS, HAS_E3_MS_PINS, HAS_E4_MS_PINS, HAS_E5_MS_PINS, HAS_E6_MS_PINS, HAS_E7_MS_PINS)
+ #define HAS_SOME_E_MS_PINS 1
#endif
-#if HAS_X_MICROSTEPS || HAS_X2_MICROSTEPS || HAS_Y_MICROSTEPS || HAS_Y2_MICROSTEPS || HAS_SOME_Z_MICROSTEPS || HAS_SOME_E_MICROSTEPS
+#if ANY(HAS_X_MS_PINS, HAS_X2_MS_PINS, HAS_Y_MS_PINS, HAS_Y2_MS_PINS, HAS_SOME_Z_MS_PINS, HAS_SOME_E_MS_PINS)
#define HAS_MICROSTEPS 1
#endif
@@ -1619,14 +2009,30 @@
#endif
#endif
- #define HAS_MICROSTEP1 defined(MICROSTEP1)
- #define HAS_MICROSTEP2 defined(MICROSTEP2)
- #define HAS_MICROSTEP4 defined(MICROSTEP4)
- #define HAS_MICROSTEP8 defined(MICROSTEP8)
- #define HAS_MICROSTEP16 defined(MICROSTEP16)
- #define HAS_MICROSTEP32 defined(MICROSTEP32)
- #define HAS_MICROSTEP64 defined(MICROSTEP64)
- #define HAS_MICROSTEP128 defined(MICROSTEP128)
+ #ifdef MICROSTEP1
+ #define HAS_MICROSTEP1 1
+ #endif
+ #ifdef MICROSTEP2
+ #define HAS_MICROSTEP2 1
+ #endif
+ #ifdef MICROSTEP4
+ #define HAS_MICROSTEP4 1
+ #endif
+ #ifdef MICROSTEP8
+ #define HAS_MICROSTEP8 1
+ #endif
+ #ifdef MICROSTEP16
+ #define HAS_MICROSTEP16 1
+ #endif
+ #ifdef MICROSTEP32
+ #define HAS_MICROSTEP32 1
+ #endif
+ #ifdef MICROSTEP64
+ #define HAS_MICROSTEP64 1
+ #endif
+ #ifdef MICROSTEP128
+ #define HAS_MICROSTEP128 1
+ #endif
#endif // HAS_MICROSTEPS
@@ -1664,7 +2070,7 @@
*/
#define WRITE_HEATER_0P(v) WRITE(HEATER_0_PIN, (v) ^ HEATER_0_INVERTING)
-#if HOTENDS > 1 || ENABLED(HEATERS_PARALLEL)
+#if EITHER(HAS_MULTI_HOTEND, HEATERS_PARALLEL)
#define WRITE_HEATER_1(v) WRITE(HEATER_1_PIN, (v) ^ HEATER_1_INVERTING)
#if HOTENDS > 2
#define WRITE_HEATER_2(v) WRITE(HEATER_2_PIN, (v) ^ HEATER_2_INVERTING)
@@ -1684,7 +2090,7 @@
#endif // HOTENDS > 4
#endif // HOTENDS > 3
#endif // HOTENDS > 2
-#endif // HOTENDS > 1
+#endif // HAS_MULTI_HOTEND || HEATERS_PARALLEL
#if ENABLED(HEATERS_PARALLEL)
#define WRITE_HEATER_0(v) { WRITE_HEATER_0P(v); WRITE_HEATER_1(v); }
#else
@@ -1724,6 +2130,24 @@
#define WRITE_HEATER_CHAMBER(v) WRITE(HEATER_CHAMBER_PIN, (v) ^ HEATER_CHAMBER_INVERTING)
#endif
+#if HAS_HOTEND || HAS_HEATED_BED || HAS_HEATED_CHAMBER
+ #define HAS_TEMPERATURE 1
+#endif
+
+#if HAS_TEMPERATURE && EITHER(HAS_LCD_MENU, DWIN_CREALITY_LCD)
+ #ifdef PREHEAT_5_LABEL
+ #define PREHEAT_COUNT 5
+ #elif defined(PREHEAT_4_LABEL)
+ #define PREHEAT_COUNT 4
+ #elif defined(PREHEAT_3_LABEL)
+ #define PREHEAT_COUNT 3
+ #elif defined(PREHEAT_2_LABEL)
+ #define PREHEAT_COUNT 2
+ #elif defined(PREHEAT_1_LABEL)
+ #define PREHEAT_COUNT 1
+ #endif
+#endif
+
/**
* Up to 3 PWM fans
*/
@@ -1752,13 +2176,16 @@
#endif
#if FAN_COUNT > 0
+ #define HAS_FAN 1
#define WRITE_FAN(n, v) WRITE(FAN##n##_PIN, (v) ^ FAN_INVERTING)
#endif
/**
* Part Cooling fan multipliexer
*/
-#define HAS_FANMUX PIN_EXISTS(FANMUX0)
+#if PIN_EXISTS(FANMUX0)
+ #define HAS_FANMUX 1
+#endif
/**
* MIN/MAX fan PWM scaling
@@ -1808,7 +2235,7 @@
* Bed Probe dependencies
*/
#if HAS_BED_PROBE
- #if ENABLED(ENDSTOPPULLUPS) && HAS_Z_MIN_PROBE_PIN
+ #if BOTH(ENDSTOPPULLUPS, HAS_Z_MIN_PROBE_PIN)
#define ENDSTOPPULLUP_ZMIN_PROBE
#endif
#ifndef Z_PROBE_OFFSET_RANGE_MIN
@@ -1877,15 +2304,19 @@
#undef NO_FAN_SLOWING_IN_PID_TUNING
#endif
-#define QUIET_PROBING (HAS_BED_PROBE && (EITHER(PROBING_HEATERS_OFF, PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0))
-#define HEATER_IDLE_HANDLER EITHER(ADVANCED_PAUSE_FEATURE, PROBING_HEATERS_OFF)
+#if HAS_BED_PROBE && (EITHER(PROBING_HEATERS_OFF, PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0)
+ #define QUIET_PROBING 1
+#endif
+#if EITHER(ADVANCED_PAUSE_FEATURE, PROBING_HEATERS_OFF)
+ #define HEATER_IDLE_HANDLER 1
+#endif
#if ENABLED(ADVANCED_PAUSE_FEATURE) && !defined(FILAMENT_CHANGE_SLOW_LOAD_LENGTH)
#define FILAMENT_CHANGE_SLOW_LOAD_LENGTH 0
#endif
-#if EXTRUDERS > 1 && !defined(TOOLCHANGE_FIL_EXTRA_PRIME)
- #define TOOLCHANGE_FIL_EXTRA_PRIME 0
+#if EXTRUDERS > 1 && !defined(TOOLCHANGE_FS_EXTRA_PRIME)
+ #define TOOLCHANGE_FS_EXTRA_PRIME 0
#endif
/**
@@ -1902,31 +2333,31 @@
* Bed Probing bounds
*/
-#ifndef MIN_PROBE_EDGE
- #define MIN_PROBE_EDGE 0
+#ifndef PROBING_MARGIN
+ #define PROBING_MARGIN 0
#endif
#if IS_KINEMATIC
- #undef MIN_PROBE_EDGE_LEFT
- #undef MIN_PROBE_EDGE_RIGHT
- #undef MIN_PROBE_EDGE_FRONT
- #undef MIN_PROBE_EDGE_BACK
- #define MIN_PROBE_EDGE_LEFT 0
- #define MIN_PROBE_EDGE_RIGHT 0
- #define MIN_PROBE_EDGE_FRONT 0
- #define MIN_PROBE_EDGE_BACK 0
+ #undef PROBING_MARGIN_LEFT
+ #undef PROBING_MARGIN_RIGHT
+ #undef PROBING_MARGIN_FRONT
+ #undef PROBING_MARGIN_BACK
+ #define PROBING_MARGIN_LEFT 0
+ #define PROBING_MARGIN_RIGHT 0
+ #define PROBING_MARGIN_FRONT 0
+ #define PROBING_MARGIN_BACK 0
#else
- #ifndef MIN_PROBE_EDGE_LEFT
- #define MIN_PROBE_EDGE_LEFT MIN_PROBE_EDGE
+ #ifndef PROBING_MARGIN_LEFT
+ #define PROBING_MARGIN_LEFT PROBING_MARGIN
#endif
- #ifndef MIN_PROBE_EDGE_RIGHT
- #define MIN_PROBE_EDGE_RIGHT MIN_PROBE_EDGE
+ #ifndef PROBING_MARGIN_RIGHT
+ #define PROBING_MARGIN_RIGHT PROBING_MARGIN
#endif
- #ifndef MIN_PROBE_EDGE_FRONT
- #define MIN_PROBE_EDGE_FRONT MIN_PROBE_EDGE
+ #ifndef PROBING_MARGIN_FRONT
+ #define PROBING_MARGIN_FRONT PROBING_MARGIN
#endif
- #ifndef MIN_PROBE_EDGE_BACK
- #define MIN_PROBE_EDGE_BACK MIN_PROBE_EDGE
+ #ifndef PROBING_MARGIN_BACK
+ #define PROBING_MARGIN_BACK PROBING_MARGIN
#endif
#endif
@@ -1992,13 +2423,24 @@
#undef MESH_MAX_Y
#endif
-#if defined(PROBE_PT_1_X) && defined(PROBE_PT_2_X) && defined(PROBE_PT_3_X) && defined(PROBE_PT_1_Y) && defined(PROBE_PT_2_Y) && defined(PROBE_PT_3_Y)
+#define _POINT_COUNT (defined(PROBE_PT_1_X) + defined(PROBE_PT_2_X) + defined(PROBE_PT_3_X) + defined(PROBE_PT_1_Y) + defined(PROBE_PT_2_Y) + defined(PROBE_PT_3_Y))
+#if _POINT_COUNT == 6
#define HAS_FIXED_3POINT 1
+#elif _POINT_COUNT > 0
+ #error "For 3-Point Leveling all XY points must be defined (or none for the defaults)."
#endif
+#undef _POINT_COUNT
/**
* Buzzer/Speaker
*/
+#if PIN_EXISTS(BEEPER) || EITHER(LCD_USE_I2C_BUZZER, PCA9632_BUZZER)
+ #define HAS_BUZZER 1
+ #if DISABLED(LCD_USE_I2C_BUZZER, PCA9632_BUZZER)
+ #define USE_BEEPER 1
+ #endif
+#endif
+
#if ENABLED(LCD_USE_I2C_BUZZER)
#ifndef LCD_FEEDBACK_FREQUENCY_HZ
#define LCD_FEEDBACK_FREQUENCY_HZ 1000
@@ -2015,6 +2457,10 @@
#endif
#endif
+#if HAS_BUZZER && LCD_FEEDBACK_FREQUENCY_DURATION_MS && LCD_FEEDBACK_FREQUENCY_HZ
+ #define HAS_CHIRP 1
+#endif
+
/**
* Make sure DOGLCD_SCK and DOGLCD_MOSI are defined.
*/
@@ -2094,7 +2540,11 @@
#endif
// Number of VFAT entries used. Each entry has 13 UTF-16 characters
-#define MAX_VFAT_ENTRIES TERN(SCROLL_LONG_FILENAMES, 5, 2)
+#if EITHER(SCROLL_LONG_FILENAMES, DWIN_CREALITY_LCD)
+ #define MAX_VFAT_ENTRIES (5)
+#else
+ #define MAX_VFAT_ENTRIES (2)
+#endif
// Nozzle park for Delta
#if BOTH(NOZZLE_PARK_FEATURE, DELTA)
@@ -2153,21 +2603,8 @@
#endif
#endif
-#if ENABLED(SDSUPPORT)
- #if SD_CONNECTION_IS(ONBOARD) && DISABLED(NO_SD_HOST_DRIVE) && !defined(ARDUINO_GRAND_CENTRAL_M4)
- //
- // The external SD card is not used. Hardware SPI is used to access the card.
- // When sharing the SD card with a PC we want the menu options to
- // mount/unmount the card and refresh it. So we disable card detect.
- //
- #undef SD_DETECT_PIN
- #define SHARED_SD_CARD
- #endif
- #if DISABLED(SHARED_SD_CARD)
- #define INIT_SDCARD_ON_BOOT
- #endif
-#endif
-
#if !NUM_SERIAL
#undef BAUD_RATE_GCODE
+#elif NUM_SERIAL > 1
+ #define HAS_MULTI_SERIAL 1
#endif
diff --git a/Marlin/src/inc/MarlinConfig.h b/Marlin/src/inc/MarlinConfig.h
index c1655015e..d1184cff5 100644
--- a/Marlin/src/inc/MarlinConfig.h
+++ b/Marlin/src/inc/MarlinConfig.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -30,6 +30,7 @@
#include "../HAL/HAL.h"
#include "../pins/pins.h"
+#include HAL_PATH(../HAL, timers.h)
#include HAL_PATH(../HAL, spi_pins.h)
#include "Conditionals_post.h"
diff --git a/Marlin/src/inc/MarlinConfigPre.h b/Marlin/src/inc/MarlinConfigPre.h
index d84f75120..1b15d4981 100644
--- a/Marlin/src/inc/MarlinConfigPre.h
+++ b/Marlin/src/inc/MarlinConfigPre.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h
index 2fd61d4be..2cba0fecf 100644
--- a/Marlin/src/inc/SanityCheck.h
+++ b/Marlin/src/inc/SanityCheck.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -262,7 +262,7 @@
#error "LCD_PIN_RESET is now LCD_RESET_PIN. Please update your pins definitions."
#elif defined(EXTRUDER_0_AUTO_FAN_PIN) || defined(EXTRUDER_1_AUTO_FAN_PIN) || defined(EXTRUDER_2_AUTO_FAN_PIN) || defined(EXTRUDER_3_AUTO_FAN_PIN)
#error "EXTRUDER_[0123]_AUTO_FAN_PIN is now E[0123]_AUTO_FAN_PIN. Please update your Configuration_adv.h."
-#elif defined(PID_FAN_SCALING) && FAN_COUNT <= 0
+#elif defined(PID_FAN_SCALING) && !HAS_FAN
#error "PID_FAN_SCALING needs at least one fan enabled."
#elif defined(min_software_endstops) || defined(max_software_endstops)
#error "(min|max)_software_endstops are now (MIN|MAX)_SOFTWARE_ENDSTOPS. Please update your configuration."
@@ -283,9 +283,9 @@
#elif defined(NEOPIXEL_RGBW_LED)
#error "NEOPIXEL_RGBW_LED is now NEOPIXEL_LED. Please update your configuration."
#elif ENABLED(DELTA) && defined(DELTA_PROBEABLE_RADIUS)
- #error "Remove DELTA_PROBEABLE_RADIUS and use MIN_PROBE_EDGE to inset the probe area instead."
+ #error "Remove DELTA_PROBEABLE_RADIUS and use PROBING_MARGIN to inset the probe area instead."
#elif ENABLED(DELTA) && defined(DELTA_CALIBRATION_RADIUS)
- #error "Remove DELTA_CALIBRATION_RADIUS and use MIN_PROBE_EDGE to inset the probe area instead."
+ #error "Remove DELTA_CALIBRATION_RADIUS and use PROBING_MARGIN to inset the probe area instead."
#elif defined(UBL_MESH_INSET)
#error "UBL_MESH_INSET is now just MESH_INSET. Please update your configuration."
#elif defined(UBL_MESH_MIN_X) || defined(UBL_MESH_MIN_Y) || defined(UBL_MESH_MAX_X) || defined(UBL_MESH_MAX_Y)
@@ -294,14 +294,24 @@
#error "ABL_PROBE_PT_[123]_[XY] is no longer required. Please remove it from Configuration.h."
#elif defined(UBL_PROBE_PT_1_X) || defined(UBL_PROBE_PT_1_Y) || defined(UBL_PROBE_PT_2_X) || defined(UBL_PROBE_PT_2_Y) || defined(UBL_PROBE_PT_3_X) || defined(UBL_PROBE_PT_3_Y)
#error "UBL_PROBE_PT_[123]_[XY] is no longer required. Please remove it from Configuration.h."
+#elif defined(MIN_PROBE_EDGE)
+ #error "MIN_PROBE_EDGE is now called PROBING_MARGIN. Please update your configuration."
+#elif defined(MIN_PROBE_EDGE_LEFT)
+ #error "MIN_PROBE_EDGE_LEFT is now called PROBING_MARGIN_LEFT. Please update your configuration."
+#elif defined(MIN_PROBE_EDGE_RIGHT)
+ #error "MIN_PROBE_EDGE_RIGHT is now called PROBING_MARGIN_RIGHT. Please update your configuration."
+#elif defined(MIN_PROBE_EDGE_FRONT)
+ #error "MIN_PROBE_EDGE_FRONT is now called PROBING_MARGIN_FRONT. Please update your configuration."
+#elif defined(MIN_PROBE_EDGE_BACK)
+ #error "MIN_PROBE_EDGE_BACK is now called PROBING_MARGIN_BACK. Please update your configuration."
#elif defined(LEFT_PROBE_BED_POSITION)
- #error "LEFT_PROBE_BED_POSITION has been replaced by MIN_PROBE_EDGE_LEFT. Please update your configuration."
+ #error "LEFT_PROBE_BED_POSITION is obsolete. Set a margin with PROBING_MARGIN or PROBING_MARGIN_LEFT instead."
#elif defined(RIGHT_PROBE_BED_POSITION)
- #error "RIGHT_PROBE_BED_POSITION has been replaced by MIN_PROBE_EDGE_RIGHT. Please update your configuration."
+ #error "RIGHT_PROBE_BED_POSITION is obsolete. Set a margin with PROBING_MARGIN or PROBING_MARGIN_RIGHT instead."
#elif defined(FRONT_PROBE_BED_POSITION)
- #error "FRONT_PROBE_BED_POSITION has been replaced by MIN_PROBE_EDGE_FRONT. Please update your configuration."
+ #error "FRONT_PROBE_BED_POSITION is obsolete. Set a margin with PROBING_MARGIN or PROBING_MARGIN_FRONT instead."
#elif defined(BACK_PROBE_BED_POSITION)
- #error "BACK_PROBE_BED_POSITION has been replaced by MIN_PROBE_EDGE_BACK. Please update your configuration."
+ #error "BACK_PROBE_BED_POSITION is obsolete. Set a margin with PROBING_MARGIN or PROBING_MARGIN_BACK instead."
#elif defined(ENABLE_MESH_EDIT_GFX_OVERLAY)
#error "ENABLE_MESH_EDIT_GFX_OVERLAY is now MESH_EDIT_GFX_OVERLAY. Please update your configuration."
#elif defined(BABYSTEP_ZPROBE_GFX_REVERSE)
@@ -355,7 +365,7 @@
#error "LEVEL_BED_CORNERS requires LEVEL_CORNERS_INSET_LFRB values. Please update your Configuration.h."
#elif defined(BEZIER_JERK_CONTROL)
#error "BEZIER_JERK_CONTROL is now S_CURVE_ACCELERATION. Please update your configuration."
-#elif DISABLED(CLASSIC_JERK) && defined(JUNCTION_DEVIATION_FACTOR)
+#elif HAS_JUNCTION_DEVIATION && defined(JUNCTION_DEVIATION_FACTOR)
#error "JUNCTION_DEVIATION_FACTOR is now JUNCTION_DEVIATION_MM. Please update your configuration."
#elif defined(JUNCTION_ACCELERATION_FACTOR)
#error "JUNCTION_ACCELERATION_FACTOR is obsolete. Delete it from Configuration_adv.h."
@@ -411,6 +421,8 @@
#error "SPINDLE_STOP_ON_DIR_CHANGE is now SPINDLE_CHANGE_DIR_STOP. Please update your Configuration_adv.h."
#elif defined(SPINDLE_LASER_ENABLE_INVERT)
#error "SPINDLE_LASER_ENABLE_INVERT is now SPINDLE_LASER_ACTIVE_HIGH. Please update your Configuration_adv.h."
+#elif defined(CUTTER_POWER_DISPLAY)
+ #error "CUTTER_POWER_DISPLAY is now CUTTER_POWER_UNIT. Please update your Configuration_adv.h."
#elif defined(CHAMBER_HEATER_PIN)
#error "CHAMBER_HEATER_PIN is now HEATER_CHAMBER_PIN. Please update your configuration and/or pins."
#elif defined(TMC_Z_CALIBRATION)
@@ -437,6 +449,10 @@
#error "POWER_SUPPLY is now obsolete. Please remove it from Configuration.h."
#elif defined(MKS_ROBIN_TFT)
#error "MKS_ROBIN_TFT is now FSMC_GRAPHICAL_TFT. Please update your configuration."
+#elif defined(TFT_LVGL_UI)
+ #error "TFT_LVGL_UI is now TFT_LVGL_UI_FSMC. Please update your configuration."
+#elif defined(SPI_GRAPHICAL_TFT)
+ #error "SPI_GRAPHICAL_TFT is now TFT_LVGL_UI_SPI. Please update your configuration."
#elif defined(SDPOWER)
#error "SDPOWER is now SDPOWER_PIN. Please update your configuration and/or pins."
#elif defined(STRING_SPLASH_LINE1) || defined(STRING_SPLASH_LINE2)
@@ -489,6 +505,42 @@
#error "Z_QUAD_ENDSTOPS is now Z_MULTI_ENDSTOPS. Please update Configuration_adv.h."
#elif defined(DUGS_UI_MOVE_DIS_OPTION)
#error "DUGS_UI_MOVE_DIS_OPTION is spelled DGUS_UI_MOVE_DIS_OPTION. Please update Configuration_adv.h."
+#elif defined(ORIG_E0_AUTO_FAN_PIN) || defined(ORIG_E1_AUTO_FAN_PIN) || defined(ORIG_E2_AUTO_FAN_PIN) || defined(ORIG_E3_AUTO_FAN_PIN) || defined(ORIG_E4_AUTO_FAN_PIN) || defined(ORIG_E5_AUTO_FAN_PIN) || defined(ORIG_E6_AUTO_FAN_PIN) || defined(ORIG_E7_AUTO_FAN_PIN)
+ #error "ORIG_Ex_AUTO_FAN_PIN is now just Ex_AUTO_FAN_PIN. Make sure your pins are up to date."
+#elif defined(ORIG_CHAMBER_AUTO_FAN_PIN)
+ #error "ORIG_CHAMBER_AUTO_FAN_PIN is now just CHAMBER_AUTO_FAN_PIN. Make sure your pins are up to date."
+#elif defined(HOMING_BACKOFF_MM)
+ #error "HOMING_BACKOFF_MM is now HOMING_BACKOFF_POST_MM. Please update Configuration_adv.h."
+#elif defined(X_HOME_BUMP_MM) || defined(Y_HOME_BUMP_MM) || defined(Z_HOME_BUMP_MM)
+ #error "[XYZ]_HOME_BUMP_MM is now HOMING_BUMP_MM. Please update Configuration_adv.h."
+#elif defined(DIGIPOT_I2C)
+ #error "DIGIPOT_I2C is now DIGIPOT_MCP4451 (or DIGIPOT_MCP4018). Please update Configuration_adv.h."
+#endif
+
+#ifdef FIL_RUNOUT_INVERTING
+ #if FIL_RUNOUT_INVERTING
+ #warning "FIL_RUNOUT_INVERTING true is now FIL_RUNOUT_STATE HIGH. Please update Configuration.h."
+ #else
+ #warning "FIL_RUNOUT_INVERTING false is now FIL_RUNOUT_STATE LOW. Please update Configuration.h."
+ #endif
+ #ifndef FIL_RUNOUT_STATE
+ #define FIL_RUNOUT_STATE ((FIL_RUNOUT_INVERTING) ? HIGH : LOW)
+ #endif
+#endif
+
+/**
+ * Probe temp compensation requirements
+ */
+#if ENABLED(PROBE_TEMP_COMPENSATION)
+ #if defined(PTC_PARK_POS_X) || defined(PTC_PARK_POS_Y) || defined(PTC_PARK_POS_Z)
+ #error "PTC_PARK_POS_[XYZ] is now PTC_PARK_POS (array). Please update Configuration_adv.h."
+ #elif !defined(PTC_PARK_POS)
+ #error "PROBE_TEMP_COMPENSATION requires PTC_PARK_POS."
+ #elif defined(PTC_PROBE_POS_X) || defined(PTC_PROBE_POS_Y)
+ #error "PTC_PROBE_POS_[XY] is now PTC_PROBE_POS (array). Please update Configuration_adv.h."
+ #elif !defined(PTC_PROBE_POS)
+ #error "PROBE_TEMP_COMPENSATION requires PTC_PROBE_POS."
+ #endif
#endif
/**
@@ -637,7 +689,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#elif PROGRESS_MSG_EXPIRE < 0
#error "PROGRESS_MSG_EXPIRE must be greater than or equal to 0."
#endif
-#elif ENABLED(LCD_SET_PROGRESS_MANUALLY) && !HAS_GRAPHICAL_LCD && DISABLED(EXTENSIBLE_UI)
+#elif ENABLED(LCD_SET_PROGRESS_MANUALLY) && NONE(HAS_GRAPHICAL_LCD, EXTENSIBLE_UI)
#error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Graphical LCD, or EXTENSIBLE_UI."
#endif
@@ -648,7 +700,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
/**
* Custom Boot and Status screens
*/
-#if ENABLED(SHOW_CUSTOM_BOOTSCREEN) && !(HAS_GRAPHICAL_LCD || ENABLED(TOUCH_UI_FTDI_EVE))
+#if ENABLED(SHOW_CUSTOM_BOOTSCREEN) && NONE(HAS_GRAPHICAL_LCD, TOUCH_UI_FTDI_EVE)
#error "SHOW_CUSTOM_BOOTSCREEN requires Graphical LCD or TOUCH_UI_FTDI_EVE."
#elif ENABLED(CUSTOM_STATUS_SCREEN_IMAGE) && !HAS_GRAPHICAL_LCD
#error "CUSTOM_STATUS_SCREEN_IMAGE requires a Graphical LCD."
@@ -723,6 +775,15 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#error "BABYSTEP_HOTEND_Z_OFFSET requires 2 or more HOTENDS."
#elif BOTH(BABYSTEP_ALWAYS_AVAILABLE, MOVE_Z_WHEN_IDLE)
#error "BABYSTEP_ALWAYS_AVAILABLE and MOVE_Z_WHEN_IDLE are incompatible."
+ #elif !defined(BABYSTEP_MULTIPLICATOR_Z)
+ #error "BABYSTEPPING requires BABYSTEP_MULTIPLICATOR_Z."
+ #elif ENABLED(BABYSTEP_XY) && !defined(BABYSTEP_MULTIPLICATOR_XY)
+ #error "BABYSTEP_XY requires BABYSTEP_MULTIPLICATOR_XY."
+ #elif ENABLED(BABYSTEP_MILLIMETER_UNITS)
+ static_assert(BABYSTEP_MULTIPLICATOR_Z <= 0.1f, "BABYSTEP_MULTIPLICATOR_Z must be less or equal to 0.1mm.");
+ #if ENABLED(BABYSTEP_XY)
+ static_assert(BABYSTEP_MULTIPLICATOR_XY <= 0.25f, "BABYSTEP_MULTIPLICATOR_XY must be less than or equal to 0.25mm.");
+ #endif
#endif
#endif
@@ -781,6 +842,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#if ENABLED(NOZZLE_PARK_FEATURE)
constexpr float npp[] = NOZZLE_PARK_POINT;
static_assert(COUNT(npp) == XYZ, "NOZZLE_PARK_POINT requires X, Y, and Z values.");
+ constexpr xyz_pos_t npp_xyz = NOZZLE_PARK_POINT;
+ static_assert(WITHIN(npp_xyz.x, X_MIN_POS, X_MAX_POS), "NOZZLE_PARK_POINT.X is out of bounds (X_MIN_POS, X_MAX_POS).");
+ static_assert(WITHIN(npp_xyz.y, Y_MIN_POS, Y_MAX_POS), "NOZZLE_PARK_POINT.Y is out of bounds (Y_MIN_POS, Y_MAX_POS).");
+ static_assert(WITHIN(npp_xyz.z, Z_MIN_POS, Z_MAX_POS), "NOZZLE_PARK_POINT.Z is out of bounds (Z_MIN_POS, Z_MAX_POS).");
#endif
/**
@@ -804,14 +869,15 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#endif
#if ENABLED(TOOLCHANGE_FILAMENT_SWAP)
- #ifndef TOOLCHANGE_FIL_SWAP_LENGTH
- #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FIL_SWAP_LENGTH. Please update your Configuration."
- #elif !defined(TOOLCHANGE_FIL_SWAP_RETRACT_SPEED)
- #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FIL_SWAP_RETRACT_SPEED. Please update your Configuration."
- #elif !defined(TOOLCHANGE_FIL_SWAP_PRIME_SPEED)
- #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FIL_SWAP_PRIME_SPEED. Please update your Configuration."
+ #ifndef TOOLCHANGE_FS_LENGTH
+ #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FS_LENGTH. Please update your Configuration_adv.h."
+ #elif !defined(TOOLCHANGE_FS_RETRACT_SPEED)
+ #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FS_RETRACT_SPEED. Please update your Configuration_adv.h."
+ #elif !defined(TOOLCHANGE_FS_PRIME_SPEED)
+ #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FS_PRIME_SPEED. Please update your Configuration_adv.h."
#endif
#endif
+
#if ENABLED(TOOLCHANGE_PARK)
#ifndef TOOLCHANGE_PARK_XY
#error "TOOLCHANGE_PARK requires TOOLCHANGE_PARK_XY. Please update your Configuration."
@@ -935,6 +1001,9 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
WITHIN(LIN_ADVANCE_K, 0, 10),
"LIN_ADVANCE_K must be a value from 0 to 10 (Changed in LIN_ADVANCE v1.5, Marlin 1.1.9)."
);
+ #if ENABLED(S_CURVE_ACCELERATION) && DISABLED(EXPERIMENTAL_SCURVE)
+ #error "LIN_ADVANCE and S_CURVE_ACCELERATION may not play well together! Enable EXPERIMENTAL_SCURVE to continue."
+ #endif
#endif
/**
@@ -1104,7 +1173,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
/**
* Junction deviation is incompatible with kinematic systems.
*/
-#if DISABLED(CLASSIC_JERK) && IS_KINEMATIC
+#if HAS_JUNCTION_DEVIATION && IS_KINEMATIC
#error "CLASSIC_JERK is required for DELTA and SCARA."
#endif
@@ -1120,7 +1189,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
+ ENABLED(FIX_MOUNTED_PROBE) \
+ ENABLED(NOZZLE_AS_PROBE) \
+ (HAS_Z_SERVO_PROBE && DISABLED(BLTOUCH)) \
- + ENABLED(BLTOUCH) \
+ + ENABLED(BLTOUCH) && DISABLED(CREALITY_TOUCH) \
+ + ENABLED(CREALITY_TOUCH) \
+ ENABLED(TOUCH_MI_PROBE) \
+ ENABLED(SOLENOID_PROBE) \
+ ENABLED(Z_PROBE_ALLEN_KEY) \
@@ -1230,13 +1300,21 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#endif
#if DISABLED(NOZZLE_AS_PROBE)
- static_assert(MIN_PROBE_EDGE >= 0, "MIN_PROBE_EDGE must be >= 0.");
- static_assert(MIN_PROBE_EDGE_BACK >= 0, "MIN_PROBE_EDGE_BACK must be >= 0.");
- static_assert(MIN_PROBE_EDGE_FRONT >= 0, "MIN_PROBE_EDGE_FRONT must be >= 0.");
- static_assert(MIN_PROBE_EDGE_LEFT >= 0, "MIN_PROBE_EDGE_LEFT must be >= 0.");
- static_assert(MIN_PROBE_EDGE_RIGHT >= 0, "MIN_PROBE_EDGE_RIGHT must be >= 0.");
+ static_assert(PROBING_MARGIN >= 0, "PROBING_MARGIN must be >= 0.");
+ static_assert(PROBING_MARGIN_BACK >= 0, "PROBING_MARGIN_BACK must be >= 0.");
+ static_assert(PROBING_MARGIN_FRONT >= 0, "PROBING_MARGIN_FRONT must be >= 0.");
+ static_assert(PROBING_MARGIN_LEFT >= 0, "PROBING_MARGIN_LEFT must be >= 0.");
+ static_assert(PROBING_MARGIN_RIGHT >= 0, "PROBING_MARGIN_RIGHT must be >= 0.");
#endif
+ #define _MARGIN(A) TERN(IS_SCARA, SCARA_PRINTABLE_RADIUS, TERN(DELTA, DELTA_PRINTABLE_RADIUS, A##_CENTER))
+ static_assert(PROBING_MARGIN < _MARGIN(X), "PROBING_MARGIN is too large.");
+ static_assert(PROBING_MARGIN_BACK < _MARGIN(Y), "PROBING_MARGIN_BACK is too large.");
+ static_assert(PROBING_MARGIN_FRONT < _MARGIN(Y), "PROBING_MARGIN_FRONT is too large.");
+ static_assert(PROBING_MARGIN_LEFT < _MARGIN(X), "PROBING_MARGIN_LEFT is too large.");
+ static_assert(PROBING_MARGIN_RIGHT < _MARGIN(X), "PROBING_MARGIN_RIGHT is too large.");
+ #undef _MARGIN
+
/**
* Make sure Z raise values are set
*/
@@ -1252,8 +1330,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#error "Probes need Z_AFTER_PROBING >= 0."
#endif
- #if MULTIPLE_PROBING || EXTRA_PROBING
- #if !MULTIPLE_PROBING
+ #if MULTIPLE_PROBING > 0 || EXTRA_PROBING > 0
+ #if MULTIPLE_PROBING == 0
#error "EXTRA_PROBING requires MULTIPLE_PROBING."
#elif MULTIPLE_PROBING < 2
#error "MULTIPLE_PROBING must be 2 or more."
@@ -1350,15 +1428,19 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#endif
-#if HAS_MESH
- #if HAS_CLASSIC_JERK
- static_assert(DEFAULT_ZJERK > 0.1, "Low DEFAULT_ZJERK values are incompatible with mesh-based leveling.");
- #endif
-#elif ENABLED(G26_MESH_VALIDATION)
- #error "G26_MESH_VALIDATION requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_UBL."
+#if HAS_MESH && HAS_CLASSIC_JERK
+ static_assert(DEFAULT_ZJERK > 0.1, "Low DEFAULT_ZJERK values are incompatible with mesh-based leveling.");
#endif
-#if ENABLED(MESH_EDIT_GFX_OVERLAY) && !(ENABLED(AUTO_BED_LEVELING_UBL) && HAS_GRAPHICAL_LCD)
+#if ENABLED(G26_MESH_VALIDATION)
+ #if !EXTRUDERS
+ #error "G26_MESH_VALIDATION requires at least one extruder."
+ #elif !HAS_MESH
+ #error "G26_MESH_VALIDATION requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_UBL."
+ #endif
+#endif
+
+#if ENABLED(MESH_EDIT_GFX_OVERLAY) && !BOTH(AUTO_BED_LEVELING_UBL, HAS_GRAPHICAL_LCD)
#error "MESH_EDIT_GFX_OVERLAY requires AUTO_BED_LEVELING_UBL and a Graphical LCD."
#endif
@@ -1384,9 +1466,11 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
/**
* Homing
*/
-#if X_HOME_BUMP_MM < 0 || Y_HOME_BUMP_MM < 0 || Z_HOME_BUMP_MM < 0
- #error "[XYZ]_HOME_BUMP_MM must be greater than or equal to 0."
-#endif
+constexpr float hbm[] = HOMING_BUMP_MM;
+static_assert(COUNT(hbm) == XYZ, "HOMING_BUMP_MM requires X, Y, and Z elements.");
+static_assert(hbm[X_AXIS] >= 0, "HOMING_BUMP_MM.X must be greater than or equal to 0.");
+static_assert(hbm[Y_AXIS] >= 0, "HOMING_BUMP_MM.Y must be greater than or equal to 0.");
+static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal to 0.");
#if ENABLED(CODEPENDENT_XY_HOMING)
#if ENABLED(QUICK_HOME)
@@ -1424,6 +1508,28 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#endif
#endif
+/**
+ * System Power Sensor
+ */
+#if ENABLED(POWER_MONITOR_CURRENT) && !PIN_EXISTS(POWER_MONITOR_CURRENT)
+ #error "POWER_MONITOR_CURRENT requires a valid POWER_MONITOR_CURRENT_PIN."
+#elif ENABLED(POWER_MONITOR_VOLTAGE) && !PIN_EXISTS(POWER_MONITOR_VOLTAGE)
+ #error "POWER_MONITOR_VOLTAGE requires POWER_MONITOR_VOLTAGE_PIN to be defined."
+#elif BOTH(POWER_MONITOR_CURRENT, POWER_MONITOR_VOLTAGE) && POWER_MONITOR_CURRENT_PIN == POWER_MONITOR_VOLTAGE_PIN
+ #error "POWER_MONITOR_CURRENT_PIN and POWER_MONITOR_VOLTAGE_PIN must be different."
+#endif
+
+/**
+ * Volumetric Extruder Limit
+ */
+#if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT)
+ #if ENABLED(NO_VOLUMETRICS)
+ #error "VOLUMETRIC_EXTRUDER_LIMIT requires NO_VOLUMETRICS to be disabled."
+ #elif MIN_STEPS_PER_SEGMENT > 1
+ #error "VOLUMETRIC_EXTRUDER_LIMIT is not compatible with MIN_STEPS_PER_SEGMENT greater than 1."
+ #endif
+#endif
+
/**
* ULTIPANEL encoder
*/
@@ -1451,7 +1557,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
* Deploying the Allen Key probe uses big moves in z direction. Too dangerous for an unhomed z-axis.
*/
#if ENABLED(Z_PROBE_ALLEN_KEY) && (Z_HOME_DIR < 0) && ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
- #error "You can't home to a z min endstop with a Z_PROBE_ALLEN_KEY"
+ #error "You can't home to a z min endstop with a Z_PROBE_ALLEN_KEY."
#endif
/**
@@ -1547,28 +1653,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#endif
/**
- * Test Heater, Temp Sensor, and Extruder Pins; Sensor Type must also be set.
+ * A Sensor ID has to be set for each heater
*/
-#if !HAS_HEATER_0
- #error "HEATER_0_PIN not defined for this board."
-#elif !ANY_PIN(TEMP_0, MAX6675_SS)
- #error "TEMP_0_PIN not defined for this board."
-#elif ((defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && !PINS_EXIST(E0_STEP, E0_DIR))
- #error "E0_STEP_PIN or E0_DIR_PIN not defined for this board."
-#elif ( !(defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && (!PINS_EXIST(E0_STEP, E0_DIR) || !HAS_E0_ENABLE))
- #error "E0_STEP_PIN, E0_DIR_PIN, or E0_ENABLE_PIN not defined for this board."
-#elif EXTRUDERS && TEMP_SENSOR_0 == 0
- #error "TEMP_SENSOR_0 is required with any extruders."
-#endif
-// Pins are required for heaters
-#if ENABLED(HEATER_0_USES_MAX6675) && !PIN_EXISTS(MAX6675_SS)
- #error "MAX6675_SS_PIN (required for TEMP_SENSOR_0) not defined for this board."
-#elif (HOTENDS > 1 || ENABLED(HEATERS_PARALLEL)) && !HAS_HEATER_1
- #error "HEATER_1_PIN not defined for this board."
-#endif
-
-#if HOTENDS > 1
+#if HAS_MULTI_HOTEND
#if ENABLED(HEATER_1_USES_MAX6675) && !PIN_EXISTS(MAX6675_SS2)
#error "MAX6675_SS2_PIN (required for TEMP_SENSOR_1) not defined for this board."
#elif TEMP_SENSOR_1 == 0
@@ -1690,9 +1778,13 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#error "TEMP_SENSOR_7 shouldn't be set with only 1 HOTEND."
#endif
+#if TEMP_SENSOR_CHAMBER && !PIN_EXISTS(TEMP_CHAMBER)
+ #error "TEMP_SENSOR_CHAMBER requires TEMP_CHAMBER_PIN. Please add it to your configuration."
+#endif
+
#if TEMP_SENSOR_PROBE
#if !PIN_EXISTS(TEMP_PROBE)
- #error "TEMP_SENSOR_PROBE requires TEMP_PROBE_PIN."
+ #error "TEMP_SENSOR_PROBE requires TEMP_PROBE_PIN. Please add it to your configuration."
#elif !HAS_TEMP_ADC_PROBE
#error "TEMP_PROBE_PIN must be an ADC pin."
#elif !ENABLED(FIX_MOUNTED_PROBE)
@@ -1704,6 +1796,30 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#error "TEMP_SENSOR_1 is required with TEMP_SENSOR_1_AS_REDUNDANT."
#endif
+/**
+ * Test Heater, Temp Sensor, and Extruder Pins
+ */
+#if !HAS_HEATER_0
+ #error "HEATER_0_PIN not defined for this board."
+#elif !ANY_PIN(TEMP_0, MAX6675_SS)
+ #error "TEMP_0_PIN not defined for this board."
+#elif ((defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && !PINS_EXIST(E0_STEP, E0_DIR))
+ #error "E0_STEP_PIN or E0_DIR_PIN not defined for this board."
+#elif ( !(defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && (!PINS_EXIST(E0_STEP, E0_DIR) || !HAS_E0_ENABLE))
+ #error "E0_STEP_PIN, E0_DIR_PIN, or E0_ENABLE_PIN not defined for this board."
+#elif EXTRUDERS && TEMP_SENSOR_0 == 0
+ #error "TEMP_SENSOR_0 is required if there are any extruders."
+#endif
+
+// Pins are required for heaters
+#if ENABLED(HEATER_0_USES_MAX6675) && !PIN_EXISTS(MAX6675_SS)
+ #error "MAX6675_SS_PIN (required for TEMP_SENSOR_0) not defined for this board."
+#elif HAS_HOTEND && !HAS_TEMP_HOTEND
+ #error "TEMP_0_PIN (required for TEMP_SENSOR_0) not defined for this board."
+#elif EITHER(HAS_MULTI_HOTEND, HEATERS_PARALLEL) && !HAS_HEATER_1
+ #error "HEATER_1_PIN is not defined. TEMP_SENSOR_1 might not be set, or the board (not EEB / EEF?) doesn't define a pin."
+#endif
+
/**
* Temperature status LEDs
*/
@@ -1792,8 +1908,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
* Endstop Tests
*/
-#define _PLUG_UNUSED_TEST(AXIS,PLUG) (DISABLED(USE_##PLUG##MIN_PLUG, USE_##PLUG##MAX_PLUG) && !(ENABLED(AXIS##_DUAL_ENDSTOPS) && WITHIN(AXIS##2_USE_ENDSTOP, _##PLUG##MAX_, _##PLUG##MIN_)))
-#define _AXIS_PLUG_UNUSED_TEST(AXIS) (_PLUG_UNUSED_TEST(AXIS,X) && _PLUG_UNUSED_TEST(AXIS,Y) && _PLUG_UNUSED_TEST(AXIS,Z))
+#define _PLUG_UNUSED_TEST(A,P) (DISABLED(USE_##P##MIN_PLUG, USE_##P##MAX_PLUG) \
+ && !(ENABLED(A##_DUAL_ENDSTOPS) && WITHIN(A##2_USE_ENDSTOP, _##P##MAX_, _##P##MIN_)) \
+ && !(ENABLED(A##_MULTI_ENDSTOPS) && WITHIN(A##2_USE_ENDSTOP, _##P##MAX_, _##P##MIN_)) )
+#define _AXIS_PLUG_UNUSED_TEST(A) (_PLUG_UNUSED_TEST(A,X) && _PLUG_UNUSED_TEST(A,Y) && _PLUG_UNUSED_TEST(A,Z))
// At least 3 endstop plugs must be used
#if _AXIS_PLUG_UNUSED_TEST(X)
@@ -1818,8 +1936,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#error "Enable USE_YMAX_PLUG when homing Y to MAX."
#endif
#endif
-#if Z_HOME_DIR < 0 && DISABLED(USE_ZMIN_PLUG)
+
+// Z homing direction and plug usage flags
+#if Z_HOME_DIR < 0 && NONE(USE_ZMIN_PLUG, HOMING_Z_WITH_PROBE)
#error "Enable USE_ZMIN_PLUG when homing Z to MIN."
+#elif Z_HOME_DIR > 0 && ENABLED(USE_PROBE_FOR_Z_HOMING)
+ #error "Z_HOME_DIR must be -1 when homing Z with the probe."
#elif Z_HOME_DIR > 0 && DISABLED(USE_ZMAX_PLUG)
#error "Enable USE_ZMAX_PLUG when homing Z to MAX."
#endif
@@ -1984,35 +2106,64 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#endif
#undef _RGB_TEST
+#if DISABLED(NO_COMPILE_TIME_PWM)
+ #define _TEST_PWM(P) PWM_PIN(P)
+#else
+ #define _TEST_PWM(P) 1 // pass
+#endif
+
/**
* Auto Fan check for PWM pins
*/
-#if HAS_AUTO_FAN && EXTRUDER_AUTO_FAN_SPEED != 255 && DISABLED(NO_COMPILE_TIME_PWM)
+#if HAS_AUTO_FAN && EXTRUDER_AUTO_FAN_SPEED != 255
#define AF_ERR_SUFF "_AUTO_FAN_PIN is not a PWM pin. Set EXTRUDER_AUTO_FAN_SPEED to 255."
#if HAS_AUTO_FAN_0
- static_assert(PWM_PIN(E0_AUTO_FAN_PIN), "E0" AF_ERR_SUFF);
+ static_assert(_TEST_PWM(E0_AUTO_FAN_PIN), "E0" AF_ERR_SUFF);
#elif HAS_AUTO_FAN_1
- static_assert(PWM_PIN(E1_AUTO_FAN_PIN), "E1" AF_ERR_SUFF);
+ static_assert(_TEST_PWM(E1_AUTO_FAN_PIN), "E1" AF_ERR_SUFF);
#elif HAS_AUTO_FAN_2
- static_assert(PWM_PIN(E2_AUTO_FAN_PIN), "E2" AF_ERR_SUFF);
+ static_assert(_TEST_PWM(E2_AUTO_FAN_PIN), "E2" AF_ERR_SUFF);
#elif HAS_AUTO_FAN_3
- static_assert(PWM_PIN(E3_AUTO_FAN_PIN), "E3" AF_ERR_SUFF);
+ static_assert(_TEST_PWM(E3_AUTO_FAN_PIN), "E3" AF_ERR_SUFF);
#elif HAS_AUTO_FAN_4
- static_assert(PWM_PIN(E4_AUTO_FAN_PIN), "E4" AF_ERR_SUFF);
+ static_assert(_TEST_PWM(E4_AUTO_FAN_PIN), "E4" AF_ERR_SUFF);
#elif HAS_AUTO_FAN_5
- static_assert(PWM_PIN(E5_AUTO_FAN_PIN), "E5" AF_ERR_SUFF);
+ static_assert(_TEST_PWM(E5_AUTO_FAN_PIN), "E5" AF_ERR_SUFF);
#elif HAS_AUTO_FAN_6
- static_assert(PWM_PIN(E6_AUTO_FAN_PIN), "E6" AF_ERR_SUFF);
+ static_assert(_TEST_PWM(E6_AUTO_FAN_PIN), "E6" AF_ERR_SUFF);
#elif HAS_AUTO_FAN_7
- static_assert(PWM_PIN(E7_AUTO_FAN_PIN), "E7" AF_ERR_SUFF);
+ static_assert(_TEST_PWM(E7_AUTO_FAN_PIN), "E7" AF_ERR_SUFF);
#endif
#endif
/**
* Make sure only one EEPROM type is enabled
*/
-#if ENABLED(EEPROM_SETTINGS) && 1 < ENABLED(SDCARD_EEPROM_EMULATION) + ENABLED(FLASH_EEPROM_EMULATION) + ENABLED(SRAM_EEPROM_EMULATION)
- #error "Please select only one of SDCARD, FLASH, or SRAM_EEPROM_EMULATION."
+#if ENABLED(EEPROM_SETTINGS)
+ #if 1 < 0 \
+ + ENABLED(I2C_EEPROM) \
+ + ENABLED(SPI_EEPROM) \
+ + ENABLED(QSPI_EEPROM) \
+ + ENABLED(SDCARD_EEPROM_EMULATION) \
+ + ENABLED(FLASH_EEPROM_EMULATION) \
+ + ENABLED(SRAM_EEPROM_EMULATION) \
+ + ENABLED(IIC_BL24CXX_EEPROM)
+ #error "Please select only one method of EEPROM Persistent Storage."
+ #endif
+#endif
+
+/**
+ * Make sure features that need to write to the SD card are
+ * disabled unless write support is enabled.
+ */
+#if ENABLED(SDCARD_READONLY)
+ #if ENABLED(POWER_LOSS_RECOVERY)
+ #error "POWER_LOSS_RECOVERY is incompatible with SDCARD_READONLY."
+ #elif ENABLED(BINARY_FILE_TRANSFER)
+ #error "BINARY_FILE_TRANSFER is incompatible with SDCARD_READONLY."
+ #elif ENABLED(SDCARD_EEPROM_EMULATION)
+ #error "SDCARD_EEPROM_EMULATION is incompatible with SDCARD_READONLY."
+ #endif
#endif
/**
@@ -2024,6 +2175,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
+ (ENABLED(ULTRA_LCD) && DISABLED(IS_ULTRA_LCD)) \
+ (ENABLED(U8GLIB_SSD1306) && DISABLED(IS_U8GLIB_SSD1306)) \
+ (ENABLED(MINIPANEL) && DISABLED(MKS_MINI_12864, ENDER2_STOCKDISPLAY)) \
+ + (ENABLED(MKS_MINI_12864) && DISABLED(MKS_LCD12864)) \
+ (ENABLED(EXTENSIBLE_UI) && DISABLED(IS_EXTUI)) \
+ (ENABLED(ULTIPANEL) && DISABLED(IS_ULTIPANEL)) \
+ ENABLED(RADDS_DISPLAY) \
@@ -2050,7 +2202,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
+ ENABLED(CARTESIO_UI) \
+ ENABLED(LCD_FOR_MELZI) \
+ ENABLED(ULTI_CONTROLLER) \
- + ENABLED(MKS_MINI_12864) \
+ + ENABLED(MKS_LCD12864) \
+ ENABLED(ENDER2_STOCKDISPLAY) \
+ ENABLED(FYSETC_MINI_12864_X_X) \
+ ENABLED(FYSETC_MINI_12864_1_2) \
@@ -2058,6 +2210,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
+ ENABLED(FYSETC_MINI_12864_2_1) \
+ ENABLED(FYSETC_GENERIC_12864_1_1) \
+ ENABLED(CR10_STOCKDISPLAY) \
+ + ENABLED(DWIN_CREALITY_LCD) \
+ ENABLED(ANET_FULL_GRAPHICS_LCD) \
+ ENABLED(AZSMZ_12864) \
+ ENABLED(SILVER_GATE_GLCD_CONTROLLER) \
@@ -2067,12 +2220,15 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
+ ENABLED(MKS_12864OLED_SSD1306) \
+ ENABLED(U8GLIB_SH1106_EINSTART) \
+ ENABLED(OVERLORD_OLED) \
+ + ENABLED(FYSETC_242_OLED_12864) \
+ ENABLED(DGUS_LCD_UI_ORIGIN) \
+ ENABLED(DGUS_LCD_UI_FYSETC) \
+ ENABLED(DGUS_LCD_UI_HIPRECY) \
+ ENABLED(MALYAN_LCD) \
+ ENABLED(TOUCH_UI_FTDI_EVE) \
- + ENABLED(FSMC_GRAPHICAL_TFT)
+ + ENABLED(FSMC_GRAPHICAL_TFT) \
+ + ENABLED(TFT_LVGL_UI_FSMC) \
+ + ENABLED(TFT_LVGL_UI_SPI)
#error "Please select no more than one LCD controller option."
#endif
@@ -2084,6 +2240,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#undef IS_EXTUI
#undef IS_ULTIPANEL
+#if 1 < ENABLED(LCD_SCREEN_ROT_0) + ENABLED(LCD_SCREEN_ROT_90) + ENABLED(LCD_SCREEN_ROT_180) + ENABLED(LCD_SCREEN_ROT_270)
+ #error "Please enable only one LCD_SCREEN_ROT_* option: 0, 90, 180, or 270."
+#endif
+
/**
* FYSETC Mini 12864 RGB backlighting required
*/
@@ -2414,10 +2574,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
/**
* Digipot requirement
*/
-#if ENABLED(DIGIPOT_MCP4018)
- #if !defined(DIGIPOTS_I2C_SDA_X) || !defined(DIGIPOTS_I2C_SDA_Y) || !defined(DIGIPOTS_I2C_SDA_Z) \
- || !defined(DIGIPOTS_I2C_SDA_E0) || !defined(DIGIPOTS_I2C_SDA_E1)
- #error "DIGIPOT_MCP4018 requires DIGIPOTS_I2C_SDA_* pins to be defined."
+#if HAS_I2C_DIGIPOT
+ #if BOTH(DIGIPOT_MCP4018, DIGIPOT_MCP4451)
+ #error "Enable only one of DIGIPOT_MCP4018 or DIGIPOT_MCP4451."
+ #elif !MB(MKS_SBASE) \
+ && (!defined(DIGIPOTS_I2C_SDA_X) || !defined(DIGIPOTS_I2C_SDA_Y) || !defined(DIGIPOTS_I2C_SDA_Z) || !defined(DIGIPOTS_I2C_SDA_E0) || !defined(DIGIPOTS_I2C_SDA_E1))
+ #error "DIGIPOT_MCP4018/4451 requires DIGIPOTS_I2C_SDA_* pins to be defined."
#endif
#endif
@@ -2654,9 +2816,9 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
#if ENABLED(BACKLASH_COMPENSATION)
#ifndef BACKLASH_DISTANCE_MM
- #error "BACKLASH_COMPENSATION requires BACKLASH_DISTANCE_MM"
+ #error "BACKLASH_COMPENSATION requires BACKLASH_DISTANCE_MM."
#elif !defined(BACKLASH_CORRECTION)
- #error "BACKLASH_COMPENSATION requires BACKLASH_CORRECTION"
+ #error "BACKLASH_COMPENSATION requires BACKLASH_CORRECTION."
#elif IS_CORE
constexpr float backlash_arr[] = BACKLASH_DISTANCE_MM;
static_assert(!backlash_arr[CORE_AXIS_1] && !backlash_arr[CORE_AXIS_2],
@@ -2689,10 +2851,14 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
* Prusa MMU2 requirements
*/
#if ENABLED(PRUSA_MMU2)
- #if DISABLED(NOZZLE_PARK_FEATURE)
- #error "PRUSA_MMU2 requires NOZZLE_PARK_FEATURE."
- #elif EXTRUDERS != 5
+ #if EXTRUDERS != 5
#error "PRUSA_MMU2 requires EXTRUDERS = 5."
+ #elif DISABLED(NOZZLE_PARK_FEATURE)
+ #error "PRUSA_MMU2 requires NOZZLE_PARK_FEATURE. Enable it to continue."
+ #elif EITHER(PRUSA_MMU2_S_MODE, MMU_EXTRUDER_SENSOR) && DISABLED(FILAMENT_RUNOUT_SENSOR)
+ #error "PRUSA_MMU2_S_MODE or MMU_EXTRUDER_SENSOR requires FILAMENT_RUNOUT_SENSOR. Enable it to continue."
+ #elif BOTH(PRUSA_MMU2_S_MODE, MMU_EXTRUDER_SENSOR)
+ #error "Enable only one of PRUSA_MMU2_S_MODE or MMU_EXTRUDER_SENSOR."
#elif DISABLED(ADVANCED_PAUSE_FEATURE)
static_assert(nullptr == strstr(MMU2_FILAMENT_RUNOUT_SCRIPT, "M600"), "ADVANCED_PAUSE_FEATURE is required to use M600 with PRUSA_MMU2.");
#endif
@@ -2736,6 +2902,45 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
#endif
#if HAS_CUTTER
+ #ifndef CUTTER_POWER_UNIT
+ #error "CUTTER_POWER_UNIT is required with a spindle or laser. Please update your Configuration_adv.h."
+ #elif !CUTTER_UNIT_IS(PWM255) && !CUTTER_UNIT_IS(PERCENT) && !CUTTER_UNIT_IS(RPM)
+ #error "CUTTER_POWER_UNIT must be PWM255, PERCENT, or RPM. Please update your Configuration_adv.h."
+ #endif
+
+ #if ENABLED(LASER_POWER_INLINE)
+ #if ENABLED(SPINDLE_CHANGE_DIR)
+ #error "SPINDLE_CHANGE_DIR and LASER_POWER_INLINE are incompatible."
+ #elif ENABLED(LASER_MOVE_G0_OFF) && DISABLED(LASER_MOVE_POWER)
+ #error "LASER_MOVE_G0_OFF requires LASER_MOVE_POWER. Please update your Configuration_adv.h."
+ #endif
+ #if ENABLED(LASER_POWER_INLINE_TRAPEZOID)
+ #if DISABLED(SPINDLE_LASER_PWM)
+ #error "LASER_POWER_INLINE_TRAPEZOID requires SPINDLE_LASER_PWM to function."
+ #elif ENABLED(S_CURVE_ACCELERATION)
+ //#ifndef LASER_POWER_INLINE_S_CURVE_ACCELERATION_WARN
+ // #define LASER_POWER_INLINE_S_CURVE_ACCELERATION_WARN
+ // #warning "Combining LASER_POWER_INLINE_TRAPEZOID with S_CURVE_ACCELERATION may result in unintended behavior."
+ //#endif
+ #endif
+ #endif
+ #if ENABLED(LASER_POWER_INLINE_INVERT)
+ //#ifndef LASER_POWER_INLINE_INVERT_WARN
+ // #define LASER_POWER_INLINE_INVERT_WARN
+ // #warning "Enabling LASER_POWER_INLINE_INVERT means that `M5` won't kill the laser immediately; use `M5 I` instead."
+ //#endif
+ #endif
+ #else
+ #if SPINDLE_LASER_POWERUP_DELAY < 1
+ #error "SPINDLE_LASER_POWERUP_DELAY must be greater than 0."
+ #elif SPINDLE_LASER_POWERDOWN_DELAY < 1
+ #error "SPINDLE_LASER_POWERDOWN_DELAY must be greater than 0."
+ #elif ENABLED(LASER_MOVE_POWER)
+ #error "LASER_MOVE_POWER requires LASER_POWER_INLINE."
+ #elif ANY(LASER_POWER_INLINE_TRAPEZOID, LASER_POWER_INLINE_INVERT, LASER_MOVE_G0_OFF, LASER_MOVE_POWER)
+ #error "Enabled an inline laser feature without inline laser power being enabled."
+ #endif
+ #endif
#define _PIN_CONFLICT(P) (PIN_EXISTS(P) && P##_PIN == SPINDLE_LASER_PWM_PIN)
#if BOTH(SPINDLE_FEATURE, LASER_FEATURE)
#error "Enable only one of SPINDLE_FEATURE or LASER_FEATURE."
@@ -2746,15 +2951,11 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
#elif ENABLED(SPINDLE_LASER_PWM)
#if !defined(SPINDLE_LASER_PWM_PIN) || SPINDLE_LASER_PWM_PIN < 0
#error "SPINDLE_LASER_PWM_PIN is required for SPINDLE_LASER_PWM."
- #elif !PWM_PIN(SPINDLE_LASER_PWM_PIN)
+ #elif !_TEST_PWM(SPINDLE_LASER_PWM_PIN)
#error "SPINDLE_LASER_PWM_PIN not assigned to a PWM pin."
- #elif SPINDLE_LASER_POWERUP_DELAY < 1
- #error "SPINDLE_LASER_POWERUP_DELAY must be greater than 0."
- #elif SPINDLE_LASER_POWERDOWN_DELAY < 1
- #error "SPINDLE_LASER_POWERDOWN_DELAY must be greater than 0."
#elif !defined(SPINDLE_LASER_PWM_INVERT)
#error "SPINDLE_LASER_PWM_INVERT is required for (SPINDLE|LASER)_FEATURE."
- #elif !defined(SPEED_POWER_SLOPE) || !defined(SPEED_POWER_INTERCEPT) || !defined(SPEED_POWER_MIN) || !defined(SPEED_POWER_MAX)
+ #elif !(defined(SPEED_POWER_INTERCEPT) && defined(SPEED_POWER_MIN) && defined(SPEED_POWER_MAX) && defined(SPEED_POWER_STARTUP))
#error "SPINDLE_LASER_PWM equation constant(s) missing."
#elif _PIN_CONFLICT(X_MIN)
#error "SPINDLE_LASER_PWM pin conflicts with X_MIN_PIN."
@@ -2817,8 +3018,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
#endif
#endif
-#if HAS_ADC_BUTTONS && defined(ADC_BUTTON_DEBOUNCE_DELAY) && !WITHIN(ADC_BUTTON_DEBOUNCE_DELAY, 16, 255)
- #error "ADC_BUTTON_DEBOUNCE_DELAY must be an integer from 16 to 255."
+#if HAS_ADC_BUTTONS && defined(ADC_BUTTON_DEBOUNCE_DELAY) && ADC_BUTTON_DEBOUNCE_DELAY < 16
+ #error "ADC_BUTTON_DEBOUNCE_DELAY must be greater than 16."
#endif
/**
@@ -2833,3 +3034,22 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
#if SAVED_POSITIONS > 256
#error "SAVED_POSITIONS must be an integer from 0 to 256."
#endif
+
+/**
+ * Sanity checks for stepper chunk support
+ */
+#if ENABLED(DIRECT_STEPPING)
+ #if ENABLED(LIN_ADVANCE)
+ #error "DIRECT_STEPPING is incompatible with LIN_ADVANCE. Enable in external planner if possible."
+ #endif
+#endif
+
+/**
+ * Sanity check for WIFI
+ */
+#if ENABLED(ESP3D_WIFISUPPORT) && DISABLED(ARDUINO_ARCH_ESP32)
+ #error "ESP3D_WIFISUPPORT requires an ESP32 controller. Use WIFISUPPORT for standalone ESP3D modules."
+#endif
+
+// Misc. Cleanup
+#undef _TEST_PWM
diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h
index 33d867aca..8513cd759 100644
--- a/Marlin/src/inc/Version.h
+++ b/Marlin/src/inc/Version.h
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
@@ -33,7 +33,7 @@
* vendor name, download location, GitHub account, etc.
*/
#ifndef DETAILED_BUILD_VERSION
- #define DETAILED_BUILD_VERSION SHORT_BUILD_VERSION " (GitHub)"
+ #define DETAILED_BUILD_VERSION SHORT_BUILD_VERSION
#endif
/**
@@ -42,7 +42,7 @@
* version was tagged.
*/
#ifndef STRING_DISTRIBUTION_DATE
- #define STRING_DISTRIBUTION_DATE "2020-07-09"
+ #define STRING_DISTRIBUTION_DATE "2020-07-27"
#endif
/**
@@ -52,7 +52,7 @@
* to alert users to major changes.
*/
-#define MARLIN_HEX_VERSION 020005
+#define MARLIN_HEX_VERSION 020006
#ifndef REQUIRED_CONFIGURATION_H_VERSION
#define REQUIRED_CONFIGURATION_H_VERSION MARLIN_HEX_VERSION
#endif
@@ -97,7 +97,7 @@
* documentation about a specific Marlin release. Displayed in the Info Menu.
*/
#ifndef WEBSITE_URL
- #define WEBSITE_URL "http://marlinfw.org"
+ #define WEBSITE_URL "https://marlinfw.org"
#endif
/**
diff --git a/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp b/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp
index a1258a3b1..9ba9b871e 100644
--- a/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp
+++ b/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp
@@ -23,10 +23,6 @@
#include
-#ifndef LCD_CLASS
- #include
- #define LCD_CLASS LiquidCrystal
-#endif
extern LCD_CLASS lcd;
int lcd_glyph_height() { return 1; }
@@ -678,6 +674,8 @@ static const hd44780_charmap_t g_hd44780_charmap_common[] PROGMEM = {
{IV('ď'), 'd', 0}, // 010F
{IV('đ'), 'd', 0}, // 0111
{IV('ę'), 'e', 0}, // 0119
+ {IV('Ě'), 'E', 0}, // 011A
+ {IV('ě'), 'e', 0}, // 011B
{IV('ğ'), 'g', 0}, // 011F
{IV('İ'), 'I', 0}, // 0130
{IV('ı'), 'i', 0}, // 0131
@@ -688,6 +686,7 @@ static const hd44780_charmap_t g_hd44780_charmap_common[] PROGMEM = {
{IV('ń'), 'n', 0}, // 0144
{IV('ň'), 'n', 0}, // 0148
+ {IV('Ř'), 'R', 0}, // 0158
{IV('ř'), 'r', 0}, // 0159
{IV('Ś'), 'S', 0}, // 015A
{IV('ś'), 's', 0}, // 015B
@@ -924,6 +923,7 @@ static const hd44780_charmap_t g_hd44780_charmap_common[] PROGMEM = {
{IV('ю'), '|', 'o'},
{IV('я'), 'g', 0}, // 044F
{IV('ё'), 'e', 0}, // 0451
+
#endif
{IV('•'), '.', 0}, // 2022 ·
diff --git a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp
index ee025f658..a924528c3 100644
--- a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp
+++ b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp
@@ -16,7 +16,7 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
@@ -275,7 +275,7 @@ void MarlinUI::set_custom_characters(const HD44780CharSet screen_charset/*=CHARS
#endif // LCD_PROGRESS_BAR
- #if ENABLED(SDSUPPORT) && HAS_LCD_MENU
+ #if BOTH(SDSUPPORT, HAS_LCD_MENU)
// CHARSET_MENU
const static PROGMEM byte refresh[8] = {
@@ -325,7 +325,7 @@ void MarlinUI::set_custom_characters(const HD44780CharSet screen_charset/*=CHARS
#endif
{
createChar_P(LCD_STR_UPLEVEL[0], uplevel);
- #if ENABLED(SDSUPPORT) && HAS_LCD_MENU
+ #if BOTH(SDSUPPORT, HAS_LCD_MENU)
// SD Card sub-menu special characters
createChar_P(LCD_STR_REFRESH[0], refresh);
createChar_P(LCD_STR_FOLDER[0], folder);
@@ -367,11 +367,11 @@ void MarlinUI::init_lcd() {
}
bool MarlinUI::detected() {
- return true
+ return (true
#if EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) && defined(DETECT_DEVICE)
&& lcd.LcdDetected() == 1
#endif
- ;
+ );
}
#if HAS_SLOW_BUTTONS
@@ -745,7 +745,7 @@ void MarlinUI::draw_status_screen() {
//
// Hotend 1 or Bed Temperature
//
- #if HOTENDS > 1
+ #if HAS_MULTI_HOTEND
lcd_moveto(8, 0);
_draw_heater_status(H_E1, LCD_STR_THERMOMETER[0], blink);
#elif HAS_HEATED_BED
@@ -763,7 +763,7 @@ void MarlinUI::draw_status_screen() {
//
// Hotend 1 or Bed Temperature
//
- #if HOTENDS > 1
+ #if HAS_MULTI_HOTEND
lcd_moveto(10, 0);
_draw_heater_status(H_E1, LCD_STR_THERMOMETER[0], blink);
#elif HAS_HEATED_BED
@@ -791,7 +791,7 @@ void MarlinUI::draw_status_screen() {
// If the first line has two extruder temps,
// show more temperatures on the next line
- #if HOTENDS > 2 || (HOTENDS > 1 && HAS_HEATED_BED)
+ #if HOTENDS > 2 || (HAS_MULTI_HOTEND && HAS_HEATED_BED)
#if HOTENDS > 2
_draw_heater_status(H_E2, LCD_STR_THERMOMETER[0], blink);
@@ -802,7 +802,7 @@ void MarlinUI::draw_status_screen() {
#else // HOTENDS <= 2 && (HOTENDS <= 1 || !HAS_HEATED_BED)
- #if DUAL_MIXING_EXTRUDER
+ #if HAS_DUAL_MIXING
// Two-component mix / gradient instead of XY
@@ -822,19 +822,11 @@ void MarlinUI::draw_status_screen() {
sprintf_P(mixer_messages, PSTR("%s %d;%d%% "), mix_label, int(mixer.mix[0]), int(mixer.mix[1]));
lcd_put_u8str(mixer_messages);
- #else // !DUAL_MIXING_EXTRUDER
+ #else // !HAS_DUAL_MIXING
- if (true
- #if ENABLED(LCD_SHOW_E_TOTAL)
- && !printingIsActive()
- #endif
- ) {
- const xy_pos_t lpos = current_position.asLogical();
- _draw_axis_value(X_AXIS, ftostr4sign(lpos.x), blink);
- lcd_put_wchar(' ');
- _draw_axis_value(Y_AXIS, ftostr4sign(lpos.y), blink);
- }
- else {
+ const bool show_e_total = TERN0(LCD_SHOW_E_TOTAL, printingIsActive() || marlin_state == MF_SD_COMPLETE);
+
+ if (show_e_total) {
#if ENABLED(LCD_SHOW_E_TOTAL)
char tmp[20];
const uint8_t escale = e_move_accumulator >= 100000.0f ? 10 : 1; // After 100m switch to cm
@@ -842,8 +834,14 @@ void MarlinUI::draw_status_screen() {
lcd_put_u8str(tmp);
#endif
}
+ else {
+ const xy_pos_t lpos = current_position.asLogical();
+ _draw_axis_value(X_AXIS, ftostr4sign(lpos.x), blink);
+ lcd_put_wchar(' ');
+ _draw_axis_value(Y_AXIS, ftostr4sign(lpos.y), blink);
+ }
- #endif // !DUAL_MIXING_EXTRUDER
+ #endif // !HAS_DUAL_MIXING
#endif // HOTENDS <= 2 && (HOTENDS <= 1 || !HAS_HEATED_BED)
@@ -924,7 +922,7 @@ void MarlinUI::draw_status_screen() {
lcd_moveto(LCD_WIDTH - 9, 0);
_draw_axis_value(Z_AXIS, ftostr52sp(LOGICAL_Z_POSITION(current_position.z)), blink);
- #if HAS_LEVELING && (HOTENDS > 1 || !HAS_HEATED_BED)
+ #if HAS_LEVELING && (HAS_MULTI_HOTEND || !HAS_HEATED_BED)
lcd_put_wchar(LCD_WIDTH - 1, 0, planner.leveling_active || blink ? '_' : ' ');
#endif
@@ -934,7 +932,7 @@ void MarlinUI::draw_status_screen() {
// Hotend 1 or Bed Temperature
//
lcd_moveto(0, 1);
- #if HOTENDS > 1
+ #if HAS_MULTI_HOTEND
_draw_heater_status(H_E1, LCD_STR_THERMOMETER[0], blink);
#elif HAS_HEATED_BED
_draw_bed_status(blink);
@@ -952,7 +950,7 @@ void MarlinUI::draw_status_screen() {
lcd_moveto(0, 2);
#if HOTENDS > 2
_draw_heater_status(H_E2, LCD_STR_THERMOMETER[0], blink);
- #elif HOTENDS > 1 && HAS_HEATED_BED
+ #elif HAS_MULTI_HOTEND && HAS_HEATED_BED
_draw_bed_status(blink);
#elif HAS_PRINT_PROGRESS
#define DREW_PRINT_PROGRESS
@@ -1006,7 +1004,7 @@ void MarlinUI::draw_status_screen() {
int8_t pad = (LCD_WIDTH - utf8_strlen_P(pstr)) / 2;
while (--pad >= 0) { lcd_put_wchar(' '); n--; }
}
- n = lcd_put_u8str_ind_P(pstr, itemIndex, n);
+ n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, n);
if (valstr) n -= lcd_put_u8str_max(valstr, n);
for (; n > 0; --n) lcd_put_wchar(' ');
}
@@ -1014,33 +1012,32 @@ void MarlinUI::draw_status_screen() {
// Draw a generic menu item with pre_char (if selected) and post_char
void MenuItemBase::_draw(const bool sel, const uint8_t row, PGM_P const pstr, const char pre_char, const char post_char) {
lcd_put_wchar(0, row, sel ? pre_char : ' ');
- uint8_t n = lcd_put_u8str_ind_P(pstr, itemIndex, LCD_WIDTH - 2);
+ uint8_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 2);
for (; n; --n) lcd_put_wchar(' ');
lcd_put_wchar(post_char);
}
// Draw a menu item with a (potentially) editable value
- void MenuEditItemBase::draw(const bool sel, const uint8_t row, PGM_P const pstr, const char* const data, const bool pgm) {
- const uint8_t vlen = data ? (pgm ? utf8_strlen_P(data) : utf8_strlen(data)) : 0;
+ void MenuEditItemBase::draw(const bool sel, const uint8_t row, PGM_P const pstr, const char* const inStr, const bool pgm) {
+ const uint8_t vlen = inStr ? (pgm ? utf8_strlen_P(inStr) : utf8_strlen(inStr)) : 0;
lcd_put_wchar(0, row, sel ? LCD_STR_ARROW_RIGHT[0] : ' ');
- uint8_t n = lcd_put_u8str_ind_P(pstr, itemIndex, LCD_WIDTH - 2 - vlen);
+ uint8_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 2 - vlen);
if (vlen) {
lcd_put_wchar(':');
for (; n; --n) lcd_put_wchar(' ');
- if (pgm) lcd_put_u8str_P(data); else lcd_put_u8str(data);
+ if (pgm) lcd_put_u8str_P(inStr); else lcd_put_u8str(inStr);
}
}
// Low-level draw_edit_screen can be used to draw an edit screen from anyplace
void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char* const value/*=nullptr*/) {
ui.encoder_direction_normal();
-
- uint8_t n = lcd_put_u8str_ind_P(0, 1, pstr, itemIndex, LCD_WIDTH - 1);
+ uint8_t n = lcd_put_u8str_ind_P(0, 1, pstr, itemIndex, itemString, LCD_WIDTH - 1);
if (value != nullptr) {
- lcd_put_wchar(':');
- int len = utf8_strlen(value);
- const lcd_uint_t valrow = (n < len + 1) ? 2 : 1; // Value on the next row if it won't fit
- lcd_put_wchar((LCD_WIDTH - 1) - (len + 1), valrow, ' '); // Right-justified, padded, leading space
+ lcd_put_wchar(':'); n--;
+ const uint8_t len = utf8_strlen(value) + 1; // Plus one for a leading space
+ const lcd_uint_t valrow = n < len ? 2 : 1; // Value on the next row if it won't fit
+ lcd_put_wchar(LCD_WIDTH - len, valrow, ' '); // Right-justified, padded, leading space
lcd_put_u8str(value);
}
}
@@ -1073,46 +1070,22 @@ void MarlinUI::draw_status_screen() {
static uint8_t ledsprev = 0;
uint8_t leds = 0;
- #if HAS_HEATED_BED
- if (thermalManager.degTargetBed() > 0) leds |= LED_A;
- #endif
+ if (TERN0(HAS_HEATED_BED, thermalManager.degTargetBed() > 0)) leds |= LED_A;
+ if (TERN0(HAS_HOTEND, thermalManager.degTargetHotend(0) > 0)) leds |= LED_B;
- #if HOTENDS
- if (thermalManager.degTargetHotend(0) > 0) leds |= LED_B;
- #endif
-
- #if FAN_COUNT > 0
- if (0
- #if HAS_FAN0
- || thermalManager.fan_speed[0]
- #endif
- #if HAS_FAN1
- || thermalManager.fan_speed[1]
- #endif
- #if HAS_FAN2
- || thermalManager.fan_speed[2]
- #endif
- #if HAS_FAN3
- || thermalManager.fan_speed[3]
- #endif
- #if HAS_FAN4
- || thermalManager.fan_speed[4]
- #endif
- #if HAS_FAN5
- || thermalManager.fan_speed[5]
- #endif
- #if HAS_FAN6
- || thermalManager.fan_speed[6]
- #endif
- #if HAS_FAN7
- || thermalManager.fan_speed[7]
- #endif
+ #if HAS_FAN
+ if ( TERN0(HAS_FAN0, thermalManager.fan_speed[0])
+ || TERN0(HAS_FAN1, thermalManager.fan_speed[1])
+ || TERN0(HAS_FAN2, thermalManager.fan_speed[2])
+ || TERN0(HAS_FAN3, thermalManager.fan_speed[3])
+ || TERN0(HAS_FAN4, thermalManager.fan_speed[4])
+ || TERN0(HAS_FAN5, thermalManager.fan_speed[5])
+ || TERN0(HAS_FAN6, thermalManager.fan_speed[6])
+ || TERN0(HAS_FAN7, thermalManager.fan_speed[7])
) leds |= LED_C;
- #endif // FAN_COUNT > 0
+ #endif // HAS_FAN
- #if HOTENDS > 1
- if (thermalManager.degTargetHotend(1) > 0) leds |= LED_C;
- #endif
+ if (TERN0(HAS_MULTI_HOTEND, thermalManager.degTargetHotend(1) > 0)) leds |= LED_C;
if (leds != ledsprev) {
lcd.setBacklight(leds);
diff --git a/Marlin/src/lcd/HD44780/ultralcd_HD44780.h b/Marlin/src/lcd/HD44780/ultralcd_HD44780.h
index 12bf86a16..604d26a02 100644
--- a/Marlin/src/lcd/HD44780/ultralcd_HD44780.h
+++ b/Marlin/src/lcd/HD44780/ultralcd_HD44780.h
@@ -16,32 +16,19 @@
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
+ * along with this program. If not, see .
*
*/
#pragma once
/**
- * Implementation of the LCD display routines for a Hitachi HD44780 display.
- * These are the most common LCD character displays.
+ * Hitachi HD44780 display defines and headers
*/
#include "../../inc/MarlinConfig.h"
-#if LCD_HEIGHT > 3
- #include "../../libs/duration_t.h"
-#endif
-
-////////////////////////////////////
-// Setup button and encode mappings for each panel (into 'buttons' variable
-//
-// This is just to map common functions (across different panels) onto the same
-// macro name. The mapping is independent of whether the button is directly connected or
-// via a shift/i2c register.
-
-////////////////////////////////////
-// Create LCD class instance and chipset-specific information
#if ENABLED(LCD_I2C_TYPE_PCF8575)
+
// NOTE: These are register-mapped pins on the PCF8575 controller, not Arduino pins.
#define LCD_I2C_PIN_BL 3
#define LCD_I2C_PIN_EN 2
@@ -58,6 +45,7 @@
#define LCD_CLASS LiquidCrystal_I2C
#elif ENABLED(LCD_I2C_TYPE_MCP23017)
+
// For the LED indicators (which may be mapped to different events in update_indicators())
#define LCD_HAS_STATUS_INDICATORS
#define LED_A 0x04 //100
@@ -69,40 +57,45 @@
#define LCD_CLASS LiquidTWI2
#elif ENABLED(LCD_I2C_TYPE_MCP23008)
+
#include
#include
#define LCD_CLASS LiquidTWI2
#elif ENABLED(LCD_I2C_TYPE_PCA8574)
+
#include
#define LCD_CLASS LiquidCrystal_I2C
#elif ENABLED(SR_LCD_2W_NL)
+
// 2 wire Non-latching LCD SR from:
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
-// extern "C" void __cxa_pure_virtual() { while (1); }
#include
#include
#define LCD_CLASS LiquidCrystal_SR
+
#elif ENABLED(SR_LCD_3W_NL)
-//NewLiquidCrystal was not working for me, but this worked first try
-//https://github.com/mikeshub/SailfishLCD
-//uses the code directly from Sailfish
+ // NewLiquidCrystal didn't work, so this uses
+ // https://github.com/mikeshub/SailfishLCD
#include
#define LCD_CLASS LiquidCrystalSerial
#elif ENABLED(LCM1602)
+
#include
#include
#include