diff --git a/.editorconfig b/.editorconfig
index a0fa3eff170e..b8f6ef7f8e32 100644
--- a/.editorconfig
+++ b/.editorconfig
@@ -4,10 +4,10 @@ root = true
[{*.patch,syntax_test_*}]
trim_trailing_whitespace = false
-[{*.c,*.cpp,*.h}]
+[{*.c,*.cpp,*.h,*.ino}]
charset = utf-8
-[{*.c,*.cpp,*.h,Makefile}]
+[{*.c,*.cpp,*.h,*.ino,Makefile}]
trim_trailing_whitespace = true
insert_final_newline = true
end_of_line = lf
diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml
index 7549e3defcbb..5429f3eb95ce 100644
--- a/.github/workflows/test-builds.yml
+++ b/.github/workflows/test-builds.yml
@@ -56,28 +56,31 @@ jobs:
# STM32F1 (Maple) Environments
- - STM32F103RC_btt
- - STM32F103RC_btt_USB
- - STM32F103RE_btt
- - STM32F103RE_btt_USB
+ #- STM32F103RC_btt_maple
+ - STM32F103RC_btt_USB_maple
- STM32F103RC_fysetc
- STM32F103RC_meeb
- jgaurora_a5s_a1
- STM32F103VE_longer
- - mks_robin
+ #- mks_robin_maple
- mks_robin_lite
- mks_robin_pro
- - STM32F103RET6_creality
- - mks_robin_nano35
+ #- mks_robin_nano35_maple
+ #- STM32F103RET6_creality_maple
# STM32 (ST) Environments
+ - STM32F103RC_btt
+ #- STM32F103RC_btt_USB
+ - STM32F103RE_btt
+ - STM32F103RE_btt_USB
+ - STM32F103RET6_creality
- STM32F407VE_black
- STM32F401VE_STEVAL
- BIGTREE_BTT002
- BIGTREE_SKR_PRO
- BIGTREE_GTR_V1_0
- - mks_robin_stm32
+ - mks_robin
- ARMED
- FYSETC_S6
- STM32F070CB_malyan
@@ -86,9 +89,12 @@ jobs:
- FLYF407ZG
- rumba32
- LERDGEX
- - mks_robin_nano35_stm32
+ - LERDGEK
+ - mks_robin_nano35
- NUCLEO_F767ZI
- REMRAM_V1
+ - BTT_SKR_SE_BX
+ - chitu_f103
# Put lengthy tests last
@@ -98,12 +104,30 @@ jobs:
# Non-working environment tests
#- at90usb1286_cdc
#- STM32F103CB_malyan
+ #- STM32F103RE
#- mks_robin_mini
steps:
+ - name: Check out the PR
+ uses: actions/checkout@v2
+
+ - name: Cache pip
+ uses: actions/cache@v2
+ with:
+ path: ~/.cache/pip
+ key: ${{ runner.os }}-pip-${{ hashFiles('**/requirements.txt') }}
+ restore-keys: |
+ ${{ runner.os }}-pip-
+
+ - name: Cache PlatformIO
+ uses: actions/cache@v2
+ with:
+ path: ~/.platformio
+ key: ${{ runner.os }}-${{ hashFiles('**/lockfiles') }}
+
- name: Select Python 3.7
- uses: actions/setup-python@v1
+ uses: actions/setup-python@v2
with:
python-version: '3.7' # Version range or exact version of a Python version to use, using semvers version range syntax.
architecture: 'x64' # optional x64 or x86. Defaults to x64 if not specified
@@ -113,9 +137,6 @@ jobs:
pip install -U https://github.com/platformio/platformio-core/archive/develop.zip
platformio update
- - name: Check out the PR
- uses: actions/checkout@v2
-
- name: Run ${{ matrix.test-platform }} Tests
run: |
make tests-single-ci TEST_TARGET=${{ matrix.test-platform }}
diff --git a/.gitignore b/.gitignore
index 62f73a7c0d00..ac2c9b5591fd 100755
--- a/.gitignore
+++ b/.gitignore
@@ -19,9 +19,9 @@
# along with this program. If not, see .
#
-# Our automatic versioning scheme generates the following file
-# NEVER put it in the repository
+# Generated files
_Version.h
+bdf2u8g
#
# OS
@@ -122,29 +122,6 @@ tags
.gcc-flags.json
/lib/
-# Workaround for Deviot+platformio quirks
-Marlin/lib
-Marlin/platformio.ini
-Marlin/*/platformio.ini
-Marlin/*/*/platformio.ini
-Marlin/*/*/*/platformio.ini
-Marlin/*/*/*/*/platformio.ini
-Marlin/.travis.yml
-Marlin/*/.travis.yml
-Marlin/*/*/.travis.yml
-Marlin/*/*/*/.travis.yml
-Marlin/*/*/*/*/.travis.yml
-Marlin/.gitignore
-Marlin/*/.gitignore
-Marlin/*/*/.gitignore
-Marlin/*/*/*/.gitignore
-Marlin/*/*/*/*/.gitignore
-Marlin/readme.txt
-Marlin/*/readme.txt
-Marlin/*/*/readme.txt
-Marlin/*/*/*/readme.txt
-Marlin/*/*/*/*/readme.txt
-
# Secure Credentials
Configuration_Secure.h
diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h
index ab112894b100..717cdd9236b9 100644
--- a/Marlin/Configuration.h
+++ b/Marlin/Configuration.h
@@ -35,37 +35,36 @@
*
* Advanced settings can be found in Configuration_adv.h
*/
-#define CONFIGURATION_H_VERSION 020008
+#define CONFIGURATION_H_VERSION 02000900
//===========================================================================
//============================= Getting Started =============================
//===========================================================================
/**
- * Here are some standard links for getting your machine calibrated:
+ * Here are some useful links to help get your machine configured and calibrated:
*
- * https://reprap.org/wiki/Calibration
- * https://youtu.be/wAL9d7FgInk
- * http://calculator.josefprusa.cz
- * https://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide
- * https://www.thingiverse.com/thing:5573
- * https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
- * https://www.thingiverse.com/thing:298812
+ * Example Configs: https://github.com/MarlinFirmware/Configurations/branches/all
+ *
+ * Průša Calculator: https://blog.prusaprinters.org/calculator_3416/
+ *
+ * Calibration Guides: https://reprap.org/wiki/Calibration
+ * https://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide
+ * https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
+ * https://youtu.be/wAL9d7FgInk
+ *
+ * Calibration Objects: https://www.thingiverse.com/thing:5573
+ * https://www.thingiverse.com/thing:1278865
*/
//===========================================================================
-//============================= DELTA Printer ===============================
+//========================== DELTA / SCARA / TPARA ==========================
//===========================================================================
-// For a Delta printer, start with one of the configuration files in the config/examples/delta directory
-// from https://github.com/MarlinFirmware/Configurations/branches/all and customize for your machine.
//
-
-//===========================================================================
-//============================= SCARA Printer ===============================
-//===========================================================================
-// For a SCARA printer, start with one of the configuration files in the config/examples/SCARA directory
-// from https://github.com/MarlinFirmware/Configurations/branches/all and customize for your machine.
+// Download configurations from the link above and customize for your machine.
+// Examples are located in config/examples/delta, .../SCARA, and .../TPARA.
//
+//===========================================================================
// @section info
@@ -106,14 +105,9 @@
#define SERIAL_PORT 0
/**
- * Select a secondary serial port on the board to use for communication with the host.
- * Currently Ethernet (-2) is only supported on Teensy 4.1 boards.
- * :[-2, -1, 0, 1, 2, 3, 4, 5, 6, 7]
- */
-//#define SERIAL_PORT_2 -1
-
-/**
- * This setting determines the communication speed of the printer.
+ * Serial Port Baud Rate
+ * This is the default communication speed for all serial ports.
+ * Set the baud rate defaults for additional serial ports below.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
@@ -122,6 +116,23 @@
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
*/
#define BAUDRATE 250000
+//#define BAUD_RATE_GCODE // Enable G-code M575 to set the baud rate
+
+/**
+ * Select a secondary serial port on the board to use for communication with the host.
+ * Currently Ethernet (-2) is only supported on Teensy 4.1 boards.
+ * :[-2, -1, 0, 1, 2, 3, 4, 5, 6, 7]
+ */
+//#define SERIAL_PORT_2 -1
+//#define BAUDRATE_2 250000 // Enable to override BAUDRATE
+
+/**
+ * Select a third serial port on the board to use for communication with the host.
+ * Currently only supported for AVR, DUE, LPC1768/9 and STM32/STM32F1
+ * :[-1, 0, 1, 2, 3, 4, 5, 6, 7]
+ */
+//#define SERIAL_PORT_3 1
+//#define BAUDRATE_3 250000 // Enable to override BAUDRATE
// Enable the Bluetooth serial interface on AT90USB devices
//#define BLUETOOTH
@@ -138,6 +149,45 @@
// Choose your own or use a service like https://www.uuidgenerator.net/version4
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
+/**
+ * Define the number of coordinated linear axes.
+ * See https://github.com/DerAndere1/Marlin/wiki
+ * Each linear axis gets its own stepper control and endstop:
+ *
+ * Steppers: *_STEP_PIN, *_ENABLE_PIN, *_DIR_PIN, *_ENABLE_ON
+ * Endstops: *_STOP_PIN, USE_*MIN_PLUG, USE_*MAX_PLUG
+ * Axes: *_MIN_POS, *_MAX_POS, INVERT_*_DIR
+ * Planner: DEFAULT_AXIS_STEPS_PER_UNIT, DEFAULT_MAX_FEEDRATE
+ * DEFAULT_MAX_ACCELERATION, AXIS_RELATIVE_MODES,
+ * MICROSTEP_MODES, MANUAL_FEEDRATE
+ *
+ * :[3, 4, 5, 6]
+ */
+//#define LINEAR_AXES 3
+
+/**
+ * Axis codes for additional axes:
+ * This defines the axis code that is used in G-code commands to
+ * reference a specific axis.
+ * 'A' for rotational axis parallel to X
+ * 'B' for rotational axis parallel to Y
+ * 'C' for rotational axis parallel to Z
+ * 'U' for secondary linear axis parallel to X
+ * 'V' for secondary linear axis parallel to Y
+ * 'W' for secondary linear axis parallel to Z
+ * Regardless of the settings, firmware-internal axis IDs are
+ * I (AXIS4), J (AXIS5), K (AXIS6).
+ */
+#if LINEAR_AXES >= 4
+ #define AXIS4_NAME 'A' // :['A', 'B', 'C', 'U', 'V', 'W']
+#endif
+#if LINEAR_AXES >= 5
+ #define AXIS5_NAME 'B' // :['A', 'B', 'C', 'U', 'V', 'W']
+#endif
+#if LINEAR_AXES >= 6
+ #define AXIS6_NAME 'C' // :['A', 'B', 'C', 'U', 'V', 'W']
+#endif
+
// @section extruder
// This defines the number of extruders
@@ -161,11 +211,11 @@
* Multi-Material Unit
* Set to one of these predefined models:
*
- * PRUSA_MMU1 : Průša MMU1 (The "multiplexer" version)
- * PRUSA_MMU2 : Průša MMU2
- * PRUSA_MMU2S : Průša MMU2S (Requires MK3S extruder with motion sensor, EXTRUDERS = 5)
- * SMUFF_EMU_MMU2 : Technik Gegg SMUFF (Průša MMU2 emulation mode)
- * SMUFF_EMU_MMU2S : Technik Gegg SMUFF (Průša MMU2S emulation mode)
+ * PRUSA_MMU1 : Průša MMU1 (The "multiplexer" version)
+ * PRUSA_MMU2 : Průša MMU2
+ * PRUSA_MMU2S : Průša MMU2S (Requires MK3S extruder with motion sensor, EXTRUDERS = 5)
+ * EXTENDABLE_EMU_MMU2 : MMU with configurable number of filaments (ERCF, SMuFF or similar with Průša MMU2 compatible firmware)
+ * EXTENDABLE_EMU_MMU2S : MMUS with configurable number of filaments (ERCF, SMuFF or similar with Průša MMU2 compatible firmware)
*
* Requires NOZZLE_PARK_FEATURE to park print head in case MMU unit fails.
* See additional options in Configuration_adv.h.
@@ -330,8 +380,10 @@
#define AUTO_POWER_E_FANS
#define AUTO_POWER_CONTROLLERFAN
#define AUTO_POWER_CHAMBER_FAN
+ #define AUTO_POWER_COOLER_FAN
//#define AUTO_POWER_E_TEMP 50 // (°C) Turn on PSU if any extruder is over this temperature
//#define AUTO_POWER_CHAMBER_TEMP 30 // (°C) Turn on PSU if the chamber is over this temperature
+ //#define AUTO_POWER_COOLER_TEMP 26 // (°C) Turn on PSU if the cooler is over this temperature
#define POWER_TIMEOUT 30 // (s) Turn off power if the machine is idle for this duration
//#define POWER_OFF_DELAY 60 // (s) Delay of poweroff after M81 command. Useful to let fans run for extra time.
#endif
@@ -419,9 +471,11 @@
#define TEMP_SENSOR_BED 0
#define TEMP_SENSOR_PROBE 0
#define TEMP_SENSOR_CHAMBER 0
+#define TEMP_SENSOR_COOLER 0
+#define TEMP_SENSOR_REDUNDANT 0
// Dummy thermistor constant temperature readings, for use with 998 and 999
-#define DUMMY_THERMISTOR_998_VALUE 25
+#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Resistor values when using MAX31865 sensors (-5) on TEMP_SENSOR_0 / 1
@@ -430,18 +484,39 @@
//#define MAX31865_SENSOR_OHMS_1 100
//#define MAX31865_CALIBRATION_OHMS_1 430
-// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
-// from the two sensors differ too much the print will be aborted.
-//#define TEMP_SENSOR_1_AS_REDUNDANT
-#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
+#define TEMP_RESIDENCY_TIME 10 // (seconds) Time to wait for hotend to "settle" in M109
+#define TEMP_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
+#define TEMP_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
-#define TEMP_RESIDENCY_TIME 10 // (seconds) Time to wait for hotend to "settle" in M109
-#define TEMP_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
-#define TEMP_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
+#define TEMP_BED_RESIDENCY_TIME 10 // (seconds) Time to wait for bed to "settle" in M190
+#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
+#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
-#define TEMP_BED_RESIDENCY_TIME 10 // (seconds) Time to wait for bed to "settle" in M190
-#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
-#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
+#define TEMP_CHAMBER_RESIDENCY_TIME 10 // (seconds) Time to wait for chamber to "settle" in M191
+#define TEMP_CHAMBER_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer
+#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target
+
+/**
+ * Redundant Temperature Sensor (TEMP_SENSOR_REDUNDANT)
+ *
+ * Use a temp sensor as a redundant sensor for another reading. Select an unused temperature sensor, and another
+ * sensor you'd like it to be redundant for. If the two thermistors differ by TEMP_SENSOR_REDUNDANT_MAX_DIFF (°C),
+ * the print will be aborted. Whichever sensor is selected will have its normal functions disabled; i.e. selecting
+ * the Bed sensor (-1) will disable bed heating/monitoring.
+ *
+ * Use the following to select temp sensors:
+ * -5 : Cooler
+ * -4 : Probe
+ * -3 : not used
+ * -2 : Chamber
+ * -1 : Bed
+ * 0-7 : E0 through E7
+ */
+#if TEMP_SENSOR_REDUNDANT
+ #define TEMP_SENSOR_REDUNDANT_SOURCE 1 // The sensor that will provide the redundant reading.
+ #define TEMP_SENSOR_REDUNDANT_TARGET 0 // The sensor that we are providing a redundant reading for.
+ #define TEMP_SENSOR_REDUNDANT_MAX_DIFF 10 // (°C) Temperature difference that will trigger a print abort.
+#endif
// Below this temperature the heater will be switched off
// because it probably indicates a broken thermistor wire.
@@ -454,6 +529,7 @@
#define HEATER_6_MINTEMP 5
#define HEATER_7_MINTEMP 5
#define BED_MINTEMP 5
+#define CHAMBER_MINTEMP 5
// Above this temperature the heater will be switched off.
// This can protect components from overheating, but NOT from shorts and failures.
@@ -467,6 +543,17 @@
#define HEATER_6_MAXTEMP 275
#define HEATER_7_MAXTEMP 275
#define BED_MAXTEMP 150
+#define CHAMBER_MAXTEMP 60
+
+/**
+ * Thermal Overshoot
+ * During heatup (and printing) the temperature can often "overshoot" the target by many degrees
+ * (especially before PID tuning). Setting the target temperature too close to MAXTEMP guarantees
+ * a MAXTEMP shutdown! Use these values to forbid temperatures being set too close to MAXTEMP.
+ */
+#define HOTEND_OVERSHOOT 15 // (°C) Forbid temperatures over MAXTEMP - OVERSHOOT
+#define BED_OVERSHOOT 10 // (°C) Forbid temperatures over MAXTEMP - OVERSHOOT
+#define COOLER_OVERSHOOT 2 // (°C) Forbid temperatures closer than OVERSHOOT
//===========================================================================
//============================= PID Settings ================================
@@ -540,7 +627,51 @@
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
#endif // PIDTEMPBED
-#if EITHER(PIDTEMP, PIDTEMPBED)
+//===========================================================================
+//==================== PID > Chamber Temperature Control ====================
+//===========================================================================
+
+/**
+ * PID Chamber Heating
+ *
+ * If this option is enabled set PID constants below.
+ * If this option is disabled, bang-bang will be used and CHAMBER_LIMIT_SWITCHING will enable
+ * hysteresis.
+ *
+ * The PID frequency will be the same as the extruder PWM.
+ * If PID_dT is the default, and correct for the hardware/configuration, that means 7.689Hz,
+ * which is fine for driving a square wave into a resistive load and does not significantly
+ * impact FET heating. This also works fine on a Fotek SSR-10DA Solid State Relay into a 200W
+ * heater. If your configuration is significantly different than this and you don't understand
+ * the issues involved, don't use chamber PID until someone else verifies that your hardware works.
+ */
+//#define PIDTEMPCHAMBER
+//#define CHAMBER_LIMIT_SWITCHING
+
+/**
+ * Max Chamber Power
+ * Applies to all forms of chamber control (PID, bang-bang, and bang-bang with hysteresis).
+ * When set to any value below 255, enables a form of PWM to the chamber heater that acts like a divider
+ * so don't use it unless you are OK with PWM on your heater. (See the comment on enabling PIDTEMPCHAMBER)
+ */
+#define MAX_CHAMBER_POWER 255 // limits duty cycle to chamber heater; 255=full current
+
+#if ENABLED(PIDTEMPCHAMBER)
+ #define MIN_CHAMBER_POWER 0
+ //#define PID_CHAMBER_DEBUG // Sends debug data to the serial port.
+
+ // Lasko "MyHeat Personal Heater" (200w) modified with a Fotek SSR-10DA to control only the heating element
+ // and placed inside the small Creality printer enclosure tent.
+ //
+ #define DEFAULT_chamberKp 37.04
+ #define DEFAULT_chamberKi 1.40
+ #define DEFAULT_chamberKd 655.17
+ // M309 P37.04 I1.04 D655.17
+
+ // FIND YOUR OWN: "M303 E-2 C8 S50" to run autotune on the chamber at 50 degreesC for 8 cycles.
+#endif // PIDTEMPCHAMBER
+
+#if ANY(PIDTEMP, PIDTEMPBED, PIDTEMPCHAMBER)
//#define PID_DEBUG // Sends debug data to the serial port. Use 'M303 D' to toggle activation.
//#define PID_OPENLOOP // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
//#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay
@@ -587,6 +718,7 @@
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
#define THERMAL_PROTECTION_BED // Enable thermal protection for the heated bed
#define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber
+#define THERMAL_PROTECTION_COOLER // Enable thermal protection for the laser cooling
//===========================================================================
//============================= Mechanical Settings =========================
@@ -616,9 +748,15 @@
#define USE_XMIN_PLUG
#define USE_YMIN_PLUG
#define USE_ZMIN_PLUG
+//#define USE_IMIN_PLUG
+//#define USE_JMIN_PLUG
+//#define USE_KMIN_PLUG
//#define USE_XMAX_PLUG
//#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG
+//#define USE_IMAX_PLUG
+//#define USE_JMAX_PLUG
+//#define USE_KMAX_PLUG
// Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS
@@ -627,9 +765,15 @@
//#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX
+ //#define ENDSTOPPULLUP_IMAX
+ //#define ENDSTOPPULLUP_JMAX
+ //#define ENDSTOPPULLUP_KMAX
//#define ENDSTOPPULLUP_XMIN
//#define ENDSTOPPULLUP_YMIN
//#define ENDSTOPPULLUP_ZMIN
+ //#define ENDSTOPPULLUP_IMIN
+ //#define ENDSTOPPULLUP_JMIN
+ //#define ENDSTOPPULLUP_KMIN
//#define ENDSTOPPULLUP_ZMIN_PROBE
#endif
@@ -640,9 +784,15 @@
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
+ //#define ENDSTOPPULLDOWN_IMAX
+ //#define ENDSTOPPULLDOWN_JMAX
+ //#define ENDSTOPPULLDOWN_KMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
+ //#define ENDSTOPPULLDOWN_IMIN
+ //#define ENDSTOPPULLDOWN_JMIN
+ //#define ENDSTOPPULLDOWN_KMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
@@ -650,9 +800,15 @@
#define X_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
#define Z_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
+#define I_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
+#define J_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
+#define K_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
#define X_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
#define Y_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
#define Z_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
+#define I_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
+#define J_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
+#define K_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // Set to true to invert the logic of the probe.
/**
@@ -681,6 +837,9 @@
//#define Z2_DRIVER_TYPE A4988
//#define Z3_DRIVER_TYPE A4988
//#define Z4_DRIVER_TYPE A4988
+//#define I_DRIVER_TYPE A4988
+//#define J_DRIVER_TYPE A4988
+//#define K_DRIVER_TYPE A4988
#define E0_DRIVER_TYPE A4988
//#define E1_DRIVER_TYPE A4988
//#define E2_DRIVER_TYPE A4988
@@ -734,14 +893,14 @@
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
- * X, Y, Z, E0 [, E1[, E2...]]
+ * X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 400, 500 }
/**
* Default Max Feed Rate (mm/s)
* Override with M203
- * X, Y, Z, E0 [, E1[, E2...]]
+ * X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]]
*/
#define DEFAULT_MAX_FEEDRATE { 300, 300, 5, 25 }
@@ -754,7 +913,7 @@
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
- * X, Y, Z, E0 [, E1[, E2...]]
+ * X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]]
*/
#define DEFAULT_MAX_ACCELERATION { 3000, 3000, 100, 10000 }
@@ -788,6 +947,9 @@
#define DEFAULT_XJERK 10.0
#define DEFAULT_YJERK 10.0
#define DEFAULT_ZJERK 0.3
+ //#define DEFAULT_IJERK 0.3
+ //#define DEFAULT_JJERK 0.3
+ //#define DEFAULT_KJERK 0.3
//#define TRAVEL_EXTRA_XYJERK 0.0 // Additional jerk allowance for all travel moves
@@ -871,7 +1033,6 @@
* or (with LCD_BED_LEVELING) the LCD controller.
*/
//#define PROBE_MANUALLY
-//#define MANUAL_PROBE_START_Z 0.2
/**
* A Fix-Mounted Probe either doesn't deploy or needs manual deployment.
@@ -993,13 +1154,13 @@
#define PROBING_MARGIN 10
// X and Y axis travel speed (mm/min) between probes
-#define XY_PROBE_SPEED (133*60)
+#define XY_PROBE_FEEDRATE (133*60)
// Feedrate (mm/min) for the first approach when double-probing (MULTIPLE_PROBING == 2)
-#define Z_PROBE_SPEED_FAST (4*60)
+#define Z_PROBE_FEEDRATE_FAST (4*60)
// Feedrate (mm/min) for the "accurate" probe of each point
-#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
+#define Z_PROBE_FEEDRATE_SLOW (Z_PROBE_FEEDRATE_FAST / 2)
/**
* Probe Activation Switch
@@ -1084,6 +1245,7 @@
//#define PROBING_HEATERS_OFF // Turn heaters off when probing
#if ENABLED(PROBING_HEATERS_OFF)
//#define WAIT_FOR_BED_HEATER // Wait for bed to heat back up between probes (to improve accuracy)
+ //#define WAIT_FOR_HOTEND // Wait for hotend to heat back up between probes (to improve accuracy & prevent cold extrude)
#endif
//#define PROBING_FANS_OFF // Turn fans off when probing
//#define PROBING_STEPPERS_OFF // Turn steppers off (unless needed to hold position) when probing
@@ -1102,12 +1264,18 @@
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
#define E_ENABLE_ON 0 // For all extruders
+//#define I_ENABLE_ON 0
+//#define J_ENABLE_ON 0
+//#define K_ENABLE_ON 0
// Disable axis steppers immediately when they're not being stepped.
// WARNING: When motors turn off there is a chance of losing position accuracy!
#define DISABLE_X false
#define DISABLE_Y false
#define DISABLE_Z false
+//#define DISABLE_I false
+//#define DISABLE_J false
+//#define DISABLE_K false
// Turn off the display blinking that warns about possible accuracy reduction
//#define DISABLE_REDUCED_ACCURACY_WARNING
@@ -1123,6 +1291,9 @@
#define INVERT_X_DIR false
#define INVERT_Y_DIR true
#define INVERT_Z_DIR false
+//#define INVERT_I_DIR false
+//#define INVERT_J_DIR false
+//#define INVERT_K_DIR false
// @section extruder
@@ -1140,7 +1311,13 @@
//#define NO_MOTION_BEFORE_HOMING // Inhibit movement until all axes have been homed. Also enable HOME_AFTER_DEACTIVATE for extra safety.
//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated. Also enable NO_MOTION_BEFORE_HOMING for extra safety.
-//#define UNKNOWN_Z_NO_RAISE // Don't raise Z (lower the bed) if Z is "unknown." For beds that fall when Z is powered off.
+
+/**
+ * Set Z_IDLE_HEIGHT if the Z-Axis moves on its own when steppers are disabled.
+ * - Use a low value (i.e., Z_MIN_POS) if the nozzle falls down to the bed.
+ * - Use a large value (i.e., Z_MAX_POS) if the bed falls down, away from the nozzle.
+ */
+//#define Z_IDLE_HEIGHT Z_HOME_POS
//#define Z_HOMING_HEIGHT 4 // (mm) Minimal Z height before homing (G28) for Z clearance above the bed, clamps, ...
// Be sure to have this much clearance over your Z_MAX_POS to prevent grinding.
@@ -1152,10 +1329,13 @@
#define X_HOME_DIR -1
#define Y_HOME_DIR -1
#define Z_HOME_DIR -1
+//#define I_HOME_DIR -1
+//#define J_HOME_DIR -1
+//#define K_HOME_DIR -1
// @section machine
-// The size of the print bed
+// The size of the printable area
#define X_BED_SIZE 200
#define Y_BED_SIZE 200
@@ -1166,6 +1346,12 @@
#define X_MAX_POS X_BED_SIZE
#define Y_MAX_POS Y_BED_SIZE
#define Z_MAX_POS 200
+//#define I_MIN_POS 0
+//#define I_MAX_POS 50
+//#define J_MIN_POS 0
+//#define J_MAX_POS 50
+//#define K_MIN_POS 0
+//#define K_MAX_POS 50
/**
* Software Endstops
@@ -1182,6 +1368,9 @@
#define MIN_SOFTWARE_ENDSTOP_X
#define MIN_SOFTWARE_ENDSTOP_Y
#define MIN_SOFTWARE_ENDSTOP_Z
+ #define MIN_SOFTWARE_ENDSTOP_I
+ #define MIN_SOFTWARE_ENDSTOP_J
+ #define MIN_SOFTWARE_ENDSTOP_K
#endif
// Max software endstops constrain movement within maximum coordinate bounds
@@ -1190,6 +1379,9 @@
#define MAX_SOFTWARE_ENDSTOP_X
#define MAX_SOFTWARE_ENDSTOP_Y
#define MAX_SOFTWARE_ENDSTOP_Z
+ #define MAX_SOFTWARE_ENDSTOP_I
+ #define MAX_SOFTWARE_ENDSTOP_J
+ #define MAX_SOFTWARE_ENDSTOP_K
#endif
#if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS)
@@ -1217,6 +1409,8 @@
#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.
+ //#define WATCH_ALL_RUNOUT_SENSORS // Execute runout script on any triggering sensor, not only for the active extruder.
+ // This is automatically enabled for MIXING_EXTRUDERs.
// Override individually if the runout sensors vary
//#define FIL_RUNOUT1_STATE LOW
@@ -1251,8 +1445,9 @@
//#define FIL_RUNOUT8_PULLUP
//#define FIL_RUNOUT8_PULLDOWN
- // Set one or more commands to execute on filament runout.
- // (After 'M412 H' Marlin will ask the host to handle the process.)
+ // Commands to execute on filament runout.
+ // With multiple runout sensors use the %c placeholder for the current tool in commands (e.g., "M600 T%c")
+ // NOTE: After 'M412 H1' the host handles filament runout and this script does not apply.
#define FILAMENT_RUNOUT_SCRIPT "M600"
// After a runout is detected, continue printing this length of filament
@@ -1336,6 +1531,11 @@
*/
//#define DEBUG_LEVELING_FEATURE
+#if ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL, PROBE_MANUALLY)
+ // Set a height for the start of manual adjustment
+ #define MANUAL_PROBE_START_Z 0.2 // (mm) Comment out to use the last-measured height
+#endif
+
#if ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_UBL)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
@@ -1357,10 +1557,11 @@
//#define G26_MESH_VALIDATION
#if ENABLED(G26_MESH_VALIDATION)
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
- #define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
- #define MESH_TEST_HOTEND_TEMP 205 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
- #define MESH_TEST_BED_TEMP 60 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
- #define G26_XY_FEEDRATE 20 // (mm/s) Feedrate for XY Moves for the G26 Mesh Validation Tool.
+ #define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for G26.
+ #define MESH_TEST_HOTEND_TEMP 205 // (°C) Default nozzle temperature for G26.
+ #define MESH_TEST_BED_TEMP 60 // (°C) Default bed temperature for G26.
+ #define G26_XY_FEEDRATE 20 // (mm/s) Feedrate for G26 XY moves.
+ #define G26_XY_FEEDRATE_TRAVEL 100 // (mm/s) Feedrate for G26 XY travel moves.
#define G26_RETRACT_MULTIPLIER 1.0 // G26 Q (retraction) used by default between mesh test elements.
#endif
@@ -1405,12 +1606,16 @@
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
+ //#define UBL_HILBERT_CURVE // Use Hilbert distribution for less travel when probing multiple points
+
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
//#define UBL_Z_RAISE_WHEN_OFF_MESH 2.5 // When the nozzle is off the mesh, this value is used
// as the Z-Height correction value.
+ //#define UBL_MESH_WIZARD // Run several commands in a row to get a complete mesh
+
#elif ENABLED(MESH_BED_LEVELING)
//===========================================================================
@@ -1451,6 +1656,25 @@
#define LEVEL_CORNERS_VERIFY_RAISED // After adjustment triggers the probe, re-probe to verify
//#define LEVEL_CORNERS_AUDIO_FEEDBACK
#endif
+
+ /**
+ * Corner Leveling Order
+ *
+ * Set 2 or 4 points. When 2 points are given, the 3rd is the center of the opposite edge.
+ *
+ * LF Left-Front RF Right-Front
+ * LB Left-Back RB Right-Back
+ *
+ * Examples:
+ *
+ * Default {LF,RB,LB,RF} {LF,RF} {LB,LF}
+ * LB --------- RB LB --------- RB LB --------- RB LB --------- RB
+ * | 4 3 | | 3 2 | | <3> | | 1 |
+ * | | | | | | | <3>|
+ * | 1 2 | | 1 4 | | 1 2 | | 2 |
+ * LF --------- RF LF --------- RF LF --------- RF LF --------- RF
+ */
+ #define LEVEL_CORNERS_LEVELING_ORDER { LF, RF, RB, LB }
#endif
/**
@@ -1469,6 +1693,9 @@
//#define MANUAL_X_HOME_POS 0
//#define MANUAL_Y_HOME_POS 0
//#define MANUAL_Z_HOME_POS 0
+//#define MANUAL_I_HOME_POS 0
+//#define MANUAL_J_HOME_POS 0
+//#define MANUAL_K_HOME_POS 0
// Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area.
//
@@ -1594,15 +1821,19 @@
// @section temperature
-// Preheat Constants
+//
+// Preheat Constants - Up to 5 are supported without changes
+//
#define PREHEAT_1_LABEL "PLA"
#define PREHEAT_1_TEMP_HOTEND 180
#define PREHEAT_1_TEMP_BED 70
+#define PREHEAT_1_TEMP_CHAMBER 35
#define PREHEAT_1_FAN_SPEED 0 // Value from 0 to 255
#define PREHEAT_2_LABEL "ABS"
#define PREHEAT_2_TEMP_HOTEND 240
#define PREHEAT_2_TEMP_BED 110
+#define PREHEAT_2_TEMP_CHAMBER 35
#define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255
/**
@@ -1707,11 +1938,20 @@
/**
* Print Job Timer
*
- * Automatically start and stop the print job timer on M104/M109/M190.
+ * Automatically start and stop the print job timer on M104/M109/M140/M190/M141/M191.
+ * The print job timer will only be stopped if the bed/chamber target temp is
+ * below BED_MINTEMP/CHAMBER_MINTEMP.
*
- * M104 (hotend, no wait) - high temp = none, low temp = stop timer
- * M109 (hotend, wait) - high temp = start timer, low temp = stop timer
- * M190 (bed, wait) - high temp = start timer, low temp = none
+ * M104 (hotend, no wait) - high temp = none, low temp = stop timer
+ * M109 (hotend, wait) - high temp = start timer, low temp = stop timer
+ * M140 (bed, no wait) - high temp = none, low temp = stop timer
+ * M190 (bed, wait) - high temp = start timer, low temp = none
+ * M141 (chamber, no wait) - high temp = none, low temp = stop timer
+ * M191 (chamber, wait) - high temp = start timer, low temp = none
+ *
+ * For M104/M109, high temp is anything over EXTRUDE_MINTEMP / 2.
+ * For M140/M190, high temp is anything over BED_MINTEMP.
+ * For M141/M191, high temp is anything over CHAMBER_MINTEMP.
*
* The timer can also be controlled with the following commands:
*
@@ -1734,6 +1974,9 @@
* View the current statistics with M78.
*/
//#define PRINTCOUNTER
+#if ENABLED(PRINTCOUNTER)
+ #define PRINTCOUNTER_SAVE_INTERVAL 60 // (minutes) EEPROM save interval during print
+#endif
/**
* Password
@@ -1778,9 +2021,9 @@
* Select the language to display on the LCD. These languages are available:
*
* en, an, bg, ca, cz, da, de, el, el_gr, es, eu, fi, fr, gl, hr, hu, it,
- * jp_kana, ko_KR, nl, pl, pt, pt_br, ro, ru, sk, tr, uk, vi, zh_CN, zh_TW, test
+ * jp_kana, ko_KR, nl, pl, pt, pt_br, ro, ru, sk, sv, tr, uk, vi, zh_CN, zh_TW
*
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cz':'Czech', 'da':'Danish', 'de':'German', 'el':'Greek', 'el_gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'hu':'Hungarian', 'it':'Italian', 'jp_kana':'Japanese', 'ko_KR':'Korean (South Korea)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt_br':'Portuguese (Brazilian)', 'ro':'Romanian', 'ru':'Russian', 'sk':'Slovak', 'tr':'Turkish', 'uk':'Ukrainian', 'vi':'Vietnamese', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Traditional)', 'test':'TEST' }
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cz':'Czech', 'da':'Danish', 'de':'German', 'el':'Greek', 'el_gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'hu':'Hungarian', 'it':'Italian', 'jp_kana':'Japanese', 'ko_KR':'Korean (South Korea)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt_br':'Portuguese (Brazilian)', 'ro':'Romanian', 'ru':'Russian', 'sk':'Slovak', 'sv':'Swedish', 'tr':'Turkish', 'uk':'Ukrainian', 'vi':'Vietnamese', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Traditional)' }
*/
#define LCD_LANGUAGE en
@@ -1924,6 +2167,14 @@
//
//#define REPRAP_DISCOUNT_SMART_CONTROLLER
+//
+// GT2560 (YHCB2004) LCD Display
+//
+// Requires Testato, Koepel softwarewire library and
+// Andriy Golovnya's LiquidCrystal_AIP31068 library.
+//
+//#define YHCB2004
+
//
// Original RADDS LCD Display+Encoder+SDCardReader
// http://doku.radds.org/dokumentation/lcd-display/
@@ -2074,6 +2325,11 @@
//
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
+//
+// K.3D Full Graphic Smart Controller
+//
+//#define K3D_FULL_GRAPHIC_SMART_CONTROLLER
+
//
// ReprapWorld Graphical LCD
// https://reprapworld.com/?products_details&products_id/1218
@@ -2139,7 +2395,8 @@
// MKS LCD12864A/B with graphic controller and SD support. Follows MKS_MINI_12864 pinout.
// https://www.aliexpress.com/item/33018110072.html
//
-//#define MKS_LCD12864
+//#define MKS_LCD12864A
+//#define MKS_LCD12864B
//
// FYSETC variant of the MINI12864 graphic controller with SD support
@@ -2211,7 +2468,7 @@
//#define OLED_PANEL_TINYBOY2
//
-// MKS OLED 1.3" 128×64 FULL GRAPHICS CONTROLLER
+// MKS OLED 1.3" 128×64 Full Graphics Controller
// https://reprap.org/wiki/MKS_12864OLED
//
// Tiny, but very sharp OLED display
@@ -2220,7 +2477,7 @@
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
//
-// Zonestar OLED 128×64 FULL GRAPHICS CONTROLLER
+// Zonestar OLED 128×64 Full Graphics Controller
//
//#define ZONESTAR_12864LCD // Graphical (DOGM) with ST7920 controller
//#define ZONESTAR_12864OLED // 1.3" OLED with SH1106 controller (default)
@@ -2237,10 +2494,15 @@
//#define OVERLORD_OLED
//
-// FYSETC OLED 2.42" 128×64 FULL GRAPHICS CONTROLLER with WS2812 RGB
+// FYSETC OLED 2.42" 128×64 Full Graphics Controller with WS2812 RGB
// Where to find : https://www.aliexpress.com/item/4000345255731.html
//#define FYSETC_242_OLED_12864 // Uses the SSD1309 controller
+//
+// K.3D SSD1309 OLED 2.42" 128×64 Full Graphics Controller
+//
+//#define K3D_242_OLED_CONTROLLER // Software SPI
+
//=============================================================================
//========================== Extensible UI Displays ===========================
//=============================================================================
@@ -2254,6 +2516,11 @@
//#define DGUS_LCD_UI_FYSETC
//#define DGUS_LCD_UI_HIPRECY
+//#define DGUS_LCD_UI_MKS
+#if ENABLED(DGUS_LCD_UI_MKS)
+ #define USE_MKS_GREEN_UI
+#endif
+
//
// Touch-screen LCD for Malyan M200/M300 printers
//
@@ -2278,6 +2545,14 @@
//#define ANYCUBIC_LCD_DEBUG
#endif
+//
+// 320x240 Nextion 2.8" serial TFT Resistive Touch Screen NX3224T028
+//
+//#define NEXTION_TFT
+#if ENABLED(NEXTION_TFT)
+ #define LCD_SERIAL_PORT 1 // Default is 1 for Nextion
+#endif
+
//
// Third-party or vendor-customized controller interfaces.
// Sources should be installed in 'src/lcd/extui'.
@@ -2363,6 +2638,11 @@
//
//#define ANET_ET5_TFT35
+//
+// 1024x600, 7", RGB Stock Display from BIQU-BX
+//
+//#define BIQU_BX_TFT70
+
//
// Generic TFT with detailed options
//
@@ -2395,6 +2675,10 @@
//#define TFT_COLOR_UI
//#define TFT_LVGL_UI
+#if ENABLED(TFT_LVGL_UI)
+ //#define MKS_WIFI_MODULE // MKS WiFi module
+#endif
+
/**
* TFT Rotation. Set to one of the following values:
*
@@ -2415,7 +2699,7 @@
//#define DWIN_CREALITY_LCD
//
-// ADS7843/XPT2046 ADC Touchscreen such as ILI9341 2.8
+// Touch Screen Settings
//
//#define TOUCH_SCREEN
#if ENABLED(TOUCH_SCREEN)
@@ -2430,6 +2714,10 @@
//#define TOUCH_OFFSET_Y 257
//#define TOUCH_ORIENTATION TOUCH_LANDSCAPE
+ #if BOTH(TOUCH_SCREEN_CALIBRATION, EEPROM_SETTINGS)
+ #define TOUCH_CALIBRATION_AUTO_SAVE // Auto save successful calibration values to EEPROM
+ #endif
+
#if ENABLED(TFT_COLOR_UI)
//#define SINGLE_TOUCH_NAVIGATION
#endif
@@ -2525,7 +2813,7 @@
//#define NEOPIXEL_LED
#if ENABLED(NEOPIXEL_LED)
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
- #define NEOPIXEL_PIN 4 // LED driving pin
+ //#define NEOPIXEL_PIN 4 // LED driving pin
//#define NEOPIXEL2_TYPE NEOPIXEL_TYPE
//#define NEOPIXEL2_PIN 5
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip. (Longest strip when NEOPIXEL2_SEPARATE is disabled.)
@@ -2543,9 +2831,11 @@
//#define NEOPIXEL2_INSERIES // Default behavior is NeoPixel 2 in parallel
#endif
- // Use a single NeoPixel LED for static (background) lighting
- //#define NEOPIXEL_BKGD_LED_INDEX 0 // Index of the LED to use
- //#define NEOPIXEL_BKGD_COLOR { 255, 255, 255, 0 } // R, G, B, W
+ // Use some of the NeoPixel LEDs for static (background) lighting
+ //#define NEOPIXEL_BKGD_INDEX_FIRST 0 // Index of the first background LED
+ //#define NEOPIXEL_BKGD_INDEX_LAST 5 // Index of the last background LED
+ //#define NEOPIXEL_BKGD_COLOR { 255, 255, 255, 0 } // R, G, B, W
+ //#define NEOPIXEL_BKGD_ALWAYS_ON // Keep the backlight on when other NeoPixels are off
#endif
/**
diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h
index 7f33e3b3d0d0..7b642cc3556d 100644
--- a/Marlin/Configuration_adv.h
+++ b/Marlin/Configuration_adv.h
@@ -30,7 +30,7 @@
*
* Basic settings can be found in Configuration.h
*/
-#define CONFIGURATION_ADV_H_VERSION 020008
+#define CONFIGURATION_ADV_H_VERSION 02000900
//===========================================================================
//============================= Thermal Settings ============================
@@ -113,6 +113,24 @@
#define CHAMBER_BETA 3950 // Beta value
#endif
+#if TEMP_SENSOR_COOLER == 1000
+ #define COOLER_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor
+ #define COOLER_RESISTANCE_25C_OHMS 100000 // Resistance at 25C
+ #define COOLER_BETA 3950 // Beta value
+#endif
+
+#if TEMP_SENSOR_PROBE == 1000
+ #define PROBE_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor
+ #define PROBE_RESISTANCE_25C_OHMS 100000 // Resistance at 25C
+ #define PROBE_BETA 3950 // Beta value
+#endif
+
+#if TEMP_SENSOR_REDUNDANT == 1000
+ #define REDUNDANT_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor
+ #define REDUNDANT_RESISTANCE_25C_OHMS 100000 // Resistance at 25C
+ #define REDUNDANT_BETA 3950 // Beta value
+#endif
+
//
// Hephestos 2 24V heated bed upgrade kit.
// https://store.bq.com/en/heated-bed-kit-hephestos2
@@ -137,17 +155,21 @@
//
// Heated Chamber options
//
+#if DISABLED(PIDTEMPCHAMBER)
+ #define CHAMBER_CHECK_INTERVAL 5000 // (ms) Interval between checks in bang-bang control
+ #if ENABLED(CHAMBER_LIMIT_SWITCHING)
+ #define CHAMBER_HYSTERESIS 2 // (°C) Only set the relevant heater state when ABS(T-target) > CHAMBER_HYSTERESIS
+ #endif
+#endif
+
#if TEMP_SENSOR_CHAMBER
- #define CHAMBER_MINTEMP 5
- #define CHAMBER_MAXTEMP 60
- #define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
- //#define CHAMBER_LIMIT_SWITCHING
- //#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin
+ //#define HEATER_CHAMBER_PIN P2_04 // Required heater on/off pin (example: SKR 1.4 Turbo HE1 plug)
//#define HEATER_CHAMBER_INVERTING false
+ //#define FAN1_PIN -1 // Remove the fan signal on pin P2_04 (example: SKR 1.4 Turbo HE1 plug)
//#define CHAMBER_FAN // Enable a fan on the chamber
#if ENABLED(CHAMBER_FAN)
- #define CHAMBER_FAN_MODE 2 // Fan control mode: 0=Static; 1=Linear increase when temp is higher than target; 2=V-shaped curve.
+ #define CHAMBER_FAN_MODE 2 // Fan control mode: 0=Static; 1=Linear increase when temp is higher than target; 2=V-shaped curve; 3=similar to 1 but fan is always on.
#if CHAMBER_FAN_MODE == 0
#define CHAMBER_FAN_BASE 255 // Chamber fan PWM (0-255)
#elif CHAMBER_FAN_MODE == 1
@@ -156,6 +178,9 @@
#elif CHAMBER_FAN_MODE == 2
#define CHAMBER_FAN_BASE 128 // Minimum chamber fan PWM (0-255)
#define CHAMBER_FAN_FACTOR 25 // PWM increase per °C difference from target
+ #elif CHAMBER_FAN_MODE == 3
+ #define CHAMBER_FAN_BASE 128 // Base chamber fan PWM (0-255)
+ #define CHAMBER_FAN_FACTOR 25 // PWM increase per °C above target
#endif
#endif
@@ -163,12 +188,45 @@
#if ENABLED(CHAMBER_VENT)
#define CHAMBER_VENT_SERVO_NR 1 // Index of the vent servo
#define HIGH_EXCESS_HEAT_LIMIT 5 // How much above target temp to consider there is excess heat in the chamber
- #define LOW_EXCESS_HEAT_LIMIT 3
+ #define LOW_EXCESS_HEAT_LIMIT 3
#define MIN_COOLING_SLOPE_TIME_CHAMBER_VENT 20
#define MIN_COOLING_SLOPE_DEG_CHAMBER_VENT 1.5
#endif
#endif
+//
+// Laser Cooler options
+//
+#if TEMP_SENSOR_COOLER
+ #define COOLER_MINTEMP 8 // (°C)
+ #define COOLER_MAXTEMP 26 // (°C)
+ #define COOLER_DEFAULT_TEMP 16 // (°C)
+ #define TEMP_COOLER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target
+ #define COOLER_PIN 8 // Laser cooler on/off pin used to control power to the cooling element (e.g., TEC, External chiller via relay)
+ #define COOLER_INVERTING false
+ #define TEMP_COOLER_PIN 15 // Laser/Cooler temperature sensor pin. ADC is required.
+ #define COOLER_FAN // Enable a fan on the cooler, Fan# 0,1,2,3 etc.
+ #define COOLER_FAN_INDEX 0 // FAN number 0, 1, 2 etc. e.g.
+ #if ENABLED(COOLER_FAN)
+ #define COOLER_FAN_BASE 100 // Base Cooler fan PWM (0-255); turns on when Cooler temperature is above the target
+ #define COOLER_FAN_FACTOR 25 // PWM increase per °C above target
+ #endif
+#endif
+
+//
+// Laser Coolant Flow Meter
+//
+//#define LASER_COOLANT_FLOW_METER
+#if ENABLED(LASER_COOLANT_FLOW_METER)
+ #define FLOWMETER_PIN 20 // Requires an external interrupt-enabled pin (e.g., RAMPS 2,3,18,19,20,21)
+ #define FLOWMETER_PPL 5880 // (pulses/liter) Flow meter pulses-per-liter on the input pin
+ #define FLOWMETER_INTERVAL 1000 // (ms) Flow rate calculation interval in milliseconds
+ #define FLOWMETER_SAFETY // Prevent running the laser without the minimum flow rate set below
+ #if ENABLED(FLOWMETER_SAFETY)
+ #define FLOWMETER_MIN_LITERS_PER_MINUTE 1.5 // (liters/min) Minimum flow required when enabled
+ #endif
+#endif
+
/**
* Thermal Protection provides additional protection to your printer from damage
* and fire. Marlin always includes safe min and max temperature ranges which
@@ -206,7 +264,7 @@
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
* below 2.
*/
- #define WATCH_TEMP_PERIOD 20 // Seconds
+ #define WATCH_TEMP_PERIOD 20 // Seconds
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
#endif
@@ -238,6 +296,20 @@
#define WATCH_CHAMBER_TEMP_INCREASE 2 // Degrees Celsius
#endif
+/**
+ * Thermal Protection parameters for the laser cooler.
+ */
+#if ENABLED(THERMAL_PROTECTION_COOLER)
+ #define THERMAL_PROTECTION_COOLER_PERIOD 10 // Seconds
+ #define THERMAL_PROTECTION_COOLER_HYSTERESIS 3 // Degrees Celsius
+
+ /**
+ * Laser cooling watch settings (M143/M193).
+ */
+ #define WATCH_COOLER_TEMP_PERIOD 60 // Seconds
+ #define WATCH_COOLER_TEMP_INCREASE 3 // Degrees Celsius
+#endif
+
#if ENABLED(PIDTEMP)
// Add an experimental additional term to the heater power, proportional to the extrusion speed.
// A well-chosen Kc value should add just enough power to melt the increased material volume.
@@ -284,8 +356,8 @@
// DEFAULT_Kf and PID_FAN_SCALING_LIN_FACTOR are calculated accordingly.
#define PID_FAN_SCALING_AT_FULL_SPEED 13.0 //=PID_FAN_SCALING_LIN_FACTOR*255+DEFAULT_Kf
- #define PID_FAN_SCALING_AT_MIN_SPEED 6.0 //=PID_FAN_SCALING_LIN_FACTOR*PID_FAN_SCALING_MIN_SPEED+DEFAULT_Kf
- #define PID_FAN_SCALING_MIN_SPEED 10.0 // Minimum fan speed at which to enable PID_FAN_SCALING
+ #define PID_FAN_SCALING_AT_MIN_SPEED 6.0 //=PID_FAN_SCALING_LIN_FACTOR*PID_FAN_SCALING_MIN_SPEED+DEFAULT_Kf
+ #define PID_FAN_SCALING_MIN_SPEED 10.0 // Minimum fan speed at which to enable PID_FAN_SCALING
#define DEFAULT_Kf (255.0*PID_FAN_SCALING_AT_MIN_SPEED-PID_FAN_SCALING_AT_FULL_SPEED*PID_FAN_SCALING_MIN_SPEED)/(255.0-PID_FAN_SCALING_MIN_SPEED)
#define PID_FAN_SCALING_LIN_FACTOR (PID_FAN_SCALING_AT_FULL_SPEED-DEFAULT_Kf)/255.0
@@ -331,7 +403,7 @@
* High Temperature Thermistor Support
*
* Thermistors able to support high temperature tend to have a hard time getting
- * good readings at room and lower temperatures. This means HEATER_X_RAW_LO_TEMP
+ * good readings at room and lower temperatures. This means TEMP_SENSOR_X_RAW_LO_TEMP
* will probably be caught when the heating element first turns on during the
* preheating process, which will trigger a min_temp_error as a safety measure
* and force stop everything.
@@ -460,6 +532,11 @@
//#define USE_OCR2A_AS_TOP
#endif
+/**
+ * Use one of the PWM fans as a redundant part-cooling fan
+ */
+//#define REDUNDANT_PART_COOLING_FAN 2 // Index of the fan to sync with FAN 0.
+
// @section extruder
/**
@@ -483,11 +560,15 @@
#define E6_AUTO_FAN_PIN -1
#define E7_AUTO_FAN_PIN -1
#define CHAMBER_AUTO_FAN_PIN -1
+#define COOLER_AUTO_FAN_PIN -1
+#define COOLER_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // 255 == full speed
#define CHAMBER_AUTO_FAN_TEMPERATURE 30
#define CHAMBER_AUTO_FAN_SPEED 255
+#define COOLER_AUTO_FAN_TEMPERATURE 18
+#define COOLER_AUTO_FAN_SPEED 255
/**
* Part-Cooling Fan Multiplexer
@@ -509,12 +590,17 @@
#define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
- //#define CASE_LIGHT_MAX_PWM 128 // Limit pwm
- //#define CASE_LIGHT_MENU // Add Case Light options to the LCD menu
//#define CASE_LIGHT_NO_BRIGHTNESS // Disable brightness control. Enable for non-PWM lighting.
- //#define CASE_LIGHT_USE_NEOPIXEL // Use NeoPixel LED as case light, requires NEOPIXEL_LED.
- #if ENABLED(CASE_LIGHT_USE_NEOPIXEL)
- #define CASE_LIGHT_NEOPIXEL_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White }
+ //#define CASE_LIGHT_MAX_PWM 128 // Limit PWM duty cycle (0-255)
+ //#define CASE_LIGHT_MENU // Add Case Light options to the LCD menu
+ #if ENABLED(NEOPIXEL_LED)
+ //#define CASE_LIGHT_USE_NEOPIXEL // Use NeoPixel LED as case light
+ #endif
+ #if EITHER(RGB_LED, RGBW_LED)
+ //#define CASE_LIGHT_USE_RGB_LED // Use RGB / RGBW LED as case light
+ #endif
+ #if EITHER(CASE_LIGHT_USE_NEOPIXEL, CASE_LIGHT_USE_RGB_LED)
+ #define CASE_LIGHT_DEFAULT_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White }
#endif
#endif
@@ -596,6 +682,12 @@
#endif
#endif
+// Drive the E axis with two synchronized steppers
+//#define E_DUAL_STEPPER_DRIVERS
+#if ENABLED(E_DUAL_STEPPER_DRIVERS)
+ //#define INVERT_E1_VS_E0_DIR // Enable if the E motors need opposite DIR states
+#endif
+
/**
* Dual X Carriage
*
@@ -659,7 +751,7 @@
* the position of the toolhead relative to the workspace.
*/
-//#define SENSORLESS_BACKOFF_MM { 2, 2 } // (mm) Backoff from endstops before sensorless homing
+//#define SENSORLESS_BACKOFF_MM { 2, 2, 0 } // (mm) Backoff from endstops before sensorless homing
#define HOMING_BUMP_MM { 5, 5, 2 } // (mm) Backoff from endstops after first bump
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
@@ -730,8 +822,8 @@
/**
* Use "HIGH SPEED" mode for probing.
* Danger: Disable if your probe sometimes fails. Only suitable for stable well-adjusted systems.
- * This feature was designed for Delta's with very fast Z moves however higher speed cartesians may function
- * If the machine cannot raise the probe fast enough after a trigger, it may enter a fault state.
+ * This feature was designed for Deltabots with very fast Z moves; however, higher speed Cartesians
+ * might be able to use it. If the machine can't raise Z fast enough the BLTouch may go into ALARM.
*/
//#define BLTOUCH_HS_MODE
@@ -843,6 +935,9 @@
#define INVERT_X_STEP_PIN false
#define INVERT_Y_STEP_PIN false
#define INVERT_Z_STEP_PIN false
+#define INVERT_I_STEP_PIN false
+#define INVERT_J_STEP_PIN false
+#define INVERT_K_STEP_PIN false
#define INVERT_E_STEP_PIN false
/**
@@ -854,11 +949,11 @@
#define DISABLE_INACTIVE_X true
#define DISABLE_INACTIVE_Y true
#define DISABLE_INACTIVE_Z true // Set 'false' if the nozzle could fall onto your printed part!
+#define DISABLE_INACTIVE_I true
+#define DISABLE_INACTIVE_J true
+#define DISABLE_INACTIVE_K true
#define DISABLE_INACTIVE_E true
-// If the Nozzle or Bed falls when the Z stepper is disabled, set its resting position here.
-//#define Z_AFTER_DEACTIVATE Z_HOME_POS
-
// Default Minimum Feedrates for printing and travel moves
#define DEFAULT_MINIMUMFEEDRATE 0.0 // (mm/s) Minimum feedrate. Set with M205 S.
#define DEFAULT_MINTRAVELFEEDRATE 0.0 // (mm/s) Minimum travel feedrate. Set with M205 T.
@@ -897,9 +992,12 @@
#if ENABLED(BACKLASH_COMPENSATION)
// Define values for backlash distance and correction.
// If BACKLASH_GCODE is enabled these values are the defaults.
- #define BACKLASH_DISTANCE_MM { 0, 0, 0 } // (mm)
+ #define BACKLASH_DISTANCE_MM { 0, 0, 0 } // (mm) One value for each linear axis
#define BACKLASH_CORRECTION 0.0 // 0.0 = no correction; 1.0 = full correction
+ // Add steps for motor direction changes on CORE kinematics
+ //#define CORE_BACKLASH
+
// Set BACKLASH_SMOOTHING_MM to spread backlash correction over multiple segments
// to reduce print artifacts. (Enabling this is costly in memory and computation!)
//#define BACKLASH_SMOOTHING_MM 3 // (mm)
@@ -917,7 +1015,7 @@
// increments while checking for the contact to be broken.
#define BACKLASH_MEASUREMENT_LIMIT 0.5 // (mm)
#define BACKLASH_MEASUREMENT_RESOLUTION 0.005 // (mm)
- #define BACKLASH_MEASUREMENT_FEEDRATE Z_PROBE_SPEED_SLOW // (mm/min)
+ #define BACKLASH_MEASUREMENT_FEEDRATE Z_PROBE_FEEDRATE_SLOW // (mm/min)
#endif
#endif
#endif
@@ -965,6 +1063,13 @@
#define CALIBRATION_MEASURE_LEFT
#define CALIBRATION_MEASURE_BACK
+ //#define CALIBRATION_MEASURE_IMIN
+ //#define CALIBRATION_MEASURE_IMAX
+ //#define CALIBRATION_MEASURE_JMIN
+ //#define CALIBRATION_MEASURE_JMAX
+ //#define CALIBRATION_MEASURE_KMIN
+ //#define CALIBRATION_MEASURE_KMAX
+
// Probing at the exact top center only works if the center is flat. If
// probing on a screwhead or hollow washer, probe near the edges.
//#define CALIBRATION_MEASURE_AT_TOP_EDGES
@@ -1137,6 +1242,9 @@
#endif
#endif
+ // Insert a menu for preheating at the top level to allow for quick access
+ //#define PREHEAT_SHORTCUT_MENU_ITEM
+
#endif // HAS_LCD_MENU
#if HAS_DISPLAY
@@ -1223,6 +1331,8 @@
//#define BROWSE_MEDIA_ON_INSERT // Open the file browser when media is inserted
+ //#define MEDIA_MENU_AT_TOP // Force the media menu to be listed on the top of the main menu
+
#define EVENT_GCODE_SD_ABORT "G28XY" // G-code to run on SD Abort Print (e.g., "G28XY" or "G27")
#if ENABLED(PRINTER_EVENT_LEDS)
@@ -1241,7 +1351,6 @@
#if ENABLED(POWER_LOSS_RECOVERY)
#define PLR_ENABLED_DEFAULT false // Power Loss Recovery enabled by default. (Set with 'M413 Sn' & M500)
//#define BACKUP_POWER_SUPPLY // Backup power / UPS to move the steppers on power loss
- //#define POWER_LOSS_RECOVER_ZHOME // Z homing is needed for proper recovery. 99.9% of the time this should be disabled!
//#define POWER_LOSS_ZRAISE 2 // (mm) Z axis raise on resume (on power loss with UPS)
//#define POWER_LOSS_PIN 44 // Pin to detect power loss. Set to -1 to disable default pin on boards without module.
//#define POWER_LOSS_STATE HIGH // State of pin indicating power loss
@@ -1253,6 +1362,12 @@
// Without a POWER_LOSS_PIN the following option helps reduce wear on the SD card,
// especially with "vase mode" printing. Set too high and vases cannot be continued.
#define POWER_LOSS_MIN_Z_CHANGE 0.05 // (mm) Minimum Z change before saving power-loss data
+
+ // Enable if Z homing is needed for proper recovery. 99.9% of the time this should be disabled!
+ //#define POWER_LOSS_RECOVER_ZHOME
+ #if ENABLED(POWER_LOSS_RECOVER_ZHOME)
+ //#define POWER_LOSS_ZHOME_POS { 0, 0 } // Safe XY position to home Z while avoiding objects on the bed
+ #endif
#endif
/**
@@ -1388,13 +1503,25 @@
* Set this option to one of the following (or the board's defaults apply):
*
* LCD - Use the SD drive in the external LCD controller.
- * ONBOARD - Use the SD drive on the control board. (No SD_DETECT_PIN. M21 to init.)
+ * ONBOARD - Use the SD drive on the control board.
* CUSTOM_CABLE - Use a custom cable to access the SD (as defined in a pins file).
*
* :[ 'LCD', 'ONBOARD', 'CUSTOM_CABLE' ]
*/
//#define SDCARD_CONNECTION LCD
+ // Enable if SD detect is rendered useless (e.g., by using an SD extender)
+ //#define NO_SD_DETECT
+
+ // Multiple volume support - EXPERIMENTAL.
+ //#define MULTI_VOLUME
+ #if ENABLED(MULTI_VOLUME)
+ #define VOLUME_SD_ONBOARD
+ #define VOLUME_USB_FLASH_DRIVE
+ #define DEFAULT_VOLUME SV_SD_ONBOARD
+ #define DEFAULT_SHARED_VOLUME SV_USB_FLASH_DRIVE
+ #endif
+
#endif // SDSUPPORT
/**
@@ -1472,6 +1599,8 @@
#define STATUS_BED_ANIM // Use a second bitmap to indicate bed heating
#define STATUS_CHAMBER_ANIM // Use a second bitmap to indicate chamber heating
//#define STATUS_CUTTER_ANIM // Use a second bitmap to indicate spindle / laser active
+ //#define STATUS_COOLER_ANIM // Use a second bitmap to indicate laser cooling
+ //#define STATUS_FLOWMETER_ANIM // Use multiple bitmaps to indicate coolant flow
//#define STATUS_ALT_BED_BITMAP // Use the alternative bed bitmap
//#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap
//#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames
@@ -1499,12 +1628,12 @@
#define DGUS_UPDATE_INTERVAL_MS 500 // (ms) Interval between automatic screen updates
- #if EITHER(DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY)
+ #if ANY(DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_MKS, DGUS_LCD_UI_HIPRECY)
#define DGUS_PRINT_FILENAME // Display the filename during printing
#define DGUS_PREHEAT_UI // Display a preheat screen during heatup
- #if ENABLED(DGUS_LCD_UI_FYSETC)
- //#define DGUS_UI_MOVE_DIS_OPTION // Disabled by default for UI_FYSETC
+ #if EITHER(DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_MKS)
+ //#define DGUS_UI_MOVE_DIS_OPTION // Disabled by default for FYSETC and MKS
#else
#define DGUS_UI_MOVE_DIS_OPTION // Enabled by default for UI_HIPRECY
#endif
@@ -1523,6 +1652,44 @@
#endif
#endif // HAS_DGUS_LCD
+//
+// Additional options for AnyCubic Chiron TFT displays
+//
+#if ENABLED(ANYCUBIC_LCD_CHIRON)
+ // By default the type of panel is automatically detected.
+ // Enable one of these options if you know the panel type.
+ //#define CHIRON_TFT_STANDARD
+ //#define CHIRON_TFT_NEW
+
+ // Enable the longer Anycubic powerup startup tune
+ //#define AC_DEFAULT_STARTUP_TUNE
+
+ /**
+ * Display Folders
+ * By default the file browser lists all G-code files (including those in subfolders) in a flat list.
+ * Enable this option to display a hierarchical file browser.
+ *
+ * NOTES:
+ * - Without this option it helps to enable SDCARD_SORT_ALPHA so files are sorted before/after folders.
+ * - When used with the "new" panel, folder names will also have '.gcode' appended to their names.
+ * This hack is currently required to force the panel to show folders.
+ */
+ #define AC_SD_FOLDER_VIEW
+#endif
+
+//
+// Specify additional languages for the UI. Default specified by LCD_LANGUAGE.
+//
+#if ANY(DOGLCD, TFT_COLOR_UI, TOUCH_UI_FTDI_EVE)
+ //#define LCD_LANGUAGE_2 fr
+ //#define LCD_LANGUAGE_3 de
+ //#define LCD_LANGUAGE_4 es
+ //#define LCD_LANGUAGE_5 it
+ #ifdef LCD_LANGUAGE_2
+ //#define LCD_LANGUAGE_AUTO_SAVE // Automatically save language to EEPROM on change
+ #endif
+#endif
+
//
// Touch UI for the FTDI Embedded Video Engine (EVE)
//
@@ -1534,6 +1701,8 @@
//#define LCD_HAOYU_FT810CB // Haoyu with 5" (800x480)
//#define LCD_ALEPHOBJECTS_CLCD_UI // Aleph Objects Color LCD UI
//#define LCD_FYSETC_TFT81050 // FYSETC with 5" (800x480)
+ //#define LCD_EVE3_50G // Matrix Orbital 5.0", 800x480, BT815
+ //#define LCD_EVE2_50G // Matrix Orbital 5.0", 800x480, FT813
// Correct the resolution if not using the stock TFT panel.
//#define TOUCH_UI_320x240
@@ -1598,13 +1767,6 @@
// Use a smaller font when labels don't fit buttons
#define TOUCH_UI_FIT_TEXT
- // Allow language selection from menu at run-time (otherwise use LCD_LANGUAGE)
- //#define LCD_LANGUAGE_1 en
- //#define LCD_LANGUAGE_2 fr
- //#define LCD_LANGUAGE_3 de
- //#define LCD_LANGUAGE_4 es
- //#define LCD_LANGUAGE_5 it
-
// Use a numeric passcode for "Screen lock" keypad.
// (recommended for smaller displays)
//#define TOUCH_UI_PASSCODE
@@ -1810,21 +1972,21 @@
//#define USE_TEMP_EXT_COMPENSATION
// Probe temperature calibration generates a table of values starting at PTC_SAMPLE_START
- // (e.g. 30), in steps of PTC_SAMPLE_RES (e.g. 5) with PTC_SAMPLE_COUNT (e.g. 10) samples.
+ // (e.g., 30), in steps of PTC_SAMPLE_RES (e.g., 5) with PTC_SAMPLE_COUNT (e.g., 10) samples.
- //#define PTC_SAMPLE_START 30.0f
- //#define PTC_SAMPLE_RES 5.0f
- //#define PTC_SAMPLE_COUNT 10U
+ //#define PTC_SAMPLE_START 30 // (°C)
+ //#define PTC_SAMPLE_RES 5 // (°C)
+ //#define PTC_SAMPLE_COUNT 10
// Bed temperature calibration builds a similar table.
- //#define BTC_SAMPLE_START 60.0f
- //#define BTC_SAMPLE_RES 5.0f
- //#define BTC_SAMPLE_COUNT 10U
+ //#define BTC_SAMPLE_START 60 // (°C)
+ //#define BTC_SAMPLE_RES 5 // (°C)
+ //#define BTC_SAMPLE_COUNT 10
// The temperature the probe should be at while taking measurements during bed temperature
// calibration.
- //#define BTC_PROBE_TEMP 30.0f
+ //#define BTC_PROBE_TEMP 30 // (°C)
// Height above Z=0.0f to raise the nozzle. Lowering this can help the probe to heat faster.
// Note: the Z=0.0f offset is determined by the probe offset which can be set using M851.
@@ -1833,7 +1995,7 @@
// Height to raise the Z-probe between heating and taking the next measurement. Some probes
// may fail to untrigger if they have been triggered for a long time, which can be solved by
// increasing the height the probe is raised to.
- //#define PTC_PROBE_RAISE 15U
+ //#define PTC_PROBE_RAISE 15
// If the probe is outside of the defined range, use linear extrapolation using the closest
// point and the PTC_LINEAR_EXTRAPOLATION'th next point. E.g. if set to 4 it will use data[0]
@@ -1948,7 +2110,7 @@
// @section motion
// The number of linear moves that can be in the planner at once.
-// The value of BLOCK_BUFFER_SIZE must be a power of 2 (e.g. 8, 16, 32)
+// The value of BLOCK_BUFFER_SIZE must be a power of 2 (e.g., 8, 16, 32)
#if BOTH(SDSUPPORT, DIRECT_STEPPING)
#define BLOCK_BUFFER_SIZE 8
#elif ENABLED(SDSUPPORT)
@@ -1984,9 +2146,6 @@
//#define SERIAL_XON_XOFF
#endif
-// Add M575 G-code to change the baud rate
-//#define BAUD_RATE_GCODE
-
#if ENABLED(SDSUPPORT)
// Enable this option to collect and display the maximum
// RX queue usage after transferring a file to SD.
@@ -1997,6 +2156,12 @@
//#define SERIAL_STATS_DROPPED_RX
#endif
+// Monitor RX buffer usage
+// Dump an error to the serial port if the serial receive buffer overflows.
+// If you see these errors, increase the RX_BUFFER_SIZE value.
+// Not supported on all platforms.
+//#define RX_BUFFER_MONITOR
+
/**
* Emergency Command Parser
*
@@ -2007,6 +2172,26 @@
*/
//#define EMERGENCY_PARSER
+/**
+ * Realtime Reporting (requires EMERGENCY_PARSER)
+ *
+ * - Report position and state of the machine (like Grbl).
+ * - Auto-report position during long moves.
+ * - Useful for CNC/LASER.
+ *
+ * Adds support for commands:
+ * S000 : Report State and Position while moving.
+ * P000 : Instant Pause / Hold while moving.
+ * R000 : Resume from Pause / Hold.
+ *
+ * - During Hold all Emergency Parser commands are available, as usual.
+ * - Enable NANODLP_Z_SYNC and NANODLP_ALL_AXIS for move command end-state reports.
+ */
+//#define REALTIME_REPORTING_COMMANDS
+#if ENABLED(REALTIME_REPORTING_COMMANDS)
+ //#define FULL_REPORT_TO_HOST_FEATURE // Auto-report the machine status like Grbl CNC
+#endif
+
// Bad Serial-connections can miss a received command by sending an 'ok'
// Therefore some clients abort after 30 seconds in a timeout.
// Some other clients start sending commands while receiving a 'wait'.
@@ -2050,21 +2235,21 @@
*/
//#define FWRETRACT
#if ENABLED(FWRETRACT)
- #define FWRETRACT_AUTORETRACT // Override slicer retractions
+ #define FWRETRACT_AUTORETRACT // Override slicer retractions
#if ENABLED(FWRETRACT_AUTORETRACT)
- #define MIN_AUTORETRACT 0.1 // (mm) Don't convert E moves under this length
- #define MAX_AUTORETRACT 10.0 // (mm) Don't convert E moves over this length
- #endif
- #define RETRACT_LENGTH 3 // (mm) Default retract length (positive value)
- #define RETRACT_LENGTH_SWAP 13 // (mm) Default swap retract length (positive value)
- #define RETRACT_FEEDRATE 45 // (mm/s) Default feedrate for retracting
- #define RETRACT_ZRAISE 0 // (mm) Default retract Z-raise
- #define RETRACT_RECOVER_LENGTH 0 // (mm) Default additional recover length (added to retract length on recover)
- #define RETRACT_RECOVER_LENGTH_SWAP 0 // (mm) Default additional swap recover length (added to retract length on recover from toolchange)
- #define RETRACT_RECOVER_FEEDRATE 8 // (mm/s) Default feedrate for recovering from retraction
- #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // (mm/s) Default feedrate for recovering from swap retraction
+ #define MIN_AUTORETRACT 0.1 // (mm) Don't convert E moves under this length
+ #define MAX_AUTORETRACT 10.0 // (mm) Don't convert E moves over this length
+ #endif
+ #define RETRACT_LENGTH 3 // (mm) Default retract length (positive value)
+ #define RETRACT_LENGTH_SWAP 13 // (mm) Default swap retract length (positive value)
+ #define RETRACT_FEEDRATE 45 // (mm/s) Default feedrate for retracting
+ #define RETRACT_ZRAISE 0 // (mm) Default retract Z-raise
+ #define RETRACT_RECOVER_LENGTH 0 // (mm) Default additional recover length (added to retract length on recover)
+ #define RETRACT_RECOVER_LENGTH_SWAP 0 // (mm) Default additional swap recover length (added to retract length on recover from toolchange)
+ #define RETRACT_RECOVER_FEEDRATE 8 // (mm/s) Default feedrate for recovering from retraction
+ #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // (mm/s) Default feedrate for recovering from swap retraction
#if ENABLED(MIXING_EXTRUDER)
- //#define RETRACT_SYNC_MIXING // Retract and restore all mixing steppers simultaneously
+ //#define RETRACT_SYNC_MIXING // Retract and restore all mixing steppers simultaneously
#endif
#endif
@@ -2081,6 +2266,19 @@
//#define EVENT_GCODE_AFTER_TOOLCHANGE "G12X" // Extra G-code to run after tool-change
#endif
+ /**
+ * Extra G-code to run while executing tool-change commands. Can be used to use an additional
+ * stepper motor (I axis, see option LINEAR_AXES in Configuration.h) to drive the tool-changer.
+ */
+ //#define EVENT_GCODE_TOOLCHANGE_T0 "G28 A\nG1 A0" // Extra G-code to run while executing tool-change command T0
+ //#define EVENT_GCODE_TOOLCHANGE_T1 "G1 A10" // Extra G-code to run while executing tool-change command T1
+
+ /**
+ * Tool Sensors detect when tools have been picked up or dropped.
+ * Requires the pins TOOL_SENSOR1_PIN, TOOL_SENSOR2_PIN, etc.
+ */
+ //#define TOOL_SENSOR
+
/**
* Retract and prime filament on tool-change to reduce
* ooze and stringing and to get cleaner transitions.
@@ -2139,14 +2337,15 @@
#endif // HAS_MULTI_EXTRUDER
/**
- * Advanced Pause
- * Experimental feature for filament change support and for parking the nozzle when paused.
- * Adds the GCode M600 for initiating filament change.
- * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle.
+ * Advanced Pause for Filament Change
+ * - Adds the G-code M600 Filament Change to initiate a filament change.
+ * - This feature is required for the default FILAMENT_RUNOUT_SCRIPT.
+ *
+ * Requirements:
+ * - For Filament Change parking enable and configure NOZZLE_PARK_FEATURE.
+ * - For user interaction enable an LCD display, HOST_PROMPT_SUPPORT, or EMERGENCY_PARSER.
*
- * Requires an LCD display.
- * Requires NOZZLE_PARK_FEATURE.
- * This feature is required for the default FILAMENT_RUNOUT_SCRIPT.
+ * Enable PARK_HEAD_ON_PAUSE to add the G-code M125 Pause and Park.
*/
//#define ADVANCED_PAUSE_FEATURE
#if ENABLED(ADVANCED_PAUSE_FEATURE)
@@ -2212,7 +2411,7 @@
#if AXIS_DRIVER_TYPE_X2(TMC26X)
#define X2_MAX_CURRENT 1000
#define X2_SENSE_RESISTOR 91
- #define X2_MICROSTEPS 16
+ #define X2_MICROSTEPS X_MICROSTEPS
#endif
#if AXIS_DRIVER_TYPE_Y(TMC26X)
@@ -2224,7 +2423,7 @@
#if AXIS_DRIVER_TYPE_Y2(TMC26X)
#define Y2_MAX_CURRENT 1000
#define Y2_SENSE_RESISTOR 91
- #define Y2_MICROSTEPS 16
+ #define Y2_MICROSTEPS Y_MICROSTEPS
#endif
#if AXIS_DRIVER_TYPE_Z(TMC26X)
@@ -2236,19 +2435,37 @@
#if AXIS_DRIVER_TYPE_Z2(TMC26X)
#define Z2_MAX_CURRENT 1000
#define Z2_SENSE_RESISTOR 91
- #define Z2_MICROSTEPS 16
+ #define Z2_MICROSTEPS Z_MICROSTEPS
#endif
#if AXIS_DRIVER_TYPE_Z3(TMC26X)
#define Z3_MAX_CURRENT 1000
#define Z3_SENSE_RESISTOR 91
- #define Z3_MICROSTEPS 16
+ #define Z3_MICROSTEPS Z_MICROSTEPS
#endif
#if AXIS_DRIVER_TYPE_Z4(TMC26X)
#define Z4_MAX_CURRENT 1000
#define Z4_SENSE_RESISTOR 91
- #define Z4_MICROSTEPS 16
+ #define Z4_MICROSTEPS Z_MICROSTEPS
+ #endif
+
+ #if AXIS_DRIVER_TYPE_I(TMC26X)
+ #define I_MAX_CURRENT 1000
+ #define I_SENSE_RESISTOR 91
+ #define I_MICROSTEPS 16
+ #endif
+
+ #if AXIS_DRIVER_TYPE_J(TMC26X)
+ #define J_MAX_CURRENT 1000
+ #define J_SENSE_RESISTOR 91
+ #define J_MICROSTEPS 16
+ #endif
+
+ #if AXIS_DRIVER_TYPE_K(TMC26X)
+ #define K_MAX_CURRENT 1000
+ #define K_SENSE_RESISTOR 91
+ #define K_MICROSTEPS 16
#endif
#if AXIS_DRIVER_TYPE_E0(TMC26X)
@@ -2260,43 +2477,43 @@
#if AXIS_DRIVER_TYPE_E1(TMC26X)
#define E1_MAX_CURRENT 1000
#define E1_SENSE_RESISTOR 91
- #define E1_MICROSTEPS 16
+ #define E1_MICROSTEPS E0_MICROSTEPS
#endif
#if AXIS_DRIVER_TYPE_E2(TMC26X)
#define E2_MAX_CURRENT 1000
#define E2_SENSE_RESISTOR 91
- #define E2_MICROSTEPS 16
+ #define E2_MICROSTEPS E0_MICROSTEPS
#endif
#if AXIS_DRIVER_TYPE_E3(TMC26X)
#define E3_MAX_CURRENT 1000
#define E3_SENSE_RESISTOR 91
- #define E3_MICROSTEPS 16
+ #define E3_MICROSTEPS E0_MICROSTEPS
#endif
#if AXIS_DRIVER_TYPE_E4(TMC26X)
#define E4_MAX_CURRENT 1000
#define E4_SENSE_RESISTOR 91
- #define E4_MICROSTEPS 16
+ #define E4_MICROSTEPS E0_MICROSTEPS
#endif
#if AXIS_DRIVER_TYPE_E5(TMC26X)
#define E5_MAX_CURRENT 1000
#define E5_SENSE_RESISTOR 91
- #define E5_MICROSTEPS 16
+ #define E5_MICROSTEPS E0_MICROSTEPS
#endif
#if AXIS_DRIVER_TYPE_E6(TMC26X)
#define E6_MAX_CURRENT 1000
#define E6_SENSE_RESISTOR 91
- #define E6_MICROSTEPS 16
+ #define E6_MICROSTEPS E0_MICROSTEPS
#endif
#if AXIS_DRIVER_TYPE_E7(TMC26X)
#define E7_MAX_CURRENT 1000
#define E7_SENSE_RESISTOR 91
- #define E7_MICROSTEPS 16
+ #define E7_MICROSTEPS E0_MICROSTEPS
#endif
#endif // TMC26X
@@ -2341,7 +2558,7 @@
#if AXIS_IS_TMC(X2)
#define X2_CURRENT 800
#define X2_CURRENT_HOME X2_CURRENT
- #define X2_MICROSTEPS 16
+ #define X2_MICROSTEPS X_MICROSTEPS
#define X2_RSENSE 0.11
#define X2_CHAIN_POS -1
//#define X2_INTERPOLATE true
@@ -2359,7 +2576,7 @@
#if AXIS_IS_TMC(Y2)
#define Y2_CURRENT 800
#define Y2_CURRENT_HOME Y2_CURRENT
- #define Y2_MICROSTEPS 16
+ #define Y2_MICROSTEPS Y_MICROSTEPS
#define Y2_RSENSE 0.11
#define Y2_CHAIN_POS -1
//#define Y2_INTERPOLATE true
@@ -2377,7 +2594,7 @@
#if AXIS_IS_TMC(Z2)
#define Z2_CURRENT 800
#define Z2_CURRENT_HOME Z2_CURRENT
- #define Z2_MICROSTEPS 16
+ #define Z2_MICROSTEPS Z_MICROSTEPS
#define Z2_RSENSE 0.11
#define Z2_CHAIN_POS -1
//#define Z2_INTERPOLATE true
@@ -2386,7 +2603,7 @@
#if AXIS_IS_TMC(Z3)
#define Z3_CURRENT 800
#define Z3_CURRENT_HOME Z3_CURRENT
- #define Z3_MICROSTEPS 16
+ #define Z3_MICROSTEPS Z_MICROSTEPS
#define Z3_RSENSE 0.11
#define Z3_CHAIN_POS -1
//#define Z3_INTERPOLATE true
@@ -2395,12 +2612,39 @@
#if AXIS_IS_TMC(Z4)
#define Z4_CURRENT 800
#define Z4_CURRENT_HOME Z4_CURRENT
- #define Z4_MICROSTEPS 16
+ #define Z4_MICROSTEPS Z_MICROSTEPS
#define Z4_RSENSE 0.11
#define Z4_CHAIN_POS -1
//#define Z4_INTERPOLATE true
#endif
+ #if AXIS_IS_TMC(I)
+ #define I_CURRENT 800
+ #define I_CURRENT_HOME I_CURRENT
+ #define I_MICROSTEPS 16
+ #define I_RSENSE 0.11
+ #define I_CHAIN_POS -1
+ //#define I_INTERPOLATE true
+ #endif
+
+ #if AXIS_IS_TMC(J)
+ #define J_CURRENT 800
+ #define J_CURRENT_HOME J_CURRENT
+ #define J_MICROSTEPS 16
+ #define J_RSENSE 0.11
+ #define J_CHAIN_POS -1
+ //#define J_INTERPOLATE true
+ #endif
+
+ #if AXIS_IS_TMC(K)
+ #define K_CURRENT 800
+ #define K_CURRENT_HOME K_CURRENT
+ #define K_MICROSTEPS 16
+ #define K_RSENSE 0.11
+ #define K_CHAIN_POS -1
+ //#define K_INTERPOLATE true
+ #endif
+
#if AXIS_IS_TMC(E0)
#define E0_CURRENT 800
#define E0_MICROSTEPS 16
@@ -2411,7 +2655,7 @@
#if AXIS_IS_TMC(E1)
#define E1_CURRENT 800
- #define E1_MICROSTEPS 16
+ #define E1_MICROSTEPS E0_MICROSTEPS
#define E1_RSENSE 0.11
#define E1_CHAIN_POS -1
//#define E1_INTERPOLATE true
@@ -2419,7 +2663,7 @@
#if AXIS_IS_TMC(E2)
#define E2_CURRENT 800
- #define E2_MICROSTEPS 16
+ #define E2_MICROSTEPS E0_MICROSTEPS
#define E2_RSENSE 0.11
#define E2_CHAIN_POS -1
//#define E2_INTERPOLATE true
@@ -2427,7 +2671,7 @@
#if AXIS_IS_TMC(E3)
#define E3_CURRENT 800
- #define E3_MICROSTEPS 16
+ #define E3_MICROSTEPS E0_MICROSTEPS
#define E3_RSENSE 0.11
#define E3_CHAIN_POS -1
//#define E3_INTERPOLATE true
@@ -2435,7 +2679,7 @@
#if AXIS_IS_TMC(E4)
#define E4_CURRENT 800
- #define E4_MICROSTEPS 16
+ #define E4_MICROSTEPS E0_MICROSTEPS
#define E4_RSENSE 0.11
#define E4_CHAIN_POS -1
//#define E4_INTERPOLATE true
@@ -2443,7 +2687,7 @@
#if AXIS_IS_TMC(E5)
#define E5_CURRENT 800
- #define E5_MICROSTEPS 16
+ #define E5_MICROSTEPS E0_MICROSTEPS
#define E5_RSENSE 0.11
#define E5_CHAIN_POS -1
//#define E5_INTERPOLATE true
@@ -2451,7 +2695,7 @@
#if AXIS_IS_TMC(E6)
#define E6_CURRENT 800
- #define E6_MICROSTEPS 16
+ #define E6_MICROSTEPS E0_MICROSTEPS
#define E6_RSENSE 0.11
#define E6_CHAIN_POS -1
//#define E6_INTERPOLATE true
@@ -2459,7 +2703,7 @@
#if AXIS_IS_TMC(E7)
#define E7_CURRENT 800
- #define E7_MICROSTEPS 16
+ #define E7_MICROSTEPS E0_MICROSTEPS
#define E7_RSENSE 0.11
#define E7_CHAIN_POS -1
//#define E7_INTERPOLATE true
@@ -2476,6 +2720,10 @@
//#define Y2_CS_PIN -1
//#define Z2_CS_PIN -1
//#define Z3_CS_PIN -1
+ //#define Z4_CS_PIN -1
+ //#define I_CS_PIN -1
+ //#define J_CS_PIN -1
+ //#define K_CS_PIN -1
//#define E0_CS_PIN -1
//#define E1_CS_PIN -1
//#define E2_CS_PIN -1
@@ -2515,6 +2763,9 @@
//#define Z2_SLAVE_ADDRESS 0
//#define Z3_SLAVE_ADDRESS 0
//#define Z4_SLAVE_ADDRESS 0
+ //#define I_SLAVE_ADDRESS 0
+ //#define J_SLAVE_ADDRESS 0
+ //#define K_SLAVE_ADDRESS 0
//#define E0_SLAVE_ADDRESS 0
//#define E1_SLAVE_ADDRESS 0
//#define E2_SLAVE_ADDRESS 0
@@ -2539,6 +2790,9 @@
*/
#define STEALTHCHOP_XY
#define STEALTHCHOP_Z
+ #define STEALTHCHOP_I
+ #define STEALTHCHOP_J
+ #define STEALTHCHOP_K
#define STEALTHCHOP_E
/**
@@ -2557,22 +2811,22 @@
* { , , hysteresis_start[1..8] }
*/
#define CHOPPER_TIMING CHOPPER_DEFAULT_12V // All axes (override below)
- //#define CHOPPER_TIMING_X CHOPPER_DEFAULT_12V // For X Axes (override below)
- //#define CHOPPER_TIMING_X2 CHOPPER_DEFAULT_12V
- //#define CHOPPER_TIMING_Y CHOPPER_DEFAULT_12V // For Y Axes (override below)
- //#define CHOPPER_TIMING_Y2 CHOPPER_DEFAULT_12V
- //#define CHOPPER_TIMING_Z CHOPPER_DEFAULT_12V // For Z Axes (override below)
- //#define CHOPPER_TIMING_Z2 CHOPPER_DEFAULT_12V
- //#define CHOPPER_TIMING_Z3 CHOPPER_DEFAULT_12V
- //#define CHOPPER_TIMING_Z4 CHOPPER_DEFAULT_12V
- //#define CHOPPER_TIMING_E CHOPPER_DEFAULT_12V // For Extruders (override below)
- //#define CHOPPER_TIMING_E1 CHOPPER_DEFAULT_12V
- //#define CHOPPER_TIMING_E2 CHOPPER_DEFAULT_12V
- //#define CHOPPER_TIMING_E3 CHOPPER_DEFAULT_12V
- //#define CHOPPER_TIMING_E4 CHOPPER_DEFAULT_12V
- //#define CHOPPER_TIMING_E5 CHOPPER_DEFAULT_12V
- //#define CHOPPER_TIMING_E6 CHOPPER_DEFAULT_12V
- //#define CHOPPER_TIMING_E7 CHOPPER_DEFAULT_12V
+ //#define CHOPPER_TIMING_X CHOPPER_TIMING // For X Axes (override below)
+ //#define CHOPPER_TIMING_X2 CHOPPER_TIMING_X
+ //#define CHOPPER_TIMING_Y CHOPPER_TIMING // For Y Axes (override below)
+ //#define CHOPPER_TIMING_Y2 CHOPPER_TIMING_Y
+ //#define CHOPPER_TIMING_Z CHOPPER_TIMING // For Z Axes (override below)
+ //#define CHOPPER_TIMING_Z2 CHOPPER_TIMING_Z
+ //#define CHOPPER_TIMING_Z3 CHOPPER_TIMING_Z
+ //#define CHOPPER_TIMING_Z4 CHOPPER_TIMING_Z
+ //#define CHOPPER_TIMING_E CHOPPER_TIMING // For Extruders (override below)
+ //#define CHOPPER_TIMING_E1 CHOPPER_TIMING_E
+ //#define CHOPPER_TIMING_E2 CHOPPER_TIMING_E
+ //#define CHOPPER_TIMING_E3 CHOPPER_TIMING_E
+ //#define CHOPPER_TIMING_E4 CHOPPER_TIMING_E
+ //#define CHOPPER_TIMING_E5 CHOPPER_TIMING_E
+ //#define CHOPPER_TIMING_E6 CHOPPER_TIMING_E
+ //#define CHOPPER_TIMING_E7 CHOPPER_TIMING_E
/**
* Monitor Trinamic drivers
@@ -2610,6 +2864,9 @@
#define Z2_HYBRID_THRESHOLD 3
#define Z3_HYBRID_THRESHOLD 3
#define Z4_HYBRID_THRESHOLD 3
+ #define I_HYBRID_THRESHOLD 3
+ #define J_HYBRID_THRESHOLD 3
+ #define K_HYBRID_THRESHOLD 3
#define E0_HYBRID_THRESHOLD 30
#define E1_HYBRID_THRESHOLD 30
#define E2_HYBRID_THRESHOLD 30
@@ -2656,6 +2913,9 @@
//#define Z2_STALL_SENSITIVITY Z_STALL_SENSITIVITY
//#define Z3_STALL_SENSITIVITY Z_STALL_SENSITIVITY
//#define Z4_STALL_SENSITIVITY Z_STALL_SENSITIVITY
+ //#define I_STALL_SENSITIVITY 8
+ //#define J_STALL_SENSITIVITY 8
+ //#define K_STALL_SENSITIVITY 8
//#define SPI_ENDSTOPS // TMC2130 only
//#define IMPROVE_HOMING_RELIABILITY
#endif
@@ -2680,7 +2940,7 @@
/**
* Enable M122 debugging command for TMC stepper drivers.
- * M122 S0/1 will enable continous reporting.
+ * M122 S0/1 will enable continuous reporting.
*/
//#define TMC_DEBUG
@@ -2734,138 +2994,165 @@
#endif
#if AXIS_IS_L64XX(X2)
- #define X2_MICROSTEPS 128
- #define X2_OVERCURRENT 2000
- #define X2_STALLCURRENT 1500
- #define X2_MAX_VOLTAGE 127
- #define X2_CHAIN_POS -1
- #define X2_SLEW_RATE 1
+ #define X2_MICROSTEPS X_MICROSTEPS
+ #define X2_OVERCURRENT 2000
+ #define X2_STALLCURRENT 1500
+ #define X2_MAX_VOLTAGE 127
+ #define X2_CHAIN_POS -1
+ #define X2_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(Y)
- #define Y_MICROSTEPS 128
- #define Y_OVERCURRENT 2000
- #define Y_STALLCURRENT 1500
- #define Y_MAX_VOLTAGE 127
- #define Y_CHAIN_POS -1
- #define Y_SLEW_RATE 1
+ #define Y_MICROSTEPS 128
+ #define Y_OVERCURRENT 2000
+ #define Y_STALLCURRENT 1500
+ #define Y_MAX_VOLTAGE 127
+ #define Y_CHAIN_POS -1
+ #define Y_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(Y2)
- #define Y2_MICROSTEPS 128
- #define Y2_OVERCURRENT 2000
- #define Y2_STALLCURRENT 1500
- #define Y2_MAX_VOLTAGE 127
- #define Y2_CHAIN_POS -1
- #define Y2_SLEW_RATE 1
+ #define Y2_MICROSTEPS Y_MICROSTEPS
+ #define Y2_OVERCURRENT 2000
+ #define Y2_STALLCURRENT 1500
+ #define Y2_MAX_VOLTAGE 127
+ #define Y2_CHAIN_POS -1
+ #define Y2_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(Z)
- #define Z_MICROSTEPS 128
- #define Z_OVERCURRENT 2000
- #define Z_STALLCURRENT 1500
- #define Z_MAX_VOLTAGE 127
- #define Z_CHAIN_POS -1
- #define Z_SLEW_RATE 1
+ #define Z_MICROSTEPS 128
+ #define Z_OVERCURRENT 2000
+ #define Z_STALLCURRENT 1500
+ #define Z_MAX_VOLTAGE 127
+ #define Z_CHAIN_POS -1
+ #define Z_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(Z2)
- #define Z2_MICROSTEPS 128
- #define Z2_OVERCURRENT 2000
- #define Z2_STALLCURRENT 1500
- #define Z2_MAX_VOLTAGE 127
- #define Z2_CHAIN_POS -1
- #define Z2_SLEW_RATE 1
+ #define Z2_MICROSTEPS Z_MICROSTEPS
+ #define Z2_OVERCURRENT 2000
+ #define Z2_STALLCURRENT 1500
+ #define Z2_MAX_VOLTAGE 127
+ #define Z2_CHAIN_POS -1
+ #define Z2_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(Z3)
- #define Z3_MICROSTEPS 128
- #define Z3_OVERCURRENT 2000
- #define Z3_STALLCURRENT 1500
- #define Z3_MAX_VOLTAGE 127
- #define Z3_CHAIN_POS -1
- #define Z3_SLEW_RATE 1
+ #define Z3_MICROSTEPS Z_MICROSTEPS
+ #define Z3_OVERCURRENT 2000
+ #define Z3_STALLCURRENT 1500
+ #define Z3_MAX_VOLTAGE 127
+ #define Z3_CHAIN_POS -1
+ #define Z3_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(Z4)
- #define Z4_MICROSTEPS 128
- #define Z4_OVERCURRENT 2000
- #define Z4_STALLCURRENT 1500
- #define Z4_MAX_VOLTAGE 127
- #define Z4_CHAIN_POS -1
- #define Z4_SLEW_RATE 1
+ #define Z4_MICROSTEPS Z_MICROSTEPS
+ #define Z4_OVERCURRENT 2000
+ #define Z4_STALLCURRENT 1500
+ #define Z4_MAX_VOLTAGE 127
+ #define Z4_CHAIN_POS -1
+ #define Z4_SLEW_RATE 1
+ #endif
+
+ #if AXIS_DRIVER_TYPE_I(L6470)
+ #define I_MICROSTEPS 128
+ #define I_OVERCURRENT 2000
+ #define I_STALLCURRENT 1500
+ #define I_MAX_VOLTAGE 127
+ #define I_CHAIN_POS -1
+ #define I_SLEW_RATE 1
+ #endif
+
+ #if AXIS_DRIVER_TYPE_J(L6470)
+ #define J_MICROSTEPS 128
+ #define J_OVERCURRENT 2000
+ #define J_STALLCURRENT 1500
+ #define J_MAX_VOLTAGE 127
+ #define J_CHAIN_POS -1
+ #define J_SLEW_RATE 1
+ #endif
+
+ #if AXIS_DRIVER_TYPE_K(L6470)
+ #define K_MICROSTEPS 128
+ #define K_OVERCURRENT 2000
+ #define K_STALLCURRENT 1500
+ #define K_MAX_VOLTAGE 127
+ #define K_CHAIN_POS -1
+ #define K_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(E0)
- #define E0_MICROSTEPS 128
- #define E0_OVERCURRENT 2000
- #define E0_STALLCURRENT 1500
- #define E0_MAX_VOLTAGE 127
- #define E0_CHAIN_POS -1
- #define E0_SLEW_RATE 1
+ #define E0_MICROSTEPS 128
+ #define E0_OVERCURRENT 2000
+ #define E0_STALLCURRENT 1500
+ #define E0_MAX_VOLTAGE 127
+ #define E0_CHAIN_POS -1
+ #define E0_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(E1)
- #define E1_MICROSTEPS 128
- #define E1_OVERCURRENT 2000
- #define E1_STALLCURRENT 1500
- #define E1_MAX_VOLTAGE 127
- #define E1_CHAIN_POS -1
- #define E1_SLEW_RATE 1
+ #define E1_MICROSTEPS E0_MICROSTEPS
+ #define E1_OVERCURRENT 2000
+ #define E1_STALLCURRENT 1500
+ #define E1_MAX_VOLTAGE 127
+ #define E1_CHAIN_POS -1
+ #define E1_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(E2)
- #define E2_MICROSTEPS 128
- #define E2_OVERCURRENT 2000
- #define E2_STALLCURRENT 1500
- #define E2_MAX_VOLTAGE 127
- #define E2_CHAIN_POS -1
- #define E2_SLEW_RATE 1
+ #define E2_MICROSTEPS E0_MICROSTEPS
+ #define E2_OVERCURRENT 2000
+ #define E2_STALLCURRENT 1500
+ #define E2_MAX_VOLTAGE 127
+ #define E2_CHAIN_POS -1
+ #define E2_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(E3)
- #define E3_MICROSTEPS 128
- #define E3_OVERCURRENT 2000
- #define E3_STALLCURRENT 1500
- #define E3_MAX_VOLTAGE 127
- #define E3_CHAIN_POS -1
- #define E3_SLEW_RATE 1
+ #define E3_MICROSTEPS E0_MICROSTEPS
+ #define E3_OVERCURRENT 2000
+ #define E3_STALLCURRENT 1500
+ #define E3_MAX_VOLTAGE 127
+ #define E3_CHAIN_POS -1
+ #define E3_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(E4)
- #define E4_MICROSTEPS 128
- #define E4_OVERCURRENT 2000
- #define E4_STALLCURRENT 1500
- #define E4_MAX_VOLTAGE 127
- #define E4_CHAIN_POS -1
- #define E4_SLEW_RATE 1
+ #define E4_MICROSTEPS E0_MICROSTEPS
+ #define E4_OVERCURRENT 2000
+ #define E4_STALLCURRENT 1500
+ #define E4_MAX_VOLTAGE 127
+ #define E4_CHAIN_POS -1
+ #define E4_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(E5)
- #define E5_MICROSTEPS 128
- #define E5_OVERCURRENT 2000
- #define E5_STALLCURRENT 1500
- #define E5_MAX_VOLTAGE 127
- #define E5_CHAIN_POS -1
- #define E5_SLEW_RATE 1
+ #define E5_MICROSTEPS E0_MICROSTEPS
+ #define E5_OVERCURRENT 2000
+ #define E5_STALLCURRENT 1500
+ #define E5_MAX_VOLTAGE 127
+ #define E5_CHAIN_POS -1
+ #define E5_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(E6)
- #define E6_MICROSTEPS 128
- #define E6_OVERCURRENT 2000
- #define E6_STALLCURRENT 1500
- #define E6_MAX_VOLTAGE 127
- #define E6_CHAIN_POS -1
- #define E6_SLEW_RATE 1
+ #define E6_MICROSTEPS E0_MICROSTEPS
+ #define E6_OVERCURRENT 2000
+ #define E6_STALLCURRENT 1500
+ #define E6_MAX_VOLTAGE 127
+ #define E6_CHAIN_POS -1
+ #define E6_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(E7)
- #define E7_MICROSTEPS 128
- #define E7_OVERCURRENT 2000
- #define E7_STALLCURRENT 1500
- #define E7_MAX_VOLTAGE 127
- #define E7_CHAIN_POS -1
- #define E7_SLEW_RATE 1
+ #define E7_MICROSTEPS E0_MICROSTEPS
+ #define E7_OVERCURRENT 2000
+ #define E7_STALLCURRENT 1500
+ #define E7_MAX_VOLTAGE 127
+ #define E7_CHAIN_POS -1
+ #define E7_SLEW_RATE 1
#endif
/**
@@ -3001,10 +3288,22 @@
#define SPINDLE_LASER_FREQUENCY 2500 // (Hz) Spindle/laser frequency (only on supported HALs: AVR and LPC)
- //#define SPINDLE_SERVO // A servo converting an angle to spindle power
+ //#define AIR_EVACUATION // Cutter Vacuum / Laser Blower motor control with G-codes M10-M11
+ #if ENABLED(AIR_EVACUATION)
+ #define AIR_EVACUATION_ACTIVE LOW // Set to "HIGH" if the on/off function is active HIGH
+ //#define AIR_EVACUATION_PIN 42 // Override the default Cutter Vacuum or Laser Blower pin
+ #endif
+
+ //#define AIR_ASSIST // Air Assist control with G-codes M8-M9
+ #if ENABLED(AIR_ASSIST)
+ #define AIR_ASSIST_ACTIVE LOW // Active state on air assist pin
+ //#define AIR_ASSIST_PIN 44 // Override the default Air Assist pin
+ #endif
+
+ //#define SPINDLE_SERVO // A servo converting an angle to spindle power
#ifdef SPINDLE_SERVO
- #define SPINDLE_SERVO_NR 0 // Index of servo used for spindle control
- #define SPINDLE_SERVO_MIN 10 // Minimum angle for servo spindle
+ #define SPINDLE_SERVO_NR 0 // Index of servo used for spindle control
+ #define SPINDLE_SERVO_MIN 10 // Minimum angle for servo spindle
#endif
/**
@@ -3133,8 +3432,30 @@
#define SPINDLE_LASER_POWERDOWN_DELAY 50 // (ms) Delay to allow the spindle to stop
#endif
+
+ //
+ // Laser I2C Ammeter (High precision INA226 low/high side module)
+ //
+ //#define I2C_AMMETER
+ #if ENABLED(I2C_AMMETER)
+ #define I2C_AMMETER_IMAX 0.1 // (Amps) Calibration value for the expected current range
+ #define I2C_AMMETER_SHUNT_RESISTOR 0.1 // (Ohms) Calibration shunt resistor value
+ #endif
+
#endif
-#endif
+#endif // SPINDLE_FEATURE || LASER_FEATURE
+
+/**
+ * Synchronous Laser Control with M106/M107
+ *
+ * Marlin normally applies M106/M107 fan speeds at a time "soon after" processing
+ * a planner block. This is too inaccurate for a PWM/TTL laser attached to the fan
+ * header (as with some add-on laser kits). Enable this option to set fan/laser
+ * speeds with much more exact timing for improved print fidelity.
+ *
+ * NOTE: This option sacrifices some cooling fan speed options.
+ */
+//#define LASER_SYNCHRONOUS_M106_M107
/**
* Coolant Control
@@ -3195,13 +3516,27 @@
*/
//#define POWER_MONITOR_CURRENT // Monitor the system current
//#define POWER_MONITOR_VOLTAGE // Monitor the system voltage
-#if EITHER(POWER_MONITOR_CURRENT, POWER_MONITOR_VOLTAGE)
- #define POWER_MONITOR_VOLTS_PER_AMP 0.05000 // Input voltage to the MCU analog pin per amp - DO NOT apply more than ADC_VREF!
- #define POWER_MONITOR_CURRENT_OFFSET -1 // Offset value for current sensors with linear function output
- #define POWER_MONITOR_VOLTS_PER_VOLT 0.11786 // Input voltage to the MCU analog pin per volt - DO NOT apply more than ADC_VREF!
+
+#if ENABLED(POWER_MONITOR_CURRENT)
+ #define POWER_MONITOR_VOLTS_PER_AMP 0.05000 // Input voltage to the MCU analog pin per amp - DO NOT apply more than ADC_VREF!
+ #define POWER_MONITOR_CURRENT_OFFSET 0 // Offset (in amps) applied to the calculated current
#define POWER_MONITOR_FIXED_VOLTAGE 13.6 // Voltage for a current sensor with no voltage sensor (for power display)
#endif
+#if ENABLED(POWER_MONITOR_VOLTAGE)
+ #define POWER_MONITOR_VOLTS_PER_VOLT 0.077933 // Input voltage to the MCU analog pin per volt - DO NOT apply more than ADC_VREF!
+ #define POWER_MONITOR_VOLTAGE_OFFSET 0 // Offset (in volts) applied to the calculated voltage
+#endif
+
+/**
+ * Stepper Driver Anti-SNAFU Protection
+ *
+ * If the SAFE_POWER_PIN is defined for your board, Marlin will check
+ * that stepper drivers are properly plugged in before applying power.
+ * Disable protection if your stepper drivers don't support the feature.
+ */
+//#define DISABLE_DRIVER_SAFE_POWER_PROTECT
+
/**
* CNC Coordinate Systems
*
@@ -3215,6 +3550,11 @@
*/
#define AUTO_REPORT_TEMPERATURES
+/**
+ * Auto-report position with M154 S
+ */
+//#define AUTO_REPORT_POSITION
+
/**
* Include capabilities in M115 output
*/
@@ -3284,7 +3624,7 @@
#define PROPORTIONAL_FONT_RATIO 1.0
/**
- * Spend 28 bytes of SRAM to optimize the GCode parser
+ * Spend 28 bytes of SRAM to optimize the G-code parser
*/
#define FASTER_GCODE_PARSER
@@ -3292,6 +3632,10 @@
//#define GCODE_QUOTED_STRINGS // Support for quoted string parameters
#endif
+// Support for MeatPack G-code compression (https://github.com/scottmudge/OctoPrint-MeatPack)
+//#define MEATPACK_ON_SERIAL_PORT_1
+//#define MEATPACK_ON_SERIAL_PORT_2
+
//#define GCODE_CASE_INSENSITIVE // Accept G-code sent to the firmware in lowercase
//#define REPETIER_GCODE_M360 // Add commands originally from Repetier FW
@@ -3331,29 +3675,99 @@
#endif
/**
- * User-defined menu items that execute custom GCode
+ * User-defined menu items to run custom G-code.
+ * Up to 25 may be defined, but the actual number is LCD-dependent.
*/
-//#define CUSTOM_USER_MENUS
-#if ENABLED(CUSTOM_USER_MENUS)
- //#define CUSTOM_USER_MENU_TITLE "Custom Commands"
- #define USER_SCRIPT_DONE "M117 User Script Done"
- #define USER_SCRIPT_AUDIBLE_FEEDBACK
- //#define USER_SCRIPT_RETURN // Return to status screen after a script
- #define USER_DESC_1 "Home & UBL Info"
- #define USER_GCODE_1 "G28\nG29 W"
+// Custom Menu: Main Menu
+//#define CUSTOM_MENU_MAIN
+#if ENABLED(CUSTOM_MENU_MAIN)
+ //#define CUSTOM_MENU_MAIN_TITLE "Custom Commands"
+ #define CUSTOM_MENU_MAIN_SCRIPT_DONE "M117 User Script Done"
+ #define CUSTOM_MENU_MAIN_SCRIPT_AUDIBLE_FEEDBACK
+ //#define CUSTOM_MENU_MAIN_SCRIPT_RETURN // Return to status screen after a script
+ #define CUSTOM_MENU_MAIN_ONLY_IDLE // Only show custom menu when the machine is idle
+
+ #define MAIN_MENU_ITEM_1_DESC "Home & UBL Info"
+ #define MAIN_MENU_ITEM_1_GCODE "G28\nG29 W"
+ //#define MAIN_MENU_ITEM_1_CONFIRM // Show a confirmation dialog before this action
+
+ #define MAIN_MENU_ITEM_2_DESC "Preheat for " PREHEAT_1_LABEL
+ #define MAIN_MENU_ITEM_2_GCODE "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND)
+ //#define MAIN_MENU_ITEM_2_CONFIRM
+
+ //#define MAIN_MENU_ITEM_3_DESC "Preheat for " PREHEAT_2_LABEL
+ //#define MAIN_MENU_ITEM_3_GCODE "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND)
+ //#define MAIN_MENU_ITEM_3_CONFIRM
+
+ //#define MAIN_MENU_ITEM_4_DESC "Heat Bed/Home/Level"
+ //#define MAIN_MENU_ITEM_4_GCODE "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29"
+ //#define MAIN_MENU_ITEM_4_CONFIRM
+
+ //#define MAIN_MENU_ITEM_5_DESC "Home & Info"
+ //#define MAIN_MENU_ITEM_5_GCODE "G28\nM503"
+ //#define MAIN_MENU_ITEM_5_CONFIRM
+#endif
- #define USER_DESC_2 "Preheat for " PREHEAT_1_LABEL
- #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND)
+// Custom Menu: Configuration Menu
+//#define CUSTOM_MENU_CONFIG
+#if ENABLED(CUSTOM_MENU_CONFIG)
+ //#define CUSTOM_MENU_CONFIG_TITLE "Custom Commands"
+ #define CUSTOM_MENU_CONFIG_SCRIPT_DONE "M117 Wireless Script Done"
+ #define CUSTOM_MENU_CONFIG_SCRIPT_AUDIBLE_FEEDBACK
+ //#define CUSTOM_MENU_CONFIG_SCRIPT_RETURN // Return to status screen after a script
+ #define CUSTOM_MENU_CONFIG_ONLY_IDLE // Only show custom menu when the machine is idle
+
+ #define CONFIG_MENU_ITEM_1_DESC "Wifi ON"
+ #define CONFIG_MENU_ITEM_1_GCODE "M118 [ESP110] WIFI-STA pwd=12345678"
+ //#define CONFIG_MENU_ITEM_1_CONFIRM // Show a confirmation dialog before this action
+
+ #define CONFIG_MENU_ITEM_2_DESC "Bluetooth ON"
+ #define CONFIG_MENU_ITEM_2_GCODE "M118 [ESP110] BT pwd=12345678"
+ //#define CONFIG_MENU_ITEM_2_CONFIRM
+
+ //#define CONFIG_MENU_ITEM_3_DESC "Radio OFF"
+ //#define CONFIG_MENU_ITEM_3_GCODE "M118 [ESP110] OFF pwd=12345678"
+ //#define CONFIG_MENU_ITEM_3_CONFIRM
+
+ //#define CONFIG_MENU_ITEM_4_DESC "Wifi ????"
+ //#define CONFIG_MENU_ITEM_4_GCODE "M118 ????"
+ //#define CONFIG_MENU_ITEM_4_CONFIRM
+
+ //#define CONFIG_MENU_ITEM_5_DESC "Wifi ????"
+ //#define CONFIG_MENU_ITEM_5_GCODE "M118 ????"
+ //#define CONFIG_MENU_ITEM_5_CONFIRM
+#endif
- #define USER_DESC_3 "Preheat for " PREHEAT_2_LABEL
- #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND)
+/**
+ * User-defined buttons to run custom G-code.
+ * Up to 25 may be defined.
+ */
+//#define CUSTOM_USER_BUTTONS
+#if ENABLED(CUSTOM_USER_BUTTONS)
+ //#define BUTTON1_PIN -1
+ #if PIN_EXISTS(BUTTON1)
+ #define BUTTON1_HIT_STATE LOW // State of the triggered button. NC=LOW. NO=HIGH.
+ #define BUTTON1_WHEN_PRINTING false // Button allowed to trigger during printing?
+ #define BUTTON1_GCODE "G28"
+ #define BUTTON1_DESC "Homing" // Optional string to set the LCD status
+ #endif
- #define USER_DESC_4 "Heat Bed/Home/Level"
- #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29"
+ //#define BUTTON2_PIN -1
+ #if PIN_EXISTS(BUTTON2)
+ #define BUTTON2_HIT_STATE LOW
+ #define BUTTON2_WHEN_PRINTING false
+ #define BUTTON2_GCODE "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND)
+ #define BUTTON2_DESC "Preheat for " PREHEAT_1_LABEL
+ #endif
- #define USER_DESC_5 "Home & Info"
- #define USER_GCODE_5 "G28\nM503"
+ //#define BUTTON3_PIN -1
+ #if PIN_EXISTS(BUTTON3)
+ #define BUTTON3_HIT_STATE LOW
+ #define BUTTON3_WHEN_PRINTING false
+ #define BUTTON3_GCODE "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND)
+ #define BUTTON3_DESC "Preheat for " PREHEAT_2_LABEL
+ #endif
#endif
/**
@@ -3382,6 +3796,9 @@
* Implement M486 to allow Marlin to skip objects
*/
//#define CANCEL_OBJECTS
+#if ENABLED(CANCEL_OBJECTS)
+ #define CANCEL_OBJECTS_REPORTING // Emit the current object as a status message
+#endif
/**
* I2C position encoders for closed loop control.
@@ -3503,6 +3920,16 @@
#define GANTRY_CALIBRATION_COMMANDS_POST "G28" // G28 highly recommended to ensure an accurate position
#endif
+/**
+ * Instant freeze / unfreeze functionality
+ * Specified pin has pullup and connecting to ground will instantly pause motion.
+ * Potentially useful for emergency stop that allows being resumed.
+ */
+//#define FREEZE_FEATURE
+#if ENABLED(FREEZE_FEATURE)
+ //#define FREEZE_PIN 41 // Override the default (KILL) pin here
+#endif
+
/**
* MAX7219 Debug Matrix
*
@@ -3539,14 +3966,13 @@
/**
* NanoDLP Sync support
*
- * Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
- * string to enable synchronization with DLP projector exposure. This change will allow to use
- * [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
+ * Support for Synchronized Z moves when used with NanoDLP. G0/G1 axis moves will
+ * output a "Z_move_comp" string to enable synchronization with DLP projector exposure.
+ * This feature allows you to use [[WaitForDoneMessage]] instead of M400 commands.
*/
//#define NANODLP_Z_SYNC
#if ENABLED(NANODLP_Z_SYNC)
- //#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
- // Default behavior is limited to Z axis only.
+ //#define NANODLP_ALL_AXIS // Send a "Z_move_comp" report for any axis move (not just Z).
#endif
/**
@@ -3598,10 +4024,7 @@
//#define E_MUX2_PIN 44 // Needed for 5 to 8 inputs
#elif HAS_PRUSA_MMU2
// Serial port used for communication with MMU2.
- // For AVR enable the UART port used for the MMU. (e.g., mmuSerial)
- // For 32-bit boards check your HAL for available serial ports. (e.g., Serial2)
#define MMU2_SERIAL_PORT 2
- #define MMU2_SERIAL mmuSerial
// Use hardware reset for MMU if a pin is defined for it
//#define MMU2_RST_PIN 23
@@ -3717,3 +4140,16 @@
// Enable Marlin dev mode which adds some special commands
//#define MARLIN_DEV_MODE
+
+/**
+ * Postmortem Debugging captures misbehavior and outputs the CPU status and backtrace to serial.
+ * When running in the debugger it will break for debugging. This is useful to help understand
+ * a crash from a remote location. Requires ~400 bytes of SRAM and 5Kb of flash.
+ */
+//#define POSTMORTEM_DEBUGGING
+
+/**
+ * Software Reset options
+ */
+//#define SOFT_RESET_VIA_SERIAL // 'KILL' and '^X' commands will soft-reset the controller
+//#define SOFT_RESET_ON_KILL // Use a digital button to soft-reset the controller after KILL
diff --git a/Marlin/Makefile b/Marlin/Makefile
index 49cb960b92fe..5ff183082210 100644
--- a/Marlin/Makefile
+++ b/Marlin/Makefile
@@ -219,7 +219,7 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1111)
else ifeq ($(HARDWARE_MOTHERBOARD),1112)
# MKS GEN L
else ifeq ($(HARDWARE_MOTHERBOARD),1113)
-# zrib V2.0 control board (Chinese knock off RAMPS replica)
+# zrib V2.0 control board (Chinese RAMPS replica)
else ifeq ($(HARDWARE_MOTHERBOARD),1114)
# BigTreeTech or BIQU KFB2.0
else ifeq ($(HARDWARE_MOTHERBOARD),1115)
@@ -323,6 +323,8 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1203)
else ifeq ($(HARDWARE_MOTHERBOARD),1204)
# abee Scoovo X9H
else ifeq ($(HARDWARE_MOTHERBOARD),1205)
+# Rambo ThinkerV2
+else ifeq ($(HARDWARE_MOTHERBOARD),1206)
#
# Other ATmega1280, ATmega2560
@@ -991,5 +993,5 @@ clean:
.PHONY: all build elf hex eep lss sym program coff extcoff clean depend sizebefore sizeafter
-# Automaticaly include the dependency files created by gcc
+# Automatically include the dependency files created by gcc
-include ${patsubst %.o, %.d, ${OBJ}}
diff --git a/Marlin/src/HAL/AVR/HAL.cpp b/Marlin/src/HAL/AVR/HAL.cpp
index 58d57c8ee54b..708583b262a6 100644
--- a/Marlin/src/HAL/AVR/HAL.cpp
+++ b/Marlin/src/HAL/AVR/HAL.cpp
@@ -24,6 +24,13 @@
#include "../../inc/MarlinConfig.h"
#include "HAL.h"
+#ifdef USBCON
+ DefaultSerial1 MSerial0(false, Serial);
+ #ifdef BLUETOOTH
+ BTSerial btSerial(false, bluetoothSerial);
+ #endif
+#endif
+
// ------------------------
// Public Variables
// ------------------------
@@ -51,6 +58,15 @@ void HAL_init() {
#endif
}
+void HAL_reboot() {
+ #if ENABLED(USE_WATCHDOG)
+ while (1) { /* run out the watchdog */ }
+ #else
+ void (*resetFunc)() = 0; // Declare resetFunc() at address 0
+ resetFunc(); // Jump to address 0
+ #endif
+}
+
#if ENABLED(SDSUPPORT)
#include "../../sd/SdFatUtil.h"
diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h
index aa6a32132032..a5896a0e970f 100644
--- a/Marlin/src/HAL/AVR/HAL.h
+++ b/Marlin/src/HAL/AVR/HAL.h
@@ -82,24 +82,46 @@ typedef int8_t pin_t;
// Serial ports
#ifdef USBCON
- #define MYSERIAL0 TERN(BLUETOOTH, bluetoothSerial, Serial)
+ #include "../../core/serial_hook.h"
+ typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1;
+ extern DefaultSerial1 MSerial0;
+ #ifdef BLUETOOTH
+ typedef ForwardSerial1Class< decltype(bluetoothSerial) > BTSerial;
+ extern BTSerial btSerial;
+ #endif
+
+ #define MYSERIAL1 TERN(BLUETOOTH, btSerial, MSerial0)
#else
#if !WITHIN(SERIAL_PORT, -1, 3)
- #error "SERIAL_PORT must be from -1 to 3. Please update your configuration."
+ #error "SERIAL_PORT must be from 0 to 3, or -1 for USB Serial."
#endif
- #define MYSERIAL0 customizedSerial1
+ #define MYSERIAL1 customizedSerial1
#ifdef SERIAL_PORT_2
#if !WITHIN(SERIAL_PORT_2, -1, 3)
- #error "SERIAL_PORT_2 must be from -1 to 3. Please update your configuration."
+ #error "SERIAL_PORT_2 must be from 0 to 3, or -1 for USB Serial."
+ #endif
+ #define MYSERIAL2 customizedSerial2
+ #endif
+
+ #ifdef SERIAL_PORT_3
+ #if !WITHIN(SERIAL_PORT_3, -1, 3)
+ #error "SERIAL_PORT_3 must be from 0 to 3, or -1 for USB Serial."
#endif
- #define MYSERIAL1 customizedSerial2
+ #define MYSERIAL3 customizedSerial3
+ #endif
+#endif
+
+#ifdef MMU2_SERIAL_PORT
+ #if !WITHIN(MMU2_SERIAL_PORT, -1, 3)
+ #error "MMU2_SERIAL_PORT must be from 0 to 3, or -1 for USB Serial."
#endif
+ #define MMU2_SERIAL mmuSerial
#endif
#ifdef LCD_SERIAL_PORT
#if !WITHIN(LCD_SERIAL_PORT, -1, 3)
- #error "LCD_SERIAL_PORT must be from -1 to 3. Please update your configuration."
+ #error "LCD_SERIAL_PORT must be from 0 to 3, or -1 for USB Serial."
#endif
#define LCD_SERIAL lcdSerial
#if HAS_DGUS_LCD
@@ -120,7 +142,7 @@ void HAL_init();
inline void HAL_clear_reset_source() { MCUSR = 0; }
inline uint8_t HAL_get_reset_source() { return MCUSR; }
-inline void HAL_reboot() {} // reboot the board or restart the bootloader
+void HAL_reboot();
#if GCC_VERSION <= 50000
#pragma GCC diagnostic push
@@ -164,7 +186,7 @@ inline void HAL_adc_init() {
#define GET_PIN_MAP_INDEX(pin) pin
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
-#define HAL_SENSITIVE_PINS 0, 1
+#define HAL_SENSITIVE_PINS 0, 1,
#ifdef __AVR_AT90USB1286__
#define JTAG_DISABLE() do{ MCUCR = 0x80; MCUCR = 0x80; }while(0)
diff --git a/Marlin/src/HAL/AVR/HAL_SPI.cpp b/Marlin/src/HAL/AVR/HAL_SPI.cpp
index 3e5572e559fa..1a1b98b3dd2a 100644
--- a/Marlin/src/HAL/AVR/HAL_SPI.cpp
+++ b/Marlin/src/HAL/AVR/HAL_SPI.cpp
@@ -88,7 +88,7 @@ void spiBegin() {
}
/** SPI read data */
- void spiRead(uint8_t* buf, uint16_t nbyte) {
+ void spiRead(uint8_t *buf, uint16_t nbyte) {
if (nbyte-- == 0) return;
SPDR = 0xFF;
for (uint16_t i = 0; i < nbyte; i++) {
@@ -107,7 +107,7 @@ void spiBegin() {
}
/** SPI send block */
- void spiSendBlock(uint8_t token, const uint8_t* buf) {
+ void spiSendBlock(uint8_t token, const uint8_t *buf) {
SPDR = token;
for (uint16_t i = 0; i < 512; i += 2) {
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
@@ -215,7 +215,7 @@ void spiBegin() {
}
// Soft SPI read data
- void spiRead(uint8_t* buf, uint16_t nbyte) {
+ void spiRead(uint8_t *buf, uint16_t nbyte) {
for (uint16_t i = 0; i < nbyte; i++)
buf[i] = spiRec();
}
@@ -242,7 +242,7 @@ void spiBegin() {
}
// Soft SPI send block
- void spiSendBlock(uint8_t token, const uint8_t* buf) {
+ void spiSendBlock(uint8_t token, const uint8_t *buf) {
spiSend(token);
for (uint16_t i = 0; i < 512; i++)
spiSend(buf[i]);
diff --git a/Marlin/src/HAL/AVR/MarlinSerial.cpp b/Marlin/src/HAL/AVR/MarlinSerial.cpp
index 63599efd4132..cd8bf5e6903b 100644
--- a/Marlin/src/HAL/AVR/MarlinSerial.cpp
+++ b/Marlin/src/HAL/AVR/MarlinSerial.cpp
@@ -556,161 +556,6 @@ void MarlinSerial::flushTX() {
}
}
-/**
- * Imports from print.h
- */
-
-template
-void MarlinSerial::print(char c, int base) {
- print((long)c, base);
-}
-
-template
-void MarlinSerial::print(unsigned char b, int base) {
- print((unsigned long)b, base);
-}
-
-template
-void MarlinSerial::print(int n, int base) {
- print((long)n, base);
-}
-
-template
-void MarlinSerial::print(unsigned int n, int base) {
- print((unsigned long)n, base);
-}
-
-template
-void MarlinSerial::print(long n, int base) {
- if (base == 0) write(n);
- else if (base == 10) {
- if (n < 0) { print('-'); n = -n; }
- printNumber(n, 10);
- }
- else
- printNumber(n, base);
-}
-
-template
-void MarlinSerial::print(unsigned long n, int base) {
- if (base == 0) write(n);
- else printNumber(n, base);
-}
-
-template
-void MarlinSerial::print(double n, int digits) {
- printFloat(n, digits);
-}
-
-template
-void MarlinSerial::println() {
- print('\r');
- print('\n');
-}
-
-template
-void MarlinSerial::println(const String& s) {
- print(s);
- println();
-}
-
-template
-void MarlinSerial::println(const char c[]) {
- print(c);
- println();
-}
-
-template
-void MarlinSerial::println(char c, int base) {
- print(c, base);
- println();
-}
-
-template
-void MarlinSerial::println(unsigned char b, int base) {
- print(b, base);
- println();
-}
-
-template
-void MarlinSerial::println(int n, int base) {
- print(n, base);
- println();
-}
-
-template
-void MarlinSerial::println(unsigned int n, int base) {
- print(n, base);
- println();
-}
-
-template
-void MarlinSerial::println(long n, int base) {
- print(n, base);
- println();
-}
-
-template
-void MarlinSerial::println(unsigned long n, int base) {
- print(n, base);
- println();
-}
-
-template
-void MarlinSerial::println(double n, int digits) {
- print(n, digits);
- println();
-}
-
-// Private Methods
-
-template
-void MarlinSerial::printNumber(unsigned long n, uint8_t base) {
- if (n) {
- unsigned char buf[8 * sizeof(long)]; // Enough space for base 2
- int8_t i = 0;
- while (n) {
- buf[i++] = n % base;
- n /= base;
- }
- while (i--)
- print((char)(buf[i] + (buf[i] < 10 ? '0' : 'A' - 10)));
- }
- else
- print('0');
-}
-
-template
-void MarlinSerial::printFloat(double number, uint8_t digits) {
- // Handle negative numbers
- if (number < 0.0) {
- print('-');
- number = -number;
- }
-
- // Round correctly so that print(1.999, 2) prints as "2.00"
- double rounding = 0.5;
- LOOP_L_N(i, digits) rounding *= 0.1;
- number += rounding;
-
- // Extract the integer part of the number and print it
- unsigned long int_part = (unsigned long)number;
- double remainder = number - (double)int_part;
- print(int_part);
-
- // Print the decimal point, but only if there are digits beyond
- if (digits) {
- print('.');
- // Extract digits from the remainder one at a time
- while (digits--) {
- remainder *= 10.0;
- int toPrint = int(remainder);
- print(toPrint);
- remainder -= toPrint;
- }
- }
-}
-
// Hookup ISR handlers
ISR(SERIAL_REGNAME(USART, SERIAL_PORT, _RX_vect)) {
MarlinSerial>::store_rxd_char();
@@ -720,11 +565,9 @@ ISR(SERIAL_REGNAME(USART, SERIAL_PORT, _UDRE_vect)) {
MarlinSerial>::_tx_udr_empty_irq();
}
-// Preinstantiate
-template class MarlinSerial>;
-
-// Instantiate
-MarlinSerial> customizedSerial1;
+// Because of the template definition above, it's required to instantiate the template to have all methods generated
+template class MarlinSerial< MarlinSerialCfg >;
+MSerialT1 customizedSerial1(MSerialT1::HasEmergencyParser);
#ifdef SERIAL_PORT_2
@@ -737,13 +580,26 @@ MarlinSerial> customizedSerial1;
MarlinSerial>::_tx_udr_empty_irq();
}
- // Preinstantiate
- template class MarlinSerial>;
+ template class MarlinSerial< MarlinSerialCfg >;
+ MSerialT2 customizedSerial2(MSerialT2::HasEmergencyParser);
- // Instantiate
- MarlinSerial> customizedSerial2;
+#endif // SERIAL_PORT_2
-#endif
+#ifdef SERIAL_PORT_3
+
+ // Hookup ISR handlers
+ ISR(SERIAL_REGNAME(USART, SERIAL_PORT_3, _RX_vect)) {
+ MarlinSerial>::store_rxd_char();
+ }
+
+ ISR(SERIAL_REGNAME(USART, SERIAL_PORT_3, _UDRE_vect)) {
+ MarlinSerial>::_tx_udr_empty_irq();
+ }
+
+ template class MarlinSerial< MarlinSerialCfg >;
+ MSerialT3 customizedSerial3(MSerialT3::HasEmergencyParser);
+
+#endif // SERIAL_PORT_3
#ifdef MMU2_SERIAL_PORT
@@ -755,13 +611,10 @@ MarlinSerial> customizedSerial1;
MarlinSerial>::_tx_udr_empty_irq();
}
- // Preinstantiate
- template class MarlinSerial>;
-
- // Instantiate
- MarlinSerial> mmuSerial;
+ template class MarlinSerial< MMU2SerialCfg >;
+ MSerialMMU2 mmuSerial(MSerialMMU2::HasEmergencyParser);
-#endif
+#endif // MMU2_SERIAL_PORT
#ifdef LCD_SERIAL_PORT
@@ -773,11 +626,8 @@ MarlinSerial> customizedSerial1;
MarlinSerial>::_tx_udr_empty_irq();
}
- // Preinstantiate
- template class MarlinSerial>;
-
- // Instantiate
- MarlinSerial> lcdSerial;
+ template class MarlinSerial< LCDSerialCfg >;
+ MSerialLCD lcdSerial(MSerialLCD::HasEmergencyParser);
#if HAS_DGUS_LCD
template
@@ -790,13 +640,13 @@ MarlinSerial> customizedSerial1;
}
#endif
-#endif
+#endif // LCD_SERIAL_PORT
#endif // !USBCON && (UBRRH || UBRR0H || UBRR1H || UBRR2H || UBRR3H)
// For AT90USB targets use the UART for BT interfacing
#if defined(USBCON) && ENABLED(BLUETOOTH)
- HardwareSerial bluetoothSerial;
+ MSerialBT bluetoothSerial(false);
#endif
#endif // __AVR__
diff --git a/Marlin/src/HAL/AVR/MarlinSerial.h b/Marlin/src/HAL/AVR/MarlinSerial.h
index 8a0423d143d8..0565c7b9db9e 100644
--- a/Marlin/src/HAL/AVR/MarlinSerial.h
+++ b/Marlin/src/HAL/AVR/MarlinSerial.h
@@ -34,6 +34,7 @@
#include
#include "../../inc/MarlinConfigPre.h"
+#include "../../core/serial_hook.h"
#ifndef SERIAL_PORT
#define SERIAL_PORT 0
@@ -135,10 +136,6 @@
UART_DECL(3);
#endif
- #define DEC 10
- #define HEX 16
- #define OCT 8
- #define BIN 2
#define BYTE 0
// Templated type selector
@@ -202,60 +199,30 @@
static FORCE_INLINE void atomic_set_rx_tail(ring_buffer_pos_t value);
static FORCE_INLINE ring_buffer_pos_t atomic_read_rx_tail();
- public:
-
+ public:
FORCE_INLINE static void store_rxd_char();
FORCE_INLINE static void _tx_udr_empty_irq();
- public:
- MarlinSerial() {};
- static void begin(const long);
- static void end();
- static int peek();
- static int read();
- static void flush();
- static ring_buffer_pos_t available();
- static void write(const uint8_t c);
- static void flushTX();
- #if HAS_DGUS_LCD
- static ring_buffer_pos_t get_tx_buffer_free();
- #endif
-
- static inline bool emergency_parser_enabled() { return Cfg::EMERGENCYPARSER; }
-
- FORCE_INLINE static uint8_t dropped() { return Cfg::DROPPED_RX ? rx_dropped_bytes : 0; }
- FORCE_INLINE static uint8_t buffer_overruns() { return Cfg::RX_OVERRUNS ? rx_buffer_overruns : 0; }
- FORCE_INLINE static uint8_t framing_errors() { return Cfg::RX_FRAMING_ERRORS ? rx_framing_errors : 0; }
- FORCE_INLINE static ring_buffer_pos_t rxMaxEnqueued() { return Cfg::MAX_RX_QUEUED ? rx_max_enqueued : 0; }
-
- FORCE_INLINE static void write(const char* str) { while (*str) write(*str++); }
- FORCE_INLINE static void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); }
- FORCE_INLINE static void print(const String& s) { for (int i = 0; i < (int)s.length(); i++) write(s[i]); }
- FORCE_INLINE static void print(const char* str) { write(str); }
-
- static void print(char, int = BYTE);
- static void print(unsigned char, int = BYTE);
- static void print(int, int = DEC);
- static void print(unsigned int, int = DEC);
- static void print(long, int = DEC);
- static void print(unsigned long, int = DEC);
- static void print(double, int = 2);
-
- static void println(const String& s);
- static void println(const char[]);
- static void println(char, int = BYTE);
- static void println(unsigned char, int = BYTE);
- static void println(int, int = DEC);
- static void println(unsigned int, int = DEC);
- static void println(long, int = DEC);
- static void println(unsigned long, int = DEC);
- static void println(double, int = 2);
- static void println();
- operator bool() { return true; }
-
- private:
- static void printNumber(unsigned long, const uint8_t);
- static void printFloat(double, uint8_t);
+ public:
+ static void begin(const long);
+ static void end();
+ static int peek();
+ static int read();
+ static void flush();
+ static ring_buffer_pos_t available();
+ static void write(const uint8_t c);
+ static void flushTX();
+ #if HAS_DGUS_LCD
+ static ring_buffer_pos_t get_tx_buffer_free();
+ #endif
+
+ enum { HasEmergencyParser = Cfg::EMERGENCYPARSER };
+ static inline bool emergency_parser_enabled() { return Cfg::EMERGENCYPARSER; }
+
+ FORCE_INLINE static uint8_t dropped() { return Cfg::DROPPED_RX ? rx_dropped_bytes : 0; }
+ FORCE_INLINE static uint8_t buffer_overruns() { return Cfg::RX_OVERRUNS ? rx_buffer_overruns : 0; }
+ FORCE_INLINE static uint8_t framing_errors() { return Cfg::RX_FRAMING_ERRORS ? rx_framing_errors : 0; }
+ FORCE_INLINE static ring_buffer_pos_t rxMaxEnqueued() { return Cfg::MAX_RX_QUEUED ? rx_max_enqueued : 0; }
};
template
@@ -270,12 +237,18 @@
static constexpr bool RX_FRAMING_ERRORS = ENABLED(SERIAL_STATS_RX_FRAMING_ERRORS);
static constexpr bool MAX_RX_QUEUED = ENABLED(SERIAL_STATS_MAX_RX_QUEUED);
};
- extern MarlinSerial> customizedSerial1;
- #ifdef SERIAL_PORT_2
+ typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT1;
+ extern MSerialT1 customizedSerial1;
- extern MarlinSerial> customizedSerial2;
+ #ifdef SERIAL_PORT_2
+ typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT2;
+ extern MSerialT2 customizedSerial2;
+ #endif
+ #ifdef SERIAL_PORT_3
+ typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT3;
+ extern MSerialT3 customizedSerial3;
#endif
#endif // !USBCON
@@ -284,49 +257,41 @@
template
struct MMU2SerialCfg {
static constexpr int PORT = serial;
+ static constexpr unsigned int RX_SIZE = 32;
+ static constexpr unsigned int TX_SIZE = 32;
static constexpr bool XONOFF = false;
static constexpr bool EMERGENCYPARSER = false;
static constexpr bool DROPPED_RX = false;
static constexpr bool RX_FRAMING_ERRORS = false;
static constexpr bool MAX_RX_QUEUED = false;
- static constexpr unsigned int RX_SIZE = 32;
- static constexpr unsigned int TX_SIZE = 32;
static constexpr bool RX_OVERRUNS = false;
};
- extern MarlinSerial> mmuSerial;
+ typedef Serial1Class< MarlinSerial< MMU2SerialCfg > > MSerialMMU2;
+ extern MSerialMMU2 mmuSerial;
#endif
#ifdef LCD_SERIAL_PORT
template
struct LCDSerialCfg {
- static constexpr int PORT = serial;
- static constexpr bool XONOFF = false;
- static constexpr bool EMERGENCYPARSER = ENABLED(EMERGENCY_PARSER);
- static constexpr bool DROPPED_RX = false;
- static constexpr bool RX_FRAMING_ERRORS = false;
- static constexpr bool MAX_RX_QUEUED = false;
- #if HAS_DGUS_LCD
- static constexpr unsigned int RX_SIZE = DGUS_RX_BUFFER_SIZE;
- static constexpr unsigned int TX_SIZE = DGUS_TX_BUFFER_SIZE;
- static constexpr bool RX_OVERRUNS = ENABLED(SERIAL_STATS_RX_BUFFER_OVERRUNS);
- #elif EITHER(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON)
- static constexpr unsigned int RX_SIZE = 64;
- static constexpr unsigned int TX_SIZE = 128;
- static constexpr bool RX_OVERRUNS = false;
- #else
- static constexpr unsigned int RX_SIZE = 64;
- static constexpr unsigned int TX_SIZE = 128;
- static constexpr bool RX_OVERRUNS = false
- #endif
+ static constexpr int PORT = serial;
+ static constexpr unsigned int RX_SIZE = TERN(HAS_DGUS_LCD, DGUS_RX_BUFFER_SIZE, 64);
+ static constexpr unsigned int TX_SIZE = TERN(HAS_DGUS_LCD, DGUS_TX_BUFFER_SIZE, 128);
+ static constexpr bool XONOFF = false;
+ static constexpr bool EMERGENCYPARSER = ENABLED(EMERGENCY_PARSER);
+ static constexpr bool DROPPED_RX = false;
+ static constexpr bool RX_FRAMING_ERRORS = false;
+ static constexpr bool MAX_RX_QUEUED = false;
+ static constexpr bool RX_OVERRUNS = BOTH(HAS_DGUS_LCD, SERIAL_STATS_RX_BUFFER_OVERRUNS);
};
- extern MarlinSerial> lcdSerial;
-
+ typedef Serial1Class< MarlinSerial< LCDSerialCfg > > MSerialLCD;
+ extern MSerialLCD lcdSerial;
#endif
// Use the UART for Bluetooth in AT90USB configurations
#if defined(USBCON) && ENABLED(BLUETOOTH)
- extern HardwareSerial bluetoothSerial;
+ typedef Serial1Class MSerialBT;
+ extern MSerialBT bluetoothSerial;
#endif
diff --git a/Marlin/src/HAL/AVR/eeprom.cpp b/Marlin/src/HAL/AVR/eeprom.cpp
index ee2a73e410ad..8d084dec7fdf 100644
--- a/Marlin/src/HAL/AVR/eeprom.cpp
+++ b/Marlin/src/HAL/AVR/eeprom.cpp
@@ -40,13 +40,13 @@ bool PersistentStore::access_start() { return true; }
bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ uint16_t written = 0;
while (size--) {
uint8_t * const p = (uint8_t * const)pos;
uint8_t v = *value;
- // EEPROM has only ~100,000 write cycles,
- // so only write bytes that have changed!
- if (v != eeprom_read_byte(p)) {
+ if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed!
eeprom_write_byte(p, v);
+ if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes
if (eeprom_read_byte(p) != v) {
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
return true;
diff --git a/Marlin/src/HAL/AVR/endstop_interrupts.h b/Marlin/src/HAL/AVR/endstop_interrupts.h
index 9fd9c38b86ad..50f29c3356ce 100644
--- a/Marlin/src/HAL/AVR/endstop_interrupts.h
+++ b/Marlin/src/HAL/AVR/endstop_interrupts.h
@@ -168,6 +168,51 @@ void setup_endstop_interrupts() {
pciSetup(Z_MIN_PIN);
#endif
#endif
+ #if HAS_I_MAX
+ #if (digitalPinToInterrupt(I_MAX_PIN) != NOT_AN_INTERRUPT)
+ _ATTACH(I_MAX_PIN);
+ #else
+ static_assert(digitalPinHasPCICR(I_MAX_PIN), "I_MAX_PIN is not interrupt-capable");
+ pciSetup(I_MAX_PIN);
+ #endif
+ #elif HAS_I_MIN
+ #if (digitalPinToInterrupt(I_MIN_PIN) != NOT_AN_INTERRUPT)
+ _ATTACH(I_MIN_PIN);
+ #else
+ static_assert(digitalPinHasPCICR(I_MIN_PIN), "I_MIN_PIN is not interrupt-capable");
+ pciSetup(I_MIN_PIN);
+ #endif
+ #endif
+ #if HAS_J_MAX
+ #if (digitalPinToInterrupt(J_MAX_PIN) != NOT_AN_INTERRUPT)
+ _ATTACH(J_MAX_PIN);
+ #else
+ static_assert(digitalPinHasPCICR(J_MAX_PIN), "J_MAX_PIN is not interrupt-capable");
+ pciSetup(J_MAX_PIN);
+ #endif
+ #elif HAS_J_MIN
+ #if (digitalPinToInterrupt(J_MIN_PIN) != NOT_AN_INTERRUPT)
+ _ATTACH(J_MIN_PIN);
+ #else
+ static_assert(digitalPinHasPCICR(J_MIN_PIN), "J_MIN_PIN is not interrupt-capable");
+ pciSetup(J_MIN_PIN);
+ #endif
+ #endif
+ #if HAS_K_MAX
+ #if (digitalPinToInterrupt(K_MAX_PIN) != NOT_AN_INTERRUPT)
+ _ATTACH(K_MAX_PIN);
+ #else
+ static_assert(digitalPinHasPCICR(K_MAX_PIN), "K_MAX_PIN is not interrupt-capable");
+ pciSetup(K_MAX_PIN);
+ #endif
+ #elif HAS_K_MIN
+ #if (digitalPinToInterrupt(K_MIN_PIN) != NOT_AN_INTERRUPT)
+ _ATTACH(K_MIN_PIN);
+ #else
+ static_assert(digitalPinHasPCICR(K_MIN_PIN), "K_MIN_PIN is not interrupt-capable");
+ pciSetup(K_MIN_PIN);
+ #endif
+ #endif
#if HAS_X2_MAX
#if (digitalPinToInterrupt(X2_MAX_PIN) != NOT_AN_INTERRUPT)
_ATTACH(X2_MAX_PIN);
@@ -256,6 +301,5 @@ void setup_endstop_interrupts() {
pciSetup(Z_MIN_PROBE_PIN);
#endif
#endif
-
// If we arrive here without raising an assertion, each pin has either an EXT-interrupt or a PCI.
}
diff --git a/Marlin/src/HAL/AVR/fastio.cpp b/Marlin/src/HAL/AVR/fastio.cpp
index b51d7f97686a..70132e71ee54 100644
--- a/Marlin/src/HAL/AVR/fastio.cpp
+++ b/Marlin/src/HAL/AVR/fastio.cpp
@@ -241,7 +241,7 @@ uint8_t extDigitalRead(const int8_t pin) {
*
* DC values -1.0 to 1.0. Negative duty cycle inverts the pulse.
*/
-uint16_t set_pwm_frequency_hz(const float &hz, const float dca, const float dcb, const float dcc) {
+uint16_t set_pwm_frequency_hz(const_float_t hz, const float dca, const float dcb, const float dcc) {
float count = 0;
if (hz > 0 && (dca || dcb || dcc)) {
count = float(F_CPU) / hz; // 1x prescaler, TOP for 16MHz base freq.
diff --git a/Marlin/src/HAL/AVR/fastio.h b/Marlin/src/HAL/AVR/fastio.h
index dd0163466110..cf704179c896 100644
--- a/Marlin/src/HAL/AVR/fastio.h
+++ b/Marlin/src/HAL/AVR/fastio.h
@@ -285,7 +285,7 @@ enum ClockSource2 : char {
*/
// Determine which harware PWMs are already in use
-#define _PWM_CHK_FAN_B(P) (P == E0_AUTO_FAN_PIN || P == E1_AUTO_FAN_PIN || P == E2_AUTO_FAN_PIN || P == E3_AUTO_FAN_PIN || P == E4_AUTO_FAN_PIN || P == E5_AUTO_FAN_PIN || P == E6_AUTO_FAN_PIN || P == E7_AUTO_FAN_PIN || P == CHAMBER_AUTO_FAN_PIN)
+#define _PWM_CHK_FAN_B(P) (P == E0_AUTO_FAN_PIN || P == E1_AUTO_FAN_PIN || P == E2_AUTO_FAN_PIN || P == E3_AUTO_FAN_PIN || P == E4_AUTO_FAN_PIN || P == E5_AUTO_FAN_PIN || P == E6_AUTO_FAN_PIN || P == E7_AUTO_FAN_PIN || P == CHAMBER_AUTO_FAN_PIN || P == COOLER_AUTO_FAN_PIN)
#if PIN_EXISTS(CONTROLLER_FAN)
#define PWM_CHK_FAN_B(P) (_PWM_CHK_FAN_B(P) || P == CONTROLLER_FAN_PIN)
#else
diff --git a/Marlin/src/HAL/AVR/inc/SanityCheck.h b/Marlin/src/HAL/AVR/inc/SanityCheck.h
index 731cf9286582..51ba247953b4 100644
--- a/Marlin/src/HAL/AVR/inc/SanityCheck.h
+++ b/Marlin/src/HAL/AVR/inc/SanityCheck.h
@@ -56,3 +56,10 @@
#if BOTH(HAS_TMC_SW_SERIAL, MONITOR_DRIVER_STATUS)
#error "MONITOR_DRIVER_STATUS causes performance issues when used with SoftwareSerial-connected drivers. Disable MONITOR_DRIVER_STATUS or use hardware serial to continue."
#endif
+
+/**
+ * Postmortem debugging
+ */
+#if ENABLED(POSTMORTEM_DEBUGGING)
+ #error "POSTMORTEM_DEBUGGING is not supported on AVR boards."
+#endif
diff --git a/Marlin/src/HAL/AVR/pinsDebug.h b/Marlin/src/HAL/AVR/pinsDebug.h
index dac6b1b150bd..55fddb05b862 100644
--- a/Marlin/src/HAL/AVR/pinsDebug.h
+++ b/Marlin/src/HAL/AVR/pinsDebug.h
@@ -38,7 +38,7 @@
// portModeRegister takes a different argument
#define digitalPinToTimer_DEBUG(p) digitalPinToTimer(p)
#define digitalPinToBitMask_DEBUG(p) digitalPinToBitMask(p)
- #define digitalPinToPort_DEBUG(p) digitalPinToPort_Teensy(p)
+ #define digitalPinToPort_DEBUG(p) digitalPinToPort(p)
#define GET_PINMODE(pin) (*portModeRegister(pin) & digitalPinToBitMask_DEBUG(pin))
#elif AVR_ATmega2560_FAMILY_PLUS_70 // So we can access/display all the pins on boards using more than 70
@@ -235,8 +235,8 @@ static void print_is_also_tied() { SERIAL_ECHOPGM(" is also tied to this pin");
inline void com_print(const uint8_t N, const uint8_t Z) {
const uint8_t *TCCRA = (uint8_t*)TCCR_A(N);
- SERIAL_ECHOPGM(" COM");
- SERIAL_CHAR('0' + N, Z);
+ SERIAL_ECHOPAIR(" COM", AS_CHAR('0' + N));
+ SERIAL_CHAR(Z);
SERIAL_ECHOPAIR(": ", int((*TCCRA >> (6 - Z * 2)) & 0x03));
}
@@ -247,8 +247,8 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N -
uint8_t WGM = (((*TCCRB & _BV(WGM_2)) >> 1) | (*TCCRA & (_BV(WGM_0) | _BV(WGM_1))));
if (N == 4) WGM |= ((*TCCRB & _BV(WGM_3)) >> 1);
- SERIAL_ECHOPGM(" TIMER");
- SERIAL_CHAR(T + '0', L);
+ SERIAL_ECHOPAIR(" TIMER", AS_CHAR(T + '0'));
+ SERIAL_CHAR(L);
SERIAL_ECHO_SP(3);
if (N == 3) {
@@ -262,19 +262,11 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N -
SERIAL_ECHOPAIR(" WGM: ", WGM);
com_print(T,L);
SERIAL_ECHOPAIR(" CS: ", (*TCCRB & (_BV(CS_0) | _BV(CS_1) | _BV(CS_2)) ));
-
- SERIAL_ECHOPGM(" TCCR");
- SERIAL_CHAR(T + '0');
- SERIAL_ECHOPAIR("A: ", *TCCRA);
-
- SERIAL_ECHOPGM(" TCCR");
- SERIAL_CHAR(T + '0');
- SERIAL_ECHOPAIR("B: ", *TCCRB);
+ SERIAL_ECHOPAIR(" TCCR", AS_CHAR(T + '0'), "A: ", *TCCRA);
+ SERIAL_ECHOPAIR(" TCCR", AS_CHAR(T + '0'), "B: ", *TCCRB);
const uint8_t *TMSK = (uint8_t*)TIMSK(T);
- SERIAL_ECHOPGM(" TIMSK");
- SERIAL_CHAR(T + '0');
- SERIAL_ECHOPAIR(": ", *TMSK);
+ SERIAL_ECHOPAIR(" TIMSK", AS_CHAR(T + '0'), ": ", *TMSK);
const uint8_t OCIE = L - 'A' + 1;
if (N == 3) { if (WGM == 0 || WGM == 2 || WGM == 4 || WGM == 6) err_is_counter(); }
diff --git a/Marlin/src/HAL/DUE/DebugMonitor.cpp b/Marlin/src/HAL/DUE/DebugMonitor.cpp
deleted file mode 100644
index 79759151d891..000000000000
--- a/Marlin/src/HAL/DUE/DebugMonitor.cpp
+++ /dev/null
@@ -1,342 +0,0 @@
-/**
- * Marlin 3D Printer Firmware
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
- *
- * Based on Sprinter and grbl.
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
- *
- * This program is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * This program is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
- *
- */
-#ifdef ARDUINO_ARCH_SAM
-
-#include "../../core/macros.h"
-#include "../../core/serial.h"
-
-#include "../shared/backtrace/unwinder.h"
-#include "../shared/backtrace/unwmemaccess.h"
-
-#include
-
-// Debug monitor that dumps to the Programming port all status when
-// an exception or WDT timeout happens - And then resets the board
-
-// All the Monitor routines must run with interrupts disabled and
-// under an ISR execution context. That is why we cannot reuse the
-// Serial interrupt routines or any C runtime, as we don't know the
-// state we are when running them
-
-// A SW memory barrier, to ensure GCC does not overoptimize loops
-#define sw_barrier() __asm__ volatile("": : :"memory");
-
-// (re)initialize UART0 as a monitor output to 250000,n,8,1
-static void TXBegin() {
-
- // Disable UART interrupt in NVIC
- NVIC_DisableIRQ( UART_IRQn );
-
- // We NEED memory barriers to ensure Interrupts are actually disabled!
- // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
- __DSB();
- __ISB();
-
- // Disable clock
- pmc_disable_periph_clk( ID_UART );
-
- // Configure PMC
- pmc_enable_periph_clk( ID_UART );
-
- // Disable PDC channel
- UART->UART_PTCR = UART_PTCR_RXTDIS | UART_PTCR_TXTDIS;
-
- // Reset and disable receiver and transmitter
- UART->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS | UART_CR_TXDIS;
-
- // Configure mode: 8bit, No parity, 1 bit stop
- UART->UART_MR = UART_MR_CHMODE_NORMAL | US_MR_CHRL_8_BIT | US_MR_NBSTOP_1_BIT | UART_MR_PAR_NO;
-
- // Configure baudrate (asynchronous, no oversampling) to BAUDRATE bauds
- UART->UART_BRGR = (SystemCoreClock / (BAUDRATE << 4));
-
- // Enable receiver and transmitter
- UART->UART_CR = UART_CR_RXEN | UART_CR_TXEN;
-}
-
-// Send character through UART with no interrupts
-static void TX(char c) {
- while (!(UART->UART_SR & UART_SR_TXRDY)) { WDT_Restart(WDT); sw_barrier(); };
- UART->UART_THR = c;
-}
-
-// Send String through UART
-static void TX(const char* s) {
- while (*s) TX(*s++);
-}
-
-static void TXDigit(uint32_t d) {
- if (d < 10) TX((char)(d+'0'));
- else if (d < 16) TX((char)(d+'A'-10));
- else TX('?');
-}
-
-// Send Hex number thru UART
-static void TXHex(uint32_t v) {
- TX("0x");
- for (uint8_t i = 0; i < 8; i++, v <<= 4)
- TXDigit((v >> 28) & 0xF);
-}
-
-// Send Decimal number thru UART
-static void TXDec(uint32_t v) {
- if (!v) {
- TX('0');
- return;
- }
-
- char nbrs[14];
- char *p = &nbrs[0];
- while (v != 0) {
- *p++ = '0' + (v % 10);
- v /= 10;
- }
- do {
- p--;
- TX(*p);
- } while (p != &nbrs[0]);
-}
-
-// Dump a backtrace entry
-static bool UnwReportOut(void* ctx, const UnwReport* bte) {
- int* p = (int*)ctx;
-
- (*p)++;
- TX('#'); TXDec(*p); TX(" : ");
- TX(bte->name?bte->name:"unknown"); TX('@'); TXHex(bte->function);
- TX('+'); TXDec(bte->address - bte->function);
- TX(" PC:");TXHex(bte->address); TX('\n');
- return true;
-}
-
-#ifdef UNW_DEBUG
- void UnwPrintf(const char* format, ...) {
- char dest[256];
- va_list argptr;
- va_start(argptr, format);
- vsprintf(dest, format, argptr);
- va_end(argptr);
- TX(&dest[0]);
- }
-#endif
-
-/* Table of function pointers for passing to the unwinder */
-static const UnwindCallbacks UnwCallbacks = {
- UnwReportOut,
- UnwReadW,
- UnwReadH,
- UnwReadB
- #ifdef UNW_DEBUG
- , UnwPrintf
- #endif
-};
-
-/**
- * HardFaultHandler_C:
- * This is called from the HardFault_HandlerAsm with a pointer the Fault stack
- * as the parameter. We can then read the values from the stack and place them
- * into local variables for ease of reading.
- * We then read the various Fault Status and Address Registers to help decode
- * cause of the fault.
- * The function ends with a BKPT instruction to force control back into the debugger
- */
-extern "C"
-void HardFault_HandlerC(unsigned long *sp, unsigned long lr, unsigned long cause) {
-
- static const char* causestr[] = {
- "NMI","Hard","Mem","Bus","Usage","Debug","WDT","RSTC"
- };
-
- UnwindFrame btf;
-
- // Dump report to the Programming port (interrupts are DISABLED)
- TXBegin();
- TX("\n\n## Software Fault detected ##\n");
- TX("Cause: "); TX(causestr[cause]); TX('\n');
-
- TX("R0 : "); TXHex(((unsigned long)sp[0])); TX('\n');
- TX("R1 : "); TXHex(((unsigned long)sp[1])); TX('\n');
- TX("R2 : "); TXHex(((unsigned long)sp[2])); TX('\n');
- TX("R3 : "); TXHex(((unsigned long)sp[3])); TX('\n');
- TX("R12 : "); TXHex(((unsigned long)sp[4])); TX('\n');
- TX("LR : "); TXHex(((unsigned long)sp[5])); TX('\n');
- TX("PC : "); TXHex(((unsigned long)sp[6])); TX('\n');
- TX("PSR : "); TXHex(((unsigned long)sp[7])); TX('\n');
-
- // Configurable Fault Status Register
- // Consists of MMSR, BFSR and UFSR
- TX("CFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED28)))); TX('\n');
-
- // Hard Fault Status Register
- TX("HFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED2C)))); TX('\n');
-
- // Debug Fault Status Register
- TX("DFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED30)))); TX('\n');
-
- // Auxiliary Fault Status Register
- TX("AFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED3C)))); TX('\n');
-
- // Read the Fault Address Registers. These may not contain valid values.
- // Check BFARVALID/MMARVALID to see if they are valid values
- // MemManage Fault Address Register
- TX("MMAR : "); TXHex((*((volatile unsigned long *)(0xE000ED34)))); TX('\n');
-
- // Bus Fault Address Register
- TX("BFAR : "); TXHex((*((volatile unsigned long *)(0xE000ED38)))); TX('\n');
-
- TX("ExcLR: "); TXHex(lr); TX('\n');
- TX("ExcSP: "); TXHex((unsigned long)sp); TX('\n');
-
- btf.sp = ((unsigned long)sp) + 8*4; // The original stack pointer
- btf.fp = btf.sp;
- btf.lr = ((unsigned long)sp[5]);
- btf.pc = ((unsigned long)sp[6]) | 1; // Force Thumb, as CORTEX only support it
-
- // Perform a backtrace
- TX("\nBacktrace:\n\n");
- int ctr = 0;
- UnwindStart(&btf, &UnwCallbacks, &ctr);
-
- // Disable all NVIC interrupts
- NVIC->ICER[0] = 0xFFFFFFFF;
- NVIC->ICER[1] = 0xFFFFFFFF;
-
- // Relocate VTOR table to default position
- SCB->VTOR = 0;
-
- // Disable USB
- otg_disable();
-
- // Restart watchdog
- WDT_Restart(WDT);
-
- // Reset controller
- NVIC_SystemReset();
- for (;;) WDT_Restart(WDT);
-}
-
-__attribute__((naked)) void NMI_Handler() {
- __asm__ __volatile__ (
- ".syntax unified" "\n\t"
- A("tst lr, #4")
- A("ite eq")
- A("mrseq r0, msp")
- A("mrsne r0, psp")
- A("mov r1,lr")
- A("mov r2,#0")
- A("b HardFault_HandlerC")
- );
-}
-
-__attribute__((naked)) void HardFault_Handler() {
- __asm__ __volatile__ (
- ".syntax unified" "\n\t"
- A("tst lr, #4")
- A("ite eq")
- A("mrseq r0, msp")
- A("mrsne r0, psp")
- A("mov r1,lr")
- A("mov r2,#1")
- A("b HardFault_HandlerC")
- );
-}
-
-__attribute__((naked)) void MemManage_Handler() {
- __asm__ __volatile__ (
- ".syntax unified" "\n\t"
- A("tst lr, #4")
- A("ite eq")
- A("mrseq r0, msp")
- A("mrsne r0, psp")
- A("mov r1,lr")
- A("mov r2,#2")
- A("b HardFault_HandlerC")
- );
-}
-
-__attribute__((naked)) void BusFault_Handler() {
- __asm__ __volatile__ (
- ".syntax unified" "\n\t"
- A("tst lr, #4")
- A("ite eq")
- A("mrseq r0, msp")
- A("mrsne r0, psp")
- A("mov r1,lr")
- A("mov r2,#3")
- A("b HardFault_HandlerC")
- );
-}
-
-__attribute__((naked)) void UsageFault_Handler() {
- __asm__ __volatile__ (
- ".syntax unified" "\n\t"
- A("tst lr, #4")
- A("ite eq")
- A("mrseq r0, msp")
- A("mrsne r0, psp")
- A("mov r1,lr")
- A("mov r2,#4")
- A("b HardFault_HandlerC")
- );
-}
-
-__attribute__((naked)) void DebugMon_Handler() {
- __asm__ __volatile__ (
- ".syntax unified" "\n\t"
- A("tst lr, #4")
- A("ite eq")
- A("mrseq r0, msp")
- A("mrsne r0, psp")
- A("mov r1,lr")
- A("mov r2,#5")
- A("b HardFault_HandlerC")
- );
-}
-
-/* This is NOT an exception, it is an interrupt handler - Nevertheless, the framing is the same */
-__attribute__((naked)) void WDT_Handler() {
- __asm__ __volatile__ (
- ".syntax unified" "\n\t"
- A("tst lr, #4")
- A("ite eq")
- A("mrseq r0, msp")
- A("mrsne r0, psp")
- A("mov r1,lr")
- A("mov r2,#6")
- A("b HardFault_HandlerC")
- );
-}
-
-__attribute__((naked)) void RSTC_Handler() {
- __asm__ __volatile__ (
- ".syntax unified" "\n\t"
- A("tst lr, #4")
- A("ite eq")
- A("mrseq r0, msp")
- A("mrsne r0, psp")
- A("mov r1,lr")
- A("mov r2,#7")
- A("b HardFault_HandlerC")
- );
-}
-
-#endif // ARDUINO_ARCH_SAM
diff --git a/Marlin/src/HAL/DUE/HAL.cpp b/Marlin/src/HAL/DUE/HAL.cpp
index 6ce85a4643bb..a3985652e71d 100644
--- a/Marlin/src/HAL/DUE/HAL.cpp
+++ b/Marlin/src/HAL/DUE/HAL.cpp
@@ -40,6 +40,8 @@ uint16_t HAL_adc_result;
// Public functions
// ------------------------
+TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
+
// HAL initialization task
void HAL_init() {
// Initialize the USB stack
@@ -47,6 +49,7 @@ void HAL_init() {
OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up
#endif
usb_task_init();
+ TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler
}
// HAL idle task
@@ -74,6 +77,8 @@ uint8_t HAL_get_reset_source() {
}
}
+void HAL_reboot() { rstc_start_software_reset(RSTC); }
+
void _delay_ms(const int delay_ms) {
// Todo: port for Due?
delay(delay_ms);
@@ -102,4 +107,18 @@ uint16_t HAL_adc_get_result() {
return HAL_adc_result;
}
+// Forward the default serial ports
+#if USING_HW_SERIAL0
+ DefaultSerial1 MSerial0(false, Serial);
+#endif
+#if USING_HW_SERIAL1
+ DefaultSerial2 MSerial1(false, Serial1);
+#endif
+#if USING_HW_SERIAL2
+ DefaultSerial3 MSerial2(false, Serial2);
+#endif
+#if USING_HW_SERIAL3
+ DefaultSerial4 MSerial3(false, Serial3);
+#endif
+
#endif // ARDUINO_ARCH_SAM
diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h
index 395ca4ccc971..92e26bcf4362 100644
--- a/Marlin/src/HAL/DUE/HAL.h
+++ b/Marlin/src/HAL/DUE/HAL.h
@@ -36,36 +36,61 @@
#include
-#define _MSERIAL(X) Serial##X
+#include "../../core/serial_hook.h"
+
+typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1;
+typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2;
+typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3;
+typedef ForwardSerial1Class< decltype(Serial3) > DefaultSerial4;
+extern DefaultSerial1 MSerial0;
+extern DefaultSerial2 MSerial1;
+extern DefaultSerial3 MSerial2;
+extern DefaultSerial4 MSerial3;
+
+#define _MSERIAL(X) MSerial##X
#define MSERIAL(X) _MSERIAL(X)
-#define Serial0 Serial
-// Define MYSERIAL0/1 before MarlinSerial includes!
#if SERIAL_PORT == -1 || ENABLED(EMERGENCY_PARSER)
- #define MYSERIAL0 customizedSerial1
+ #define MYSERIAL1 customizedSerial1
#elif WITHIN(SERIAL_PORT, 0, 3)
- #define MYSERIAL0 MSERIAL(SERIAL_PORT)
+ #define MYSERIAL1 MSERIAL(SERIAL_PORT)
#else
- #error "The required SERIAL_PORT must be from -1 to 3. Please update your configuration."
+ #error "The required SERIAL_PORT must be from 0 to 3, or -1 for USB Serial."
#endif
#ifdef SERIAL_PORT_2
#if SERIAL_PORT_2 == -1 || ENABLED(EMERGENCY_PARSER)
- #define MYSERIAL1 customizedSerial2
+ #define MYSERIAL2 customizedSerial2
#elif WITHIN(SERIAL_PORT_2, 0, 3)
- #define MYSERIAL1 MSERIAL(SERIAL_PORT_2)
+ #define MYSERIAL2 MSERIAL(SERIAL_PORT_2)
#else
- #error "SERIAL_PORT_2 must be from -1 to 3. Please update your configuration."
+ #error "SERIAL_PORT_2 must be from 0 to 3, or -1 for USB Serial."
+ #endif
+#endif
+
+#ifdef SERIAL_PORT_3
+ #if SERIAL_PORT_3 == -1 || ENABLED(EMERGENCY_PARSER)
+ #define MYSERIAL3 customizedSerial3
+ #elif WITHIN(SERIAL_PORT_3, 0, 3)
+ #define MYSERIAL3 MSERIAL(SERIAL_PORT_3)
+ #else
+ #error "SERIAL_PORT_3 must be from 0 to 3, or -1 for USB Serial."
+ #endif
+#endif
+
+#ifdef MMU2_SERIAL_PORT
+ #if WITHIN(MMU2_SERIAL_PORT, 0, 3)
+ #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT)
+ #else
+ #error "MMU2_SERIAL_PORT must be from 0 to 3."
#endif
#endif
#ifdef LCD_SERIAL_PORT
- #if LCD_SERIAL_PORT == -1
- #define LCD_SERIAL lcdSerial
- #elif WITHIN(LCD_SERIAL_PORT, 0, 3)
+ #if WITHIN(LCD_SERIAL_PORT, 0, 3)
#define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT)
#else
- #error "LCD_SERIAL_PORT must be from -1 to 3. Please update your configuration."
+ #error "LCD_SERIAL_PORT must be from 0 to 3."
#endif
#endif
@@ -75,16 +100,6 @@
// On AVR this is in math.h?
#define square(x) ((x)*(x))
-#ifndef strncpy_P
- #define strncpy_P(dest, src, num) strncpy((dest), (src), (num))
-#endif
-
-// Fix bug in pgm_read_ptr
-#undef pgm_read_ptr
-#define pgm_read_ptr(addr) (*((void**)(addr)))
-#undef pgm_read_word
-#define pgm_read_word(addr) (*((uint16_t*)(addr)))
-
typedef int8_t pin_t;
#define SHARED_SERVOS HAS_SERVOS
@@ -105,7 +120,7 @@ void sei(); // Enable interrupts
void HAL_clear_reset_source(); // clear reset reason
uint8_t HAL_get_reset_source(); // get reset reason
-inline void HAL_reboot() {} // reboot the board or restart the bootloader
+void HAL_reboot();
//
// ADC
diff --git a/Marlin/src/HAL/DUE/HAL_MinSerial.cpp b/Marlin/src/HAL/DUE/HAL_MinSerial.cpp
new file mode 100644
index 000000000000..93c4ed67d63c
--- /dev/null
+++ b/Marlin/src/HAL/DUE/HAL_MinSerial.cpp
@@ -0,0 +1,91 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#ifdef ARDUINO_ARCH_SAM
+
+#include "../../inc/MarlinConfigPre.h"
+
+#if ENABLED(POSTMORTEM_DEBUGGING)
+
+#include "../shared/HAL_MinSerial.h"
+
+#include
+
+static void TXBegin() {
+ // Disable UART interrupt in NVIC
+ NVIC_DisableIRQ( UART_IRQn );
+
+ // We NEED memory barriers to ensure Interrupts are actually disabled!
+ // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
+ __DSB();
+ __ISB();
+
+ // Disable clock
+ pmc_disable_periph_clk( ID_UART );
+
+ // Configure PMC
+ pmc_enable_periph_clk( ID_UART );
+
+ // Disable PDC channel
+ UART->UART_PTCR = UART_PTCR_RXTDIS | UART_PTCR_TXTDIS;
+
+ // Reset and disable receiver and transmitter
+ UART->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS | UART_CR_TXDIS;
+
+ // Configure mode: 8bit, No parity, 1 bit stop
+ UART->UART_MR = UART_MR_CHMODE_NORMAL | US_MR_CHRL_8_BIT | US_MR_NBSTOP_1_BIT | UART_MR_PAR_NO;
+
+ // Configure baudrate (asynchronous, no oversampling) to BAUDRATE bauds
+ UART->UART_BRGR = (SystemCoreClock / (BAUDRATE << 4));
+
+ // Enable receiver and transmitter
+ UART->UART_CR = UART_CR_RXEN | UART_CR_TXEN;
+}
+
+// A SW memory barrier, to ensure GCC does not overoptimize loops
+#define sw_barrier() __asm__ volatile("": : :"memory");
+static void TX(char c) {
+ while (!(UART->UART_SR & UART_SR_TXRDY)) { WDT_Restart(WDT); sw_barrier(); };
+ UART->UART_THR = c;
+}
+
+void install_min_serial() {
+ HAL_min_serial_init = &TXBegin;
+ HAL_min_serial_out = &TX;
+}
+
+#if DISABLED(DYNAMIC_VECTORTABLE)
+extern "C" {
+ __attribute__((naked)) void JumpHandler_ASM() {
+ __asm__ __volatile__ (
+ "b CommonHandler_ASM\n"
+ );
+ }
+ void __attribute__((naked, alias("JumpHandler_ASM"))) HardFault_Handler();
+ void __attribute__((naked, alias("JumpHandler_ASM"))) BusFault_Handler();
+ void __attribute__((naked, alias("JumpHandler_ASM"))) UsageFault_Handler();
+ void __attribute__((naked, alias("JumpHandler_ASM"))) MemManage_Handler();
+ void __attribute__((naked, alias("JumpHandler_ASM"))) NMI_Handler();
+}
+#endif
+
+#endif // POSTMORTEM_DEBUGGING
+#endif // ARDUINO_ARCH_SAM
diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp
index 342c37373538..f42e8a98027c 100644
--- a/Marlin/src/HAL/DUE/HAL_SPI.cpp
+++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp
@@ -56,8 +56,8 @@
#pragma GCC optimize (3)
typedef uint8_t (*pfnSpiTransfer)(uint8_t b);
- typedef void (*pfnSpiRxBlock)(uint8_t* buf, uint32_t nbyte);
- typedef void (*pfnSpiTxBlock)(const uint8_t* buf, uint32_t nbyte);
+ typedef void (*pfnSpiRxBlock)(uint8_t *buf, uint32_t nbyte);
+ typedef void (*pfnSpiTxBlock)(const uint8_t *buf, uint32_t nbyte);
/* ---------------- Macros to be able to access definitions from asm */
#define _PORT(IO) DIO ## IO ## _WPORT
@@ -240,7 +240,7 @@
}
// all the others
- static uint32_t spiDelayCyclesX4 = (F_CPU) / 1000000; // 4µs => 125khz
+ static uint32_t spiDelayCyclesX4 = 4 * (F_CPU) / 1000000; // 4µs => 125khz
static uint8_t spiTransferX(uint8_t b) { // using Mode 0
int bits = 8;
@@ -249,12 +249,12 @@
b <<= 1; // little setup time
WRITE(SD_SCK_PIN, HIGH);
- __delay_4cycles(spiDelayCyclesX4);
+ DELAY_CYCLES(spiDelayCyclesX4);
b |= (READ(SD_MISO_PIN) != 0);
WRITE(SD_SCK_PIN, LOW);
- __delay_4cycles(spiDelayCyclesX4);
+ DELAY_CYCLES(spiDelayCyclesX4);
} while (--bits);
return b;
}
@@ -270,7 +270,7 @@
static pfnSpiTransfer spiTransferTx = (pfnSpiTransfer)spiTransferX;
// Block transfers run at ~8 .. ~10Mhz - Tx version (Rx data discarded)
- static void spiTxBlock0(const uint8_t* ptr, uint32_t todo) {
+ static void spiTxBlock0(const uint8_t *ptr, uint32_t todo) {
uint32_t MOSI_PORT_PLUS30 = ((uint32_t) PORT(SD_MOSI_PIN)) + 0x30; /* SODR of port */
uint32_t MOSI_MASK = PIN_MASK(SD_MOSI_PIN);
uint32_t SCK_PORT_PLUS30 = ((uint32_t) PORT(SD_SCK_PIN)) + 0x30; /* SODR of port */
@@ -349,7 +349,7 @@
);
}
- static void spiRxBlock0(uint8_t* ptr, uint32_t todo) {
+ static void spiRxBlock0(uint8_t *ptr, uint32_t todo) {
uint32_t bin = 0;
uint32_t work = 0;
uint32_t BITBAND_MISO_PORT = BITBAND_ADDRESS( ((uint32_t)PORT(SD_MISO_PIN))+0x3C, PIN_SHIFT(SD_MISO_PIN)); /* PDSR of port in bitband area */
@@ -425,13 +425,13 @@
);
}
- static void spiTxBlockX(const uint8_t* buf, uint32_t todo) {
+ static void spiTxBlockX(const uint8_t *buf, uint32_t todo) {
do {
(void)spiTransferTx(*buf++);
} while (--todo);
}
- static void spiRxBlockX(uint8_t* buf, uint32_t todo) {
+ static void spiRxBlockX(uint8_t *buf, uint32_t todo) {
do {
*buf++ = spiTransferRx(0xFF);
} while (--todo);
@@ -463,7 +463,7 @@
return b;
}
- void spiRead(uint8_t* buf, uint16_t nbyte) {
+ void spiRead(uint8_t *buf, uint16_t nbyte) {
if (nbyte) {
_SS_WRITE(LOW);
WRITE(SD_MOSI_PIN, HIGH); // Output 1s 1
@@ -478,7 +478,7 @@
_SS_WRITE(HIGH);
}
- void spiSendBlock(uint8_t token, const uint8_t* buf) {
+ void spiSendBlock(uint8_t token, const uint8_t *buf) {
_SS_WRITE(LOW);
(void)spiTransferTx(token);
spiTxBlock(buf, 512);
@@ -510,7 +510,7 @@
spiRxBlock = (pfnSpiRxBlock)spiRxBlockX;
break;
default:
- spiDelayCyclesX4 = ((F_CPU) / 1000000) >> (6 - spiRate);
+ spiDelayCyclesX4 = ((F_CPU) / 1000000) >> (6 - spiRate) << 2; // spiRate of 2 gives the maximum error with current CPU
spiTransferTx = (pfnSpiTransfer)spiTransferX;
spiTransferRx = (pfnSpiTransfer)spiTransferX;
spiTxBlock = (pfnSpiTxBlock)spiTxBlockX;
@@ -645,7 +645,7 @@
}
// Read from SPI into buffer
- void spiRead(uint8_t* buf, uint16_t nbyte) {
+ void spiRead(uint8_t *buf, uint16_t nbyte) {
if (!nbyte) return;
--nbyte;
for (int i = 0; i < nbyte; i++) {
@@ -668,7 +668,7 @@
//DELAY_US(1U);
}
- void spiSend(const uint8_t* buf, size_t nbyte) {
+ void spiSend(const uint8_t *buf, size_t nbyte) {
if (!nbyte) return;
--nbyte;
for (size_t i = 0; i < nbyte; i++) {
@@ -689,7 +689,7 @@
FLUSH_RX();
}
- void spiSend(uint32_t chan, const uint8_t* buf, size_t nbyte) {
+ void spiSend(uint32_t chan, const uint8_t *buf, size_t nbyte) {
if (!nbyte) return;
--nbyte;
for (size_t i = 0; i < nbyte; i++) {
@@ -702,7 +702,7 @@
}
// Write from buffer to SPI
- void spiSendBlock(uint8_t token, const uint8_t* buf) {
+ void spiSendBlock(uint8_t token, const uint8_t *buf) {
SPI0->SPI_TDR = (uint32_t)token | SPI_PCS(SPI_CHAN);
WHILE_TX(0);
//WHILE_RX(0);
@@ -801,19 +801,19 @@
uint8_t spiRec() { return (uint8_t)spiTransfer(0xFF); }
- void spiRead(uint8_t* buf, uint16_t nbyte) {
+ void spiRead(uint8_t *buf, uint16_t nbyte) {
for (int i = 0; i < nbyte; i++)
buf[i] = spiTransfer(0xFF);
}
void spiSend(uint8_t data) { spiTransfer(data); }
- void spiSend(const uint8_t* buf, size_t nbyte) {
+ void spiSend(const uint8_t *buf, size_t nbyte) {
for (uint16_t i = 0; i < nbyte; i++)
spiTransfer(buf[i]);
}
- void spiSendBlock(uint8_t token, const uint8_t* buf) {
+ void spiSendBlock(uint8_t token, const uint8_t *buf) {
spiTransfer(token);
for (uint16_t i = 0; i < 512; i++)
spiTransfer(buf[i]);
diff --git a/Marlin/src/HAL/DUE/MarlinSerial.cpp b/Marlin/src/HAL/DUE/MarlinSerial.cpp
index c9a372eeb14f..fe62ff5607d5 100644
--- a/Marlin/src/HAL/DUE/MarlinSerial.cpp
+++ b/Marlin/src/HAL/DUE/MarlinSerial.cpp
@@ -382,7 +382,7 @@ void MarlinSerial::flush() {
}
template
-void MarlinSerial::write(const uint8_t c) {
+size_t MarlinSerial::write(const uint8_t c) {
_written = true;
if (Cfg::TX_SIZE == 0) {
@@ -400,7 +400,7 @@ void MarlinSerial::write(const uint8_t c) {
// XOFF char at the RX isr, but it is properly handled there
if (!(HWUART->UART_IMR & UART_IMR_TXRDY) && (HWUART->UART_SR & UART_SR_TXRDY)) {
HWUART->UART_THR = c;
- return;
+ return 1;
}
const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1);
@@ -428,6 +428,7 @@ void MarlinSerial::write(const uint8_t c) {
// Enable TX isr - Non atomic, but it will eventually enable TX isr
HWUART->UART_IER = UART_IER_TXRDY;
}
+ return 1;
}
template
@@ -473,169 +474,21 @@ void MarlinSerial::flushTX() {
}
}
-/**
- * Imports from print.h
- */
-
-template
-void MarlinSerial::print(char c, int base) {
- print((long)c, base);
-}
-
-template
-void MarlinSerial::print(unsigned char b, int base) {
- print((unsigned long)b, base);
-}
-
-template
-void MarlinSerial::print(int n, int base) {
- print((long)n, base);
-}
-
-template
-void MarlinSerial::print(unsigned int n, int base) {
- print((unsigned long)n, base);
-}
-
-template
-void MarlinSerial::print(long n, int base) {
- if (base == 0) write(n);
- else if (base == 10) {
- if (n < 0) { print('-'); n = -n; }
- printNumber(n, 10);
- }
- else
- printNumber(n, base);
-}
-
-template
-void MarlinSerial::print(unsigned long n, int base) {
- if (base == 0) write(n);
- else printNumber(n, base);
-}
-
-template
-void MarlinSerial::print(double n, int digits) {
- printFloat(n, digits);
-}
-
-template
-void MarlinSerial::println() {
- print('\r');
- print('\n');
-}
-
-template
-void MarlinSerial::println(const String& s) {
- print(s);
- println();
-}
-
-template
-void MarlinSerial::println(const char c[]) {
- print(c);
- println();
-}
-
-template
-void MarlinSerial::println(char c, int base) {
- print(c, base);
- println();
-}
-
-template
-void MarlinSerial::println(unsigned char b, int base) {
- print(b, base);
- println();
-}
-
-template
-void MarlinSerial::println(int n, int base) {
- print(n, base);
- println();
-}
-
-template
-void MarlinSerial::println(unsigned int n, int base) {
- print(n, base);
- println();
-}
-
-template
-void MarlinSerial::println(long n, int base) {
- print(n, base);
- println();
-}
-
-template
-void MarlinSerial::println(unsigned long n, int base) {
- print(n, base);
- println();
-}
-
-template
-void MarlinSerial::println(double n, int digits) {
- print(n, digits);
- println();
-}
-
-// Private Methods
-template
-void MarlinSerial::printNumber(unsigned long n, uint8_t base) {
- if (n) {
- unsigned char buf[8 * sizeof(long)]; // Enough space for base 2
- int8_t i = 0;
- while (n) {
- buf[i++] = n % base;
- n /= base;
- }
- while (i--)
- print((char)(buf[i] + (buf[i] < 10 ? '0' : 'A' - 10)));
- }
- else
- print('0');
-}
-
-template
-void MarlinSerial::printFloat(double number, uint8_t digits) {
- // Handle negative numbers
- if (number < 0.0) {
- print('-');
- number = -number;
- }
-
- // Round correctly so that print(1.999, 2) prints as "2.00"
- double rounding = 0.5;
- LOOP_L_N(i, digits) rounding *= 0.1;
- number += rounding;
-
- // Extract the integer part of the number and print it
- unsigned long int_part = (unsigned long)number;
- double remainder = number - (double)int_part;
- print(int_part);
-
- // Print the decimal point, but only if there are digits beyond
- if (digits) {
- print('.');
- // Extract digits from the remainder one at a time
- while (digits--) {
- remainder *= 10.0;
- int toPrint = int(remainder);
- print(toPrint);
- remainder -= toPrint;
- }
- }
-}
// If not using the USB port as serial port
-#if SERIAL_PORT >= 0
- template class MarlinSerial>; // Define
- MarlinSerial> customizedSerial1; // Instantiate
+#if defined(SERIAL_PORT) && SERIAL_PORT >= 0
+ template class MarlinSerial< MarlinSerialCfg >;
+ MSerialT1 customizedSerial1(MarlinSerialCfg::EMERGENCYPARSER);
#endif
#if defined(SERIAL_PORT_2) && SERIAL_PORT_2 >= 0
- template class MarlinSerial>; // Define
- MarlinSerial> customizedSerial2; // Instantiate
+ template class MarlinSerial< MarlinSerialCfg >;
+ MSerialT2 customizedSerial2(MarlinSerialCfg::EMERGENCYPARSER);
+#endif
+
+#if defined(SERIAL_PORT_3) && SERIAL_PORT_3 >= 0
+ template class MarlinSerial< MarlinSerialCfg >;
+ MSerialT3 customizedSerial3(MarlinSerialCfg::EMERGENCYPARSER);
#endif
#endif // ARDUINO_ARCH_SAM
diff --git a/Marlin/src/HAL/DUE/MarlinSerial.h b/Marlin/src/HAL/DUE/MarlinSerial.h
index a194eba2f386..4a62e2834f7f 100644
--- a/Marlin/src/HAL/DUE/MarlinSerial.h
+++ b/Marlin/src/HAL/DUE/MarlinSerial.h
@@ -30,11 +30,7 @@
#include
#include "../../inc/MarlinConfigPre.h"
-
-#define DEC 10
-#define HEX 16
-#define OCT 8
-#define BIN 2
+#include "../../core/serial_hook.h"
// Define constants and variables for buffering incoming serial data. We're
// using a ring buffer (I think), in which rx_buffer_head is the index of the
@@ -119,7 +115,7 @@ class MarlinSerial {
static int read();
static void flush();
static ring_buffer_pos_t available();
- static void write(const uint8_t c);
+ static size_t write(const uint8_t c);
static void flushTX();
static inline bool emergency_parser_enabled() { return Cfg::EMERGENCYPARSER; }
@@ -128,35 +124,6 @@ class MarlinSerial {
FORCE_INLINE static uint8_t buffer_overruns() { return Cfg::RX_OVERRUNS ? rx_buffer_overruns : 0; }
FORCE_INLINE static uint8_t framing_errors() { return Cfg::RX_FRAMING_ERRORS ? rx_framing_errors : 0; }
FORCE_INLINE static ring_buffer_pos_t rxMaxEnqueued() { return Cfg::MAX_RX_QUEUED ? rx_max_enqueued : 0; }
-
- FORCE_INLINE static void write(const char* str) { while (*str) write(*str++); }
- FORCE_INLINE static void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); }
- FORCE_INLINE static void print(const String& s) { for (int i = 0; i < (int)s.length(); i++) write(s[i]); }
- FORCE_INLINE static void print(const char* str) { write(str); }
-
- static void print(char, int = 0);
- static void print(unsigned char, int = 0);
- static void print(int, int = DEC);
- static void print(unsigned int, int = DEC);
- static void print(long, int = DEC);
- static void print(unsigned long, int = DEC);
- static void print(double, int = 2);
-
- static void println(const String& s);
- static void println(const char[]);
- static void println(char, int = 0);
- static void println(unsigned char, int = 0);
- static void println(int, int = DEC);
- static void println(unsigned int, int = DEC);
- static void println(long, int = DEC);
- static void println(unsigned long, int = DEC);
- static void println(double, int = 2);
- static void println();
- operator bool() { return true; }
-
-private:
- static void printNumber(unsigned long, const uint8_t);
- static void printFloat(double, uint8_t);
};
// Serial port configuration
@@ -173,10 +140,17 @@ struct MarlinSerialCfg {
static constexpr bool MAX_RX_QUEUED = ENABLED(SERIAL_STATS_MAX_RX_QUEUED);
};
-#if SERIAL_PORT >= 0
- extern MarlinSerial> customizedSerial1;
+#if defined(SERIAL_PORT) && SERIAL_PORT >= 0
+ typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT1;
+ extern MSerialT1 customizedSerial1;
#endif
#if defined(SERIAL_PORT_2) && SERIAL_PORT_2 >= 0
- extern MarlinSerial> customizedSerial2;
+ typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT2;
+ extern MSerialT2 customizedSerial2;
+#endif
+
+#if defined(SERIAL_PORT_3) && SERIAL_PORT_3 >= 0
+ typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT3;
+ extern MSerialT3 customizedSerial3;
#endif
diff --git a/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp b/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp
index a41dbfeb7a57..67c597da80c4 100644
--- a/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp
+++ b/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp
@@ -19,13 +19,13 @@
* along with this program. If not, see .
*
*/
+#ifdef ARDUINO_ARCH_SAM
/**
* MarlinSerial_Due.cpp - Hardware serial library for Arduino DUE
* Copyright (c) 2017 Eduardo José Tagle. All right reserved
* Based on MarlinSerial for AVR, copyright (c) 2006 Nicholas Zambetti. All right reserved.
*/
-#ifdef ARDUINO_ARCH_SAM
#include "../../inc/MarlinConfig.h"
@@ -33,10 +33,6 @@
#include "MarlinSerialUSB.h"
-#if ENABLED(EMERGENCY_PARSER)
- #include "../../feature/e_parser.h"
-#endif
-
// Imports from Atmel USB Stack/CDC implementation
extern "C" {
bool usb_task_cdc_isenabled();
@@ -50,10 +46,6 @@ extern "C" {
// Pending character
static int pending_char = -1;
-#if ENABLED(EMERGENCY_PARSER)
- static EmergencyParser::State emergency_state; // = EP_RESET
-#endif
-
// Public Methods
void MarlinSerialUSB::begin(const long) {}
@@ -73,7 +65,7 @@ int MarlinSerialUSB::peek() {
pending_char = udi_cdc_getc();
- TERN_(EMERGENCY_PARSER, emergency_parser.update(emergency_state, (char)pending_char));
+ TERN_(EMERGENCY_PARSER, emergency_parser.update(static_cast(this)->emergency_state, (char)pending_char));
return pending_char;
}
@@ -95,29 +87,27 @@ int MarlinSerialUSB::read() {
int c = udi_cdc_getc();
- TERN_(EMERGENCY_PARSER, emergency_parser.update(emergency_state, (char)c));
+ TERN_(EMERGENCY_PARSER, emergency_parser.update(static_cast(this)->emergency_state, (char)c));
return c;
}
-bool MarlinSerialUSB::available() {
- /* If Pending chars */
- return pending_char >= 0 ||
- /* or USB CDC enumerated and configured on the PC side and some
- bytes where sent to us */
- (usb_task_cdc_isenabled() && udi_cdc_is_rx_ready());
+int MarlinSerialUSB::available() {
+ if (pending_char > 0) return pending_char;
+ return pending_char == 0 ||
+ // or USB CDC enumerated and configured on the PC side and some bytes where sent to us */
+ (usb_task_cdc_isenabled() && udi_cdc_is_rx_ready());
}
void MarlinSerialUSB::flush() { }
-void MarlinSerialUSB::flushTX() { }
-void MarlinSerialUSB::write(const uint8_t c) {
+size_t MarlinSerialUSB::write(const uint8_t c) {
/* Do not even bother sending anything if USB CDC is not enumerated
or not configured on the PC side or there is no program on the PC
listening to our messages */
if (!usb_task_cdc_isenabled() || !usb_task_cdc_dtr_active())
- return;
+ return 0;
/* Wait until the PC has read the pending to be sent data */
while (usb_task_cdc_isenabled() &&
@@ -129,161 +119,23 @@ void MarlinSerialUSB::write(const uint8_t c) {
or not configured on the PC side or there is no program on the PC
listening to our messages at this point */
if (!usb_task_cdc_isenabled() || !usb_task_cdc_dtr_active())
- return;
+ return 0;
// Fifo full
// udi_cdc_signal_overrun();
udi_cdc_putc(c);
-}
-
-/**
- * Imports from print.h
- */
-
-void MarlinSerialUSB::print(char c, int base) {
- print((long)c, base);
-}
-
-void MarlinSerialUSB::print(unsigned char b, int base) {
- print((unsigned long)b, base);
-}
-
-void MarlinSerialUSB::print(int n, int base) {
- print((long)n, base);
-}
-
-void MarlinSerialUSB::print(unsigned int n, int base) {
- print((unsigned long)n, base);
-}
-
-void MarlinSerialUSB::print(long n, int base) {
- if (base == 0)
- write(n);
- else if (base == 10) {
- if (n < 0) {
- print('-');
- n = -n;
- }
- printNumber(n, 10);
- }
- else
- printNumber(n, base);
-}
-
-void MarlinSerialUSB::print(unsigned long n, int base) {
- if (base == 0) write(n);
- else printNumber(n, base);
-}
-
-void MarlinSerialUSB::print(double n, int digits) {
- printFloat(n, digits);
-}
-
-void MarlinSerialUSB::println() {
- print('\r');
- print('\n');
-}
-
-void MarlinSerialUSB::println(const String& s) {
- print(s);
- println();
-}
-
-void MarlinSerialUSB::println(const char c[]) {
- print(c);
- println();
-}
-
-void MarlinSerialUSB::println(char c, int base) {
- print(c, base);
- println();
-}
-
-void MarlinSerialUSB::println(unsigned char b, int base) {
- print(b, base);
- println();
-}
-
-void MarlinSerialUSB::println(int n, int base) {
- print(n, base);
- println();
-}
-
-void MarlinSerialUSB::println(unsigned int n, int base) {
- print(n, base);
- println();
-}
-
-void MarlinSerialUSB::println(long n, int base) {
- print(n, base);
- println();
-}
-
-void MarlinSerialUSB::println(unsigned long n, int base) {
- print(n, base);
- println();
-}
-
-void MarlinSerialUSB::println(double n, int digits) {
- print(n, digits);
- println();
-}
-
-// Private Methods
-
-void MarlinSerialUSB::printNumber(unsigned long n, uint8_t base) {
- if (n) {
- unsigned char buf[8 * sizeof(long)]; // Enough space for base 2
- int8_t i = 0;
- while (n) {
- buf[i++] = n % base;
- n /= base;
- }
- while (i--)
- print((char)(buf[i] + (buf[i] < 10 ? '0' : 'A' - 10)));
- }
- else
- print('0');
-}
-
-void MarlinSerialUSB::printFloat(double number, uint8_t digits) {
- // Handle negative numbers
- if (number < 0.0) {
- print('-');
- number = -number;
- }
-
- // Round correctly so that print(1.999, 2) prints as "2.00"
- double rounding = 0.5;
- LOOP_L_N(i, digits)
- rounding *= 0.1;
-
- number += rounding;
-
- // Extract the integer part of the number and print it
- unsigned long int_part = (unsigned long)number;
- double remainder = number - (double)int_part;
- print(int_part);
-
- // Print the decimal point, but only if there are digits beyond
- if (digits) {
- print('.');
- // Extract digits from the remainder one at a time
- while (digits--) {
- remainder *= 10.0;
- int toPrint = int(remainder);
- print(toPrint);
- remainder -= toPrint;
- }
- }
+ return 1;
}
// Preinstantiate
#if SERIAL_PORT == -1
- MarlinSerialUSB customizedSerial1;
+ MSerialT1 customizedSerial1(TERN0(EMERGENCY_PARSER, true));
#endif
#if SERIAL_PORT_2 == -1
- MarlinSerialUSB customizedSerial2;
+ MSerialT2 customizedSerial2(TERN0(EMERGENCY_PARSER, true));
+#endif
+#if SERIAL_PORT_3 == -1
+ MSerialT3 customizedSerial3(TERN0(EMERGENCY_PARSER, true));
#endif
#endif // HAS_USB_SERIAL
diff --git a/Marlin/src/HAL/DUE/MarlinSerialUSB.h b/Marlin/src/HAL/DUE/MarlinSerialUSB.h
index 2e3622e5534a..6da1ef8c08f6 100644
--- a/Marlin/src/HAL/DUE/MarlinSerialUSB.h
+++ b/Marlin/src/HAL/DUE/MarlinSerialUSB.h
@@ -27,73 +27,39 @@
*/
#include "../../inc/MarlinConfig.h"
-
-#if HAS_USB_SERIAL
+#include "../../core/serial_hook.h"
#include
-#define DEC 10
-#define HEX 16
-#define OCT 8
-#define BIN 2
-
-class MarlinSerialUSB {
-
-public:
- MarlinSerialUSB() {};
- static void begin(const long);
- static void end();
- static int peek();
- static int read();
- static void flush();
- static void flushTX();
- static bool available();
- static void write(const uint8_t c);
+struct MarlinSerialUSB {
+ void begin(const long);
+ void end();
+ int peek();
+ int read();
+ void flush();
+ int available();
+ size_t write(const uint8_t c);
#if ENABLED(SERIAL_STATS_DROPPED_RX)
- FORCE_INLINE static uint32_t dropped() { return 0; }
+ FORCE_INLINE uint32_t dropped() { return 0; }
#endif
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
- FORCE_INLINE static int rxMaxEnqueued() { return 0; }
+ FORCE_INLINE int rxMaxEnqueued() { return 0; }
#endif
-
- FORCE_INLINE static void write(const char* str) { while (*str) write(*str++); }
- FORCE_INLINE static void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); }
- FORCE_INLINE static void print(const String& s) { for (int i = 0; i < (int)s.length(); i++) write(s[i]); }
- FORCE_INLINE static void print(const char* str) { write(str); }
-
- static void print(char, int = 0);
- static void print(unsigned char, int = 0);
- static void print(int, int = DEC);
- static void print(unsigned int, int = DEC);
- static void print(long, int = DEC);
- static void print(unsigned long, int = DEC);
- static void print(double, int = 2);
-
- static void println(const String& s);
- static void println(const char[]);
- static void println(char, int = 0);
- static void println(unsigned char, int = 0);
- static void println(int, int = DEC);
- static void println(unsigned int, int = DEC);
- static void println(long, int = DEC);
- static void println(unsigned long, int = DEC);
- static void println(double, int = 2);
- static void println();
- operator bool() { return true; }
-
-private:
- static void printNumber(unsigned long, const uint8_t);
- static void printFloat(double, uint8_t);
};
#if SERIAL_PORT == -1
- extern MarlinSerialUSB customizedSerial1;
+ typedef Serial1Class MSerialT1;
+ extern MSerialT1 customizedSerial1;
#endif
#if SERIAL_PORT_2 == -1
- extern MarlinSerialUSB customizedSerial2;
+ typedef Serial1Class MSerialT2;
+ extern MSerialT2 customizedSerial2;
#endif
-#endif // HAS_USB_SERIAL
+#if SERIAL_PORT_3 == -1
+ typedef Serial1Class MSerialT3;
+ extern MSerialT3 customizedSerial3;
+#endif
diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp
index 7df180cbaa82..d01cd4dd6b27 100644
--- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp
+++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp
@@ -59,6 +59,7 @@
#if ENABLED(U8GLIB_ST7920)
+#include "../../../inc/MarlinConfig.h"
#include "../../shared/Delay.h"
#include
diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp
index 615a386c3542..4fb7a6e2c315 100644
--- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp
+++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp
@@ -59,6 +59,7 @@
#if HAS_MARLINUI_U8GLIB
+#include "../../../inc/MarlinConfig.h"
#include "../../shared/Delay.h"
#include
diff --git a/Marlin/src/HAL/DUE/eeprom_flash.cpp b/Marlin/src/HAL/DUE/eeprom_flash.cpp
index 209a5161ae02..b4cb9912b24f 100644
--- a/Marlin/src/HAL/DUE/eeprom_flash.cpp
+++ b/Marlin/src/HAL/DUE/eeprom_flash.cpp
@@ -135,11 +135,11 @@ static uint8_t buffer[256] = {0}, // The RAM buffer to accumulate writes
#define DEBUG_OUT ENABLED(EE_EMU_DEBUG)
#include "../../core/debug_out.h"
-static void ee_Dump(const int page, const void* data) {
+static void ee_Dump(const int page, const void *data) {
#ifdef EE_EMU_DEBUG
- const uint8_t* c = (const uint8_t*) data;
+ const uint8_t *c = (const uint8_t*) data;
char buffer[80];
sprintf_P(buffer, PSTR("Page: %d (0x%04x)\n"), page, page);
@@ -181,7 +181,7 @@ static void ee_Dump(const int page, const void* data) {
* @param data (pointer to the data buffer)
*/
__attribute__ ((long_call, section (".ramfunc")))
-static bool ee_PageWrite(uint16_t page, const void* data) {
+static bool ee_PageWrite(uint16_t page, const void *data) {
uint16_t i;
uint32_t addrflash = uint32_t(getFlashStorage(page));
@@ -293,8 +293,8 @@ static bool ee_PageWrite(uint16_t page, const void* data) {
ee_Dump(-page, data);
// Calculate count of changed bits
- uint32_t* p1 = (uint32_t*)addrflash;
- uint32_t* p2 = (uint32_t*)data;
+ uint32_t *p1 = (uint32_t*)addrflash;
+ uint32_t *p2 = (uint32_t*)data;
int count = 0;
for (i =0; i> 2; i++) {
if (p1[i] != p2[i]) {
@@ -470,7 +470,7 @@ static uint8_t ee_Read(uint32_t address, bool excludeRAMBuffer=false) {
for (int page = curPage - 1; page >= 0; --page) {
// Get a pointer to the flash page
- uint8_t* pflash = (uint8_t*)getFlashStorage(page + curGroup * PagesPerGroup);
+ uint8_t *pflash = (uint8_t*)getFlashStorage(page + curGroup * PagesPerGroup);
uint16_t i = 0;
while (i <= (PageSize - 4)) { /* (PageSize - 4) because otherwise, there is not enough room for data and headers */
@@ -550,7 +550,7 @@ static uint32_t ee_GetAddrRange(uint32_t address, bool excludeRAMBuffer=false) {
for (int page = curPage - 1; page >= 0; --page) {
// Get a pointer to the flash page
- uint8_t* pflash = (uint8_t*)getFlashStorage(page + curGroup * PagesPerGroup);
+ uint8_t *pflash = (uint8_t*)getFlashStorage(page + curGroup * PagesPerGroup);
uint16_t i = 0;
while (i <= (PageSize - 4)) { /* (PageSize - 4) because otherwise, there is not enough room for data and headers */
@@ -589,7 +589,7 @@ static uint32_t ee_GetAddrRange(uint32_t address, bool excludeRAMBuffer=false) {
}
static bool ee_IsPageClean(int page) {
- uint32_t* pflash = (uint32_t*) getFlashStorage(page);
+ uint32_t *pflash = (uint32_t*) getFlashStorage(page);
for (uint16_t i = 0; i < (PageSize >> 2); ++i)
if (*pflash++ != 0xFFFFFFFF) return false;
return true;
@@ -599,7 +599,7 @@ static bool ee_Flush(uint32_t overrideAddress = 0xFFFFFFFF, uint8_t overrideData
// Check if RAM buffer has something to be written
bool isEmpty = true;
- uint32_t* p = (uint32_t*) &buffer[0];
+ uint32_t *p = (uint32_t*) &buffer[0];
for (uint16_t j = 0; j < (PageSize >> 2); j++) {
if (*p++ != 0xFFFFFFFF) {
isEmpty = false;
@@ -976,14 +976,13 @@ bool PersistentStore::access_start() { ee_Init(); return true; }
bool PersistentStore::access_finish() { ee_Flush(); return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ uint16_t written = 0;
while (size--) {
uint8_t * const p = (uint8_t * const)pos;
uint8_t v = *value;
- // EEPROM has only ~100,000 write cycles,
- // so only write bytes that have changed!
- if (v != ee_Read(uint32_t(p))) {
+ if (v != ee_Read(uint32_t(p))) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed!
ee_Write(uint32_t(p), v);
- delay(2);
+ if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes
if (ee_Read(uint32_t(p)) != v) {
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
return true;
diff --git a/Marlin/src/HAL/DUE/eeprom_wired.cpp b/Marlin/src/HAL/DUE/eeprom_wired.cpp
index b488c36f1666..557a2f2cffa5 100644
--- a/Marlin/src/HAL/DUE/eeprom_wired.cpp
+++ b/Marlin/src/HAL/DUE/eeprom_wired.cpp
@@ -42,14 +42,13 @@ bool PersistentStore::access_start() { eeprom_init(); return true; }
bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ uint16_t written = 0;
while (size--) {
uint8_t * const p = (uint8_t * const)pos;
uint8_t v = *value;
- // EEPROM has only ~100,000 write cycles,
- // so only write bytes that have changed!
- if (v != eeprom_read_byte(p)) {
+ if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed!
eeprom_write_byte(p, v);
- delay(2);
+ if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes
if (eeprom_read_byte(p) != v) {
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
return true;
diff --git a/Marlin/src/HAL/DUE/endstop_interrupts.h b/Marlin/src/HAL/DUE/endstop_interrupts.h
index 999ada512761..9c7e2104882e 100644
--- a/Marlin/src/HAL/DUE/endstop_interrupts.h
+++ b/Marlin/src/HAL/DUE/endstop_interrupts.h
@@ -64,4 +64,10 @@ void setup_endstop_interrupts() {
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
+ TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
+ TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
+ TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
+ TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
+ TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
+ TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
}
diff --git a/Marlin/src/HAL/DUE/fastio.h b/Marlin/src/HAL/DUE/fastio.h
index 5fb8b4d01533..a609210d8130 100644
--- a/Marlin/src/HAL/DUE/fastio.h
+++ b/Marlin/src/HAL/DUE/fastio.h
@@ -33,7 +33,7 @@
* For ARDUINO_ARCH_SAM
* Note the code here was specifically crafted by disassembling what GCC produces
* out of it, so GCC is able to optimize it out as much as possible to the least
- * amount of instructions. Be very carefull if you modify them, as "clean code"
+ * amount of instructions. Be very careful if you modify them, as "clean code"
* leads to less efficient compiled code!!
*/
@@ -50,7 +50,7 @@
#define PWM_PIN(P) WITHIN(P, 2, 13)
#ifndef MASK
- #define MASK(PIN) (1 << PIN)
+ #define MASK(PIN) _BV(PIN)
#endif
/**
diff --git a/Marlin/src/HAL/DUE/inc/SanityCheck.h b/Marlin/src/HAL/DUE/inc/SanityCheck.h
index 26fb44f3980b..87b09cf29257 100644
--- a/Marlin/src/HAL/DUE/inc/SanityCheck.h
+++ b/Marlin/src/HAL/DUE/inc/SanityCheck.h
@@ -57,5 +57,5 @@
#endif
#if HAS_TMC_SW_SERIAL
- #error "TMC220x Software Serial is not supported on this platform."
+ #error "TMC220x Software Serial is not supported on the DUE platform."
#endif
diff --git a/Marlin/src/HAL/DUE/timers.cpp b/Marlin/src/HAL/DUE/timers.cpp
index 9b937d1a7c83..65073c510d7c 100644
--- a/Marlin/src/HAL/DUE/timers.cpp
+++ b/Marlin/src/HAL/DUE/timers.cpp
@@ -121,7 +121,7 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num) {
// missing from CMSIS: Check if interrupt is enabled or not
static bool NVIC_GetEnabledIRQ(IRQn_Type IRQn) {
- return (NVIC->ISER[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F))) != 0;
+ return TEST(NVIC->ISER[uint32_t(IRQn) >> 5], uint32_t(IRQn) & 0x1F);
}
bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
diff --git a/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp
index db5e82ec5502..3dcbbaecd28f 100644
--- a/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp
+++ b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp
@@ -32,7 +32,7 @@ Ctrl_status sd_mmc_spi_test_unit_ready() {
Ctrl_status sd_mmc_spi_read_capacity(uint32_t *nb_sector) {
if (!IS_SD_INSERTED() || IS_SD_PRINTING() || IS_SD_FILE_OPEN() || !card.isMounted())
return CTRL_NO_PRESENT;
- *nb_sector = card.getSd2Card().cardSize() - 1;
+ *nb_sector = card.diskIODriver()->cardSize() - 1;
return CTRL_GOOD;
}
@@ -68,30 +68,30 @@ Ctrl_status sd_mmc_spi_usb_read_10(uint32_t addr, uint16_t nb_sector) {
{
char buffer[80];
sprintf_P(buffer, PSTR("SDRD: %d @ 0x%08x\n"), nb_sector, addr);
- PORT_REDIRECT(0);
+ PORT_REDIRECT(SERIAL_PORTMASK(0));
SERIAL_ECHO(buffer);
}
#endif
// Start reading
- if (!card.getSd2Card().readStart(addr))
+ if (!card.diskIODriver()->readStart(addr))
return CTRL_FAIL;
// For each specified sector
while (nb_sector--) {
// Read a sector
- card.getSd2Card().readData(sector_buf);
+ card.diskIODriver()->readData(sector_buf);
// RAM -> USB
if (!udi_msc_trans_block(true, sector_buf, SD_MMC_BLOCK_SIZE, nullptr)) {
- card.getSd2Card().readStop();
+ card.diskIODriver()->readStop();
return CTRL_FAIL;
}
}
// Stop reading
- card.getSd2Card().readStop();
+ card.diskIODriver()->readStop();
// Done
return CTRL_GOOD;
@@ -108,12 +108,12 @@ Ctrl_status sd_mmc_spi_usb_write_10(uint32_t addr, uint16_t nb_sector) {
{
char buffer[80];
sprintf_P(buffer, PSTR("SDWR: %d @ 0x%08x\n"), nb_sector, addr);
- PORT_REDIRECT(0);
+ PORT_REDIRECT(SERIAL_PORTMASK(0));
SERIAL_ECHO(buffer);
}
#endif
- if (!card.getSd2Card().writeStart(addr, nb_sector))
+ if (!card.diskIODriver()->writeStart(addr, nb_sector))
return CTRL_FAIL;
// For each specified sector
@@ -121,16 +121,16 @@ Ctrl_status sd_mmc_spi_usb_write_10(uint32_t addr, uint16_t nb_sector) {
// USB -> RAM
if (!udi_msc_trans_block(false, sector_buf, SD_MMC_BLOCK_SIZE, nullptr)) {
- card.getSd2Card().writeStop();
+ card.diskIODriver()->writeStop();
return CTRL_FAIL;
}
// Write a sector
- card.getSd2Card().writeData(sector_buf);
+ card.diskIODriver()->writeData(sector_buf);
}
// Stop writing
- card.getSd2Card().writeStop();
+ card.diskIODriver()->writeStop();
// Done
return CTRL_GOOD;
diff --git a/Marlin/src/HAL/DUE/usb/udi_cdc.h b/Marlin/src/HAL/DUE/usb/udi_cdc.h
index 0ecf7bb00e5e..b61845011aa2 100644
--- a/Marlin/src/HAL/DUE/usb/udi_cdc.h
+++ b/Marlin/src/HAL/DUE/usb/udi_cdc.h
@@ -675,11 +675,11 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s
* - \code // Waits and gets a value on CDC line
int udi_cdc_getc(void);
// Reads a RAM buffer on CDC line
- iram_size_t udi_cdc_read_buf(int* buf, iram_size_t size);
+ iram_size_t udi_cdc_read_buf(int *buf, iram_size_t size);
// Puts a byte on CDC line
int udi_cdc_putc(int value);
// Writes a RAM buffer on CDC line
- iram_size_t udi_cdc_write_buf(const int* buf, iram_size_t size); \endcode
+ iram_size_t udi_cdc_write_buf(const int *buf, iram_size_t size); \endcode
*
* \section udi_cdc_use_cases Advanced use cases
* For more advanced use of the UDI CDC module, see the following use cases:
diff --git a/Marlin/src/HAL/DUE/usb/usb_task.c b/Marlin/src/HAL/DUE/usb/usb_task.c
index 66bdb265d881..54a808d7f4f1 100644
--- a/Marlin/src/HAL/DUE/usb/usb_task.c
+++ b/Marlin/src/HAL/DUE/usb/usb_task.c
@@ -264,7 +264,7 @@ bool usb_task_extra_string(void) {
** Handle device requests that the ASF stack doesn't
*/
bool usb_task_other_requests(void) {
- uint8_t* ptr = 0;
+ uint8_t *ptr = 0;
uint16_t size = 0;
if (Udd_setup_type() == USB_REQ_TYPE_VENDOR) {
@@ -322,7 +322,7 @@ void usb_task_init(void) {
char *sptr;
// Patch in the filament diameter
- sprintf_P(diam, PSTR("%d"), (int)((DEFAULT_NOMINAL_FILAMENT_DIA) * 1000.0));
+ itoa((int)((DEFAULT_NOMINAL_FILAMENT_DIA) * 1000), diam, 10);
// And copy it to the proper place, expanding it to unicode
sptr = &diam[0];
diff --git a/Marlin/src/HAL/ESP32/FlushableHardwareSerial.cpp b/Marlin/src/HAL/ESP32/FlushableHardwareSerial.cpp
index d4b2f42c5351..145662215a9b 100644
--- a/Marlin/src/HAL/ESP32/FlushableHardwareSerial.cpp
+++ b/Marlin/src/HAL/ESP32/FlushableHardwareSerial.cpp
@@ -20,14 +20,10 @@
*
*/
-#include "FlushableHardwareSerial.h"
-
#ifdef ARDUINO_ARCH_ESP32
-FlushableHardwareSerial::FlushableHardwareSerial(int uart_nr)
- : HardwareSerial(uart_nr)
-{}
+#include "FlushableHardwareSerial.h"
-FlushableHardwareSerial flushableSerial(0);
+Serial1Class flushableSerial(false, 0);
-#endif // ARDUINO_ARCH_ESP32
+#endif
diff --git a/Marlin/src/HAL/ESP32/FlushableHardwareSerial.h b/Marlin/src/HAL/ESP32/FlushableHardwareSerial.h
index b43caea13c1d..012dda8626b0 100644
--- a/Marlin/src/HAL/ESP32/FlushableHardwareSerial.h
+++ b/Marlin/src/HAL/ESP32/FlushableHardwareSerial.h
@@ -21,17 +21,14 @@
*/
#pragma once
-#ifdef ARDUINO_ARCH_ESP32
-
#include
+#include "../shared/Marduino.h"
+#include "../../core/serial_hook.h"
+
class FlushableHardwareSerial : public HardwareSerial {
public:
- FlushableHardwareSerial(int uart_nr);
-
- inline void flushTX() { /* No need to flush the hardware serial, but defined here for compatibility. */ }
+ FlushableHardwareSerial(int uart_nr) : HardwareSerial(uart_nr) {}
};
-extern FlushableHardwareSerial flushableSerial;
-
-#endif // ARDUINO_ARCH_ESP32
+extern Serial1Class flushableSerial;
diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp
index ead448d78d7a..7818dbdd87ea 100644
--- a/Marlin/src/HAL/ESP32/HAL.cpp
+++ b/Marlin/src/HAL/ESP32/HAL.cpp
@@ -40,6 +40,10 @@
#endif
#endif
+#if ENABLED(ESP3D_WIFISUPPORT)
+ DefaultSerial1 MSerial0(false, Serial2Socket);
+#endif
+
// ------------------------
// Externs
// ------------------------
@@ -86,8 +90,6 @@ volatile int numPWMUsed = 0,
#endif
-void HAL_init() { TERN_(I2S_STEPPER_STREAM, i2s_init()); }
-
void HAL_init_board() {
#if ENABLED(ESP3D_WIFISUPPORT)
@@ -122,6 +124,10 @@ void HAL_init_board() {
#endif
#endif
+ // Initialize the i2s peripheral only if the I2S stepper stream is enabled.
+ // The following initialization is performed after Serial1 and Serial2 are defined as
+ // their native pins might conflict with the i2s stream even when they are remapped.
+ TERN_(I2S_STEPPER_STREAM, i2s_init());
}
void HAL_idletask() {
@@ -135,6 +141,8 @@ void HAL_clear_reset_source() { }
uint8_t HAL_get_reset_source() { return rtc_get_reset_reason(1); }
+void HAL_reboot() { ESP.restart(); }
+
void _delay_ms(int delay_ms) { delay(delay_ms); }
// return free memory between end of heap (or end bss) and whatever is current
@@ -179,6 +187,7 @@ void HAL_adc_init() {
TERN_(HAS_TEMP_ADC_7, adc3_set_attenuation(get_channel(TEMP_7_PIN), ADC_ATTEN_11db));
TERN_(HAS_HEATED_BED, adc1_set_attenuation(get_channel(TEMP_BED_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_CHAMBER, adc1_set_attenuation(get_channel(TEMP_CHAMBER_PIN), ADC_ATTEN_11db));
+ TERN_(HAS_TEMP_COOLER, adc1_set_attenuation(get_channel(TEMP_COOLER_PIN), ADC_ATTEN_11db));
TERN_(FILAMENT_WIDTH_SENSOR, adc1_set_attenuation(get_channel(FILWIDTH_PIN), ADC_ATTEN_11db));
// Note that adc2 is shared with the WiFi module, which has higher priority, so the conversion may fail.
diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h
index 5ef13e0c21d4..0f920520306f 100644
--- a/Marlin/src/HAL/ESP32/HAL.h
+++ b/Marlin/src/HAL/ESP32/HAL.h
@@ -51,13 +51,15 @@
extern portMUX_TYPE spinlock;
-#define MYSERIAL0 flushableSerial
+#define MYSERIAL1 flushableSerial
#if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT)
#if ENABLED(ESP3D_WIFISUPPORT)
- #define MYSERIAL1 Serial2Socket
+ typedef ForwardSerial1Class< decltype(Serial2Socket) > DefaultSerial1;
+ extern DefaultSerial1 MSerial0;
+ #define MYSERIAL2 MSerial0
#else
- #define MYSERIAL1 webSocketSerial
+ #define MYSERIAL2 webSocketSerial
#endif
#endif
@@ -67,10 +69,6 @@ extern portMUX_TYPE spinlock;
#define ENABLE_ISRS() if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock)
#define DISABLE_ISRS() portENTER_CRITICAL(&spinlock)
-// Fix bug in pgm_read_ptr
-#undef pgm_read_ptr
-#define pgm_read_ptr(addr) (*(addr))
-
// ------------------------
// Types
// ------------------------
@@ -90,13 +88,20 @@ extern uint16_t HAL_adc_result;
// Public functions
// ------------------------
+//
+// Tone
+//
+void toneInit();
+void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0);
+void noTone(const pin_t _pin);
+
// clear reset reason
void HAL_clear_reset_source();
// reset reason
uint8_t HAL_get_reset_source();
-inline void HAL_reboot() {} // reboot the board or restart the bootloader
+void HAL_reboot();
void _delay_ms(int delay);
@@ -134,7 +139,7 @@ void HAL_adc_start_conversion(const uint8_t adc_pin);
#define HAL_IDLETASK 1
#define BOARD_INIT() HAL_init_board();
void HAL_idletask();
-void HAL_init();
+inline void HAL_init() {}
void HAL_init_board();
//
diff --git a/Marlin/src/HAL/ESP32/HAL_SPI.cpp b/Marlin/src/HAL/ESP32/HAL_SPI.cpp
index 8ee837ba1567..8743ac5be215 100644
--- a/Marlin/src/HAL/ESP32/HAL_SPI.cpp
+++ b/Marlin/src/HAL/ESP32/HAL_SPI.cpp
@@ -85,7 +85,7 @@ uint8_t spiRec() {
return returnByte;
}
-void spiRead(uint8_t* buf, uint16_t nbyte) {
+void spiRead(uint8_t *buf, uint16_t nbyte) {
SPI.beginTransaction(spiConfig);
SPI.transferBytes(0, buf, nbyte);
SPI.endTransaction();
@@ -97,7 +97,7 @@ void spiSend(uint8_t b) {
SPI.endTransaction();
}
-void spiSendBlock(uint8_t token, const uint8_t* buf) {
+void spiSendBlock(uint8_t token, const uint8_t *buf) {
SPI.beginTransaction(spiConfig);
SPI.transfer(token);
SPI.writeBytes(const_cast(buf), 512);
diff --git a/Marlin/src/HAL/ESP32/Servo.h b/Marlin/src/HAL/ESP32/Servo.h
index b0d929452732..8542092d66ea 100644
--- a/Marlin/src/HAL/ESP32/Servo.h
+++ b/Marlin/src/HAL/ESP32/Servo.h
@@ -30,7 +30,7 @@ class Servo {
MAX_PULSE_WIDTH = 2400, // Longest pulse sent to a servo
TAU_MSEC = 20,
TAU_USEC = (TAU_MSEC * 1000),
- MAX_COMPARE = ((1 << 16) - 1), // 65535
+ MAX_COMPARE = _BV(16) - 1, // 65535
CHANNEL_MAX_NUM = 16;
public:
diff --git a/Marlin/src/HAL/ESP32/Tone.cpp b/Marlin/src/HAL/ESP32/Tone.cpp
new file mode 100644
index 000000000000..376c0f32e129
--- /dev/null
+++ b/Marlin/src/HAL/ESP32/Tone.cpp
@@ -0,0 +1,59 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * Copypaste of SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+
+/**
+ * Description: Tone function for ESP32
+ * Derived from https://forum.arduino.cc/index.php?topic=136500.msg2903012#msg2903012
+ */
+
+#ifdef ARDUINO_ARCH_ESP32
+
+#include "../../inc/MarlinConfig.h"
+#include "HAL.h"
+
+static pin_t tone_pin;
+volatile static int32_t toggles;
+
+void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration) {
+ tone_pin = _pin;
+ toggles = 2 * frequency * duration / 1000;
+ HAL_timer_start(TONE_TIMER_NUM, 2 * frequency);
+}
+
+void noTone(const pin_t _pin) {
+ HAL_timer_disable_interrupt(TONE_TIMER_NUM);
+ WRITE(_pin, LOW);
+}
+
+HAL_TONE_TIMER_ISR() {
+ HAL_timer_isr_prologue(TONE_TIMER_NUM);
+
+ if (toggles) {
+ toggles--;
+ TOGGLE(tone_pin);
+ }
+ else noTone(tone_pin); // turn off interrupt
+}
+
+#endif // ARDUINO_ARCH_ESP32
diff --git a/Marlin/src/HAL/ESP32/WebSocketSerial.cpp b/Marlin/src/HAL/ESP32/WebSocketSerial.cpp
index ca7f47a1f8bd..eb5b9d60395a 100644
--- a/Marlin/src/HAL/ESP32/WebSocketSerial.cpp
+++ b/Marlin/src/HAL/ESP32/WebSocketSerial.cpp
@@ -29,7 +29,7 @@
#include "wifi.h"
#include
-WebSocketSerial webSocketSerial;
+MSerialWebSocketT webSocketSerial(false);
AsyncWebSocket ws("/ws"); // TODO Move inside the class.
// RingBuffer impl
@@ -137,16 +137,12 @@ size_t WebSocketSerial::write(const uint8_t c) {
return ret;
}
-size_t WebSocketSerial::write(const uint8_t* buffer, size_t size) {
+size_t WebSocketSerial::write(const uint8_t *buffer, size_t size) {
size_t written = 0;
for (size_t i = 0; i < size; i++)
written += write(buffer[i]);
return written;
}
-void WebSocketSerial::flushTX() {
- // No need to do anything as there's no benefit to sending partial lines over the websocket connection.
-}
-
#endif // WIFISUPPORT
#endif // ARDUINO_ARCH_ESP32
diff --git a/Marlin/src/HAL/ESP32/WebSocketSerial.h b/Marlin/src/HAL/ESP32/WebSocketSerial.h
index 7a25c6dc5e9c..6b3e419d10c5 100644
--- a/Marlin/src/HAL/ESP32/WebSocketSerial.h
+++ b/Marlin/src/HAL/ESP32/WebSocketSerial.h
@@ -22,6 +22,7 @@
#pragma once
#include "../../inc/MarlinConfig.h"
+#include "../../core/serial_hook.h"
#include
@@ -53,7 +54,7 @@ class RingBuffer {
ring_buffer_pos_t read(uint8_t *buffer);
void flush();
ring_buffer_pos_t write(const uint8_t c);
- ring_buffer_pos_t write(const uint8_t* buffer, ring_buffer_pos_t size);
+ ring_buffer_pos_t write(const uint8_t *buffer, ring_buffer_pos_t size);
};
class WebSocketSerial: public Stream {
@@ -68,11 +69,8 @@ class WebSocketSerial: public Stream {
int peek();
int read();
void flush();
- void flushTX();
size_t write(const uint8_t c);
- size_t write(const uint8_t* buffer, size_t size);
-
- operator bool() { return true; }
+ size_t write(const uint8_t *buffer, size_t size);
#if ENABLED(SERIAL_STATS_DROPPED_RX)
FORCE_INLINE uint32_t dropped() { return 0; }
@@ -83,4 +81,5 @@ class WebSocketSerial: public Stream {
#endif
};
-extern WebSocketSerial webSocketSerial;
+typedef Serial1Class MSerialWebSocketT;
+extern MSerialWebSocketT webSocketSerial;
diff --git a/Marlin/src/HAL/ESP32/endstop_interrupts.h b/Marlin/src/HAL/ESP32/endstop_interrupts.h
index 743ccd99c904..4725df921b1a 100644
--- a/Marlin/src/HAL/ESP32/endstop_interrupts.h
+++ b/Marlin/src/HAL/ESP32/endstop_interrupts.h
@@ -59,4 +59,10 @@ void setup_endstop_interrupts() {
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
+ TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
+ TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
+ TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
+ TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
+ TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
+ TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
}
diff --git a/Marlin/src/HAL/ESP32/i2s.cpp b/Marlin/src/HAL/ESP32/i2s.cpp
index e8f380654314..c28c00879390 100644
--- a/Marlin/src/HAL/ESP32/i2s.cpp
+++ b/Marlin/src/HAL/ESP32/i2s.cpp
@@ -139,7 +139,7 @@ static void IRAM_ATTR i2s_intr_handler_default(void *arg) {
I2S0.int_clr.val = I2S0.int_st.val; //clear pending interrupt
}
-void stepperTask(void* parameter) {
+void stepperTask(void *parameter) {
uint32_t remaining = 0;
while (1) {
diff --git a/Marlin/src/HAL/ESP32/inc/SanityCheck.h b/Marlin/src/HAL/ESP32/inc/SanityCheck.h
index f57a6c591028..8bbc68d8715b 100644
--- a/Marlin/src/HAL/ESP32/inc/SanityCheck.h
+++ b/Marlin/src/HAL/ESP32/inc/SanityCheck.h
@@ -30,9 +30,13 @@
#endif
#if HAS_TMC_SW_SERIAL
- #error "TMC220x Software Serial is not supported on this platform."
+ #error "TMC220x Software Serial is not supported on ESP32."
#endif
#if BOTH(WIFISUPPORT, ESP3D_WIFISUPPORT)
#error "Only enable one WiFi option, either WIFISUPPORT or ESP3D_WIFISUPPORT."
#endif
+
+#if ENABLED(POSTMORTEM_DEBUGGING)
+ #error "POSTMORTEM_DEBUGGING is not yet supported on ESP32."
+#endif
diff --git a/Marlin/src/HAL/ESP32/timers.cpp b/Marlin/src/HAL/ESP32/timers.cpp
index 3300aea8a89c..57662a665882 100644
--- a/Marlin/src/HAL/ESP32/timers.cpp
+++ b/Marlin/src/HAL/ESP32/timers.cpp
@@ -45,7 +45,7 @@ const tTimerConfig TimerConfig [NUM_HARDWARE_TIMERS] = {
{ TIMER_GROUP_0, TIMER_0, STEPPER_TIMER_PRESCALE, stepTC_Handler }, // 0 - Stepper
{ TIMER_GROUP_0, TIMER_1, TEMP_TIMER_PRESCALE, tempTC_Handler }, // 1 - Temperature
{ TIMER_GROUP_1, TIMER_0, PWM_TIMER_PRESCALE, pwmTC_Handler }, // 2 - PWM
- { TIMER_GROUP_1, TIMER_1, 1, nullptr }, // 3
+ { TIMER_GROUP_1, TIMER_1, TONE_TIMER_PRESCALE, toneTC_Handler }, // 3 - Tone
};
// ------------------------
diff --git a/Marlin/src/HAL/ESP32/timers.h b/Marlin/src/HAL/ESP32/timers.h
index 98386e3980b9..a47697113d5d 100644
--- a/Marlin/src/HAL/ESP32/timers.h
+++ b/Marlin/src/HAL/ESP32/timers.h
@@ -44,6 +44,9 @@ typedef uint64_t hal_timer_t;
#ifndef PWM_TIMER_NUM
#define PWM_TIMER_NUM 2 // index of timer to use for PWM outputs
#endif
+#ifndef TONE_TIMER_NUM
+ #define TONE_TIMER_NUM 3 // index of timer for beeper tones
+#endif
#define HAL_TIMER_RATE APB_CLK_FREQ // frequency of timer peripherals
@@ -59,6 +62,8 @@ typedef uint64_t hal_timer_t;
#define STEP_TIMER_MIN_INTERVAL 8 // minimum time in µs between stepper interrupts
+#define TONE_TIMER_PRESCALE 1000 // Arbitrary value, no idea what i'm doing here
+
#define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
@@ -90,11 +95,15 @@ typedef uint64_t hal_timer_t;
#ifndef HAL_PWM_TIMER_ISR
#define HAL_PWM_TIMER_ISR() extern "C" void pwmTC_Handler()
#endif
+#ifndef HAL_TONE_TIMER_ISR
+ #define HAL_TONE_TIMER_ISR() extern "C" void toneTC_Handler()
+#endif
extern "C" {
void tempTC_Handler();
void stepTC_Handler();
void pwmTC_Handler();
+ void toneTC_Handler();
}
// ------------------------
diff --git a/Marlin/src/HAL/HAL.h b/Marlin/src/HAL/HAL.h
index 9eefda8fb1e2..0cd836af2b68 100644
--- a/Marlin/src/HAL/HAL.h
+++ b/Marlin/src/HAL/HAL.h
@@ -29,12 +29,6 @@
#include HAL_PATH(.,HAL.h)
-#ifdef SERIAL_PORT_2
- #define NUM_SERIAL 2
-#else
- #define NUM_SERIAL 1
-#endif
-
#define HAL_ADC_RANGE _BV(HAL_ADC_RESOLUTION)
#ifndef I2C_ADDRESS
diff --git a/Marlin/src/HAL/LINUX/HAL.cpp b/Marlin/src/HAL/LINUX/HAL.cpp
index ee9e31e140e8..0b679170ef17 100644
--- a/Marlin/src/HAL/LINUX/HAL.cpp
+++ b/Marlin/src/HAL/LINUX/HAL.cpp
@@ -24,7 +24,7 @@
#include "../../inc/MarlinConfig.h"
#include "../shared/Delay.h"
-HalSerial usb_serial;
+MSerialT usb_serial(TERN0(EMERGENCY_PARSER, true));
// U8glib required functions
extern "C" {
@@ -73,4 +73,6 @@ void HAL_pwm_init() {
}
+void HAL_reboot() { /* Reset the application state and GPIO */ }
+
#endif // __PLAT_LINUX__
diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h
index 729f6c856e19..36906bffc869 100644
--- a/Marlin/src/HAL/LINUX/HAL.h
+++ b/Marlin/src/HAL/LINUX/HAL.h
@@ -60,8 +60,8 @@ uint8_t _getc();
#define SHARED_SERVOS HAS_SERVOS
-extern HalSerial usb_serial;
-#define MYSERIAL0 usb_serial
+extern MSerialT usb_serial;
+#define MYSERIAL1 usb_serial
#define ST7920_DELAY_1 DELAY_NS(600)
#define ST7920_DELAY_2 DELAY_NS(750)
@@ -107,14 +107,9 @@ uint16_t HAL_adc_get_result();
inline void HAL_clear_reset_source(void) {}
inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; }
-inline void HAL_reboot() {} // reboot the board or restart the bootloader
+void HAL_reboot(); // Reset the application state and GPIO
/* ---------------- Delay in cycles */
FORCE_INLINE static void DELAY_CYCLES(uint64_t x) {
Clock::delayCycles(x);
}
-
-// Add strcmp_P if missing
-#ifndef strcmp_P
- #define strcmp_P(a, b) strcmp((a), (b))
-#endif
diff --git a/Marlin/src/HAL/LINUX/inc/SanityCheck.h b/Marlin/src/HAL/LINUX/inc/SanityCheck.h
index 84167c97a144..45bb2662ace5 100644
--- a/Marlin/src/HAL/LINUX/inc/SanityCheck.h
+++ b/Marlin/src/HAL/LINUX/inc/SanityCheck.h
@@ -35,5 +35,9 @@
#endif
#if HAS_TMC_SW_SERIAL
- #error "TMC220x Software Serial is not supported on this platform."
+ #error "TMC220x Software Serial is not supported on LINUX."
+#endif
+
+#if ENABLED(POSTMORTEM_DEBUGGING)
+ #error "POSTMORTEM_DEBUGGING is not yet supported on LINUX."
#endif
diff --git a/Marlin/src/HAL/LINUX/include/Arduino.h b/Marlin/src/HAL/LINUX/include/Arduino.h
index 6aeb0db58335..d4086e259a2f 100644
--- a/Marlin/src/HAL/LINUX/include/Arduino.h
+++ b/Marlin/src/HAL/LINUX/include/Arduino.h
@@ -73,27 +73,6 @@ extern "C" {
void GpioDisableInt(uint32_t port, uint32_t pin);
}
-// Program Memory
-#define pgm_read_ptr(addr) (*((void**)(addr)))
-#define pgm_read_byte_near(addr) (*((uint8_t*)(addr)))
-#define pgm_read_float_near(addr) (*((float*)(addr)))
-#define pgm_read_word_near(addr) (*((uint16_t*)(addr)))
-#define pgm_read_dword_near(addr) (*((uint32_t*)(addr)))
-#define pgm_read_byte(addr) pgm_read_byte_near(addr)
-#define pgm_read_float(addr) pgm_read_float_near(addr)
-#define pgm_read_word(addr) pgm_read_word_near(addr)
-#define pgm_read_dword(addr) pgm_read_dword_near(addr)
-
-using std::memcpy;
-#define memcpy_P memcpy
-#define sprintf_P sprintf
-#define strstr_P strstr
-#define strncpy_P strncpy
-#define vsnprintf_P vsnprintf
-#define strcpy_P strcpy
-#define snprintf_P snprintf
-#define strlen_P strlen
-
// Time functions
extern "C" void delay(const int milis);
void _delay_ms(const int delay);
diff --git a/Marlin/src/HAL/LINUX/include/pinmapping.cpp b/Marlin/src/HAL/LINUX/include/pinmapping.cpp
index 870ab3a96e5f..5823668cd50d 100644
--- a/Marlin/src/HAL/LINUX/include/pinmapping.cpp
+++ b/Marlin/src/HAL/LINUX/include/pinmapping.cpp
@@ -25,43 +25,6 @@
#include "../../../gcode/parser.h"
-uint8_t analog_offset = NUM_DIGITAL_PINS - NUM_ANALOG_INPUTS;
-
-// Get the digital pin for an analog index
-pin_t analogInputToDigitalPin(const int8_t p) {
- return (WITHIN(p, 0, NUM_ANALOG_INPUTS) ? analog_offset + p : P_NC);
-}
-
-// Return the index of a pin number
-int16_t GET_PIN_MAP_INDEX(const pin_t pin) {
- return pin;
-}
-
-// Test whether the pin is valid
-bool VALID_PIN(const pin_t p) {
- return WITHIN(p, 0, NUM_DIGITAL_PINS);
-}
-
-// Get the analog index for a digital pin
-int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p) {
- return (WITHIN(p, analog_offset, NUM_DIGITAL_PINS) ? p - analog_offset : P_NC);
-}
-
-// Test whether the pin is PWM
-bool PWM_PIN(const pin_t p) {
- return false;
-}
-
-// Test whether the pin is interruptable
-bool INTERRUPT_PIN(const pin_t p) {
- return false;
-}
-
-// Get the pin number at the given index
-pin_t GET_PIN_MAP_PIN(const int16_t ind) {
- return ind;
-}
-
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
return parser.intval(code, dval);
}
diff --git a/Marlin/src/HAL/LINUX/include/pinmapping.h b/Marlin/src/HAL/LINUX/include/pinmapping.h
index 98f4b812e873..3751ae0027c7 100644
--- a/Marlin/src/HAL/LINUX/include/pinmapping.h
+++ b/Marlin/src/HAL/LINUX/include/pinmapping.h
@@ -34,26 +34,32 @@ constexpr uint8_t NUM_ANALOG_INPUTS = 16;
#define HAL_SENSITIVE_PINS
+constexpr uint8_t analog_offset = NUM_DIGITAL_PINS - NUM_ANALOG_INPUTS;
+
// Get the digital pin for an analog index
-pin_t analogInputToDigitalPin(const int8_t p);
+constexpr pin_t analogInputToDigitalPin(const int8_t p) {
+ return (WITHIN(p, 0, NUM_ANALOG_INPUTS) ? analog_offset + p : P_NC);
+}
+
+// Get the analog index for a digital pin
+constexpr int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p) {
+ return (WITHIN(p, analog_offset, NUM_DIGITAL_PINS) ? p - analog_offset : P_NC);
+}
// Return the index of a pin number
-int16_t GET_PIN_MAP_INDEX(const pin_t pin);
+constexpr int16_t GET_PIN_MAP_INDEX(const pin_t pin) { return pin; }
// Test whether the pin is valid
-bool VALID_PIN(const pin_t p);
-
-// Get the analog index for a digital pin
-int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p);
+constexpr bool VALID_PIN(const pin_t p) { return WITHIN(p, 0, NUM_DIGITAL_PINS); }
// Test whether the pin is PWM
-bool PWM_PIN(const pin_t p);
+constexpr bool PWM_PIN(const pin_t p) { return false; }
// Test whether the pin is interruptable
-bool INTERRUPT_PIN(const pin_t p);
+constexpr bool INTERRUPT_PIN(const pin_t p) { return false; }
// Get the pin number at the given index
-pin_t GET_PIN_MAP_PIN(const int16_t ind);
+constexpr pin_t GET_PIN_MAP_PIN(const int16_t ind) { return ind; }
// Parse a G-code word into a pin index
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
diff --git a/Marlin/src/HAL/LINUX/include/serial.h b/Marlin/src/HAL/LINUX/include/serial.h
index e91624938978..ebae066c3a57 100644
--- a/Marlin/src/HAL/LINUX/include/serial.h
+++ b/Marlin/src/HAL/LINUX/include/serial.h
@@ -25,6 +25,7 @@
#if ENABLED(EMERGENCY_PARSER)
#include "../../../feature/e_parser.h"
#endif
+#include "../../../core/serial_hook.h"
#include
#include
@@ -73,19 +74,11 @@ template class RingBuffer {
volatile uint32_t index_read;
};
-class HalSerial {
-public:
-
- #if ENABLED(EMERGENCY_PARSER)
- EmergencyParser::State emergency_state;
- static inline bool emergency_parser_enabled() { return true; }
- #endif
-
+struct HalSerial {
HalSerial() { host_connected = true; }
void begin(int32_t) {}
-
- void end() {}
+ void end() {}
int peek() {
uint8_t value;
@@ -100,7 +93,7 @@ class HalSerial {
return transmit_buffer.write(c);
}
- operator bool() { return host_connected; }
+ bool connected() { return host_connected; }
uint16_t available() {
return (uint16_t)receive_buffer.available();
@@ -117,92 +110,9 @@ class HalSerial {
while (transmit_buffer.available()) { /* nada */ }
}
- void printf(const char *format, ...) {
- static char buffer[256];
- va_list vArgs;
- va_start(vArgs, format);
- int length = vsnprintf((char *) buffer, 256, (char const *) format, vArgs);
- va_end(vArgs);
- if (length > 0 && length < 256) {
- if (host_connected) {
- for (int i = 0; i < length;) {
- if (transmit_buffer.write(buffer[i])) {
- ++i;
- }
- }
- }
- }
- }
-
- #define DEC 10
- #define HEX 16
- #define OCT 8
- #define BIN 2
-
- void print_bin(uint32_t value, uint8_t num_digits) {
- uint32_t mask = 1 << (num_digits -1);
- for (uint8_t i = 0; i < num_digits; i++) {
- if (!(i % 4) && i) write(' ');
- if (!(i % 16) && i) write(' ');
- if (value & mask) write('1');
- else write('0');
- value <<= 1;
- }
- }
-
- void print(const char value[]) { printf("%s" , value); }
- void print(char value, int nbase = 0) {
- if (nbase == BIN) print_bin(value, 8);
- else if (nbase == OCT) printf("%3o", value);
- else if (nbase == HEX) printf("%2X", value);
- else if (nbase == DEC ) printf("%d", value);
- else printf("%c" , value);
- }
- void print(unsigned char value, int nbase = 0) {
- if (nbase == BIN) print_bin(value, 8);
- else if (nbase == OCT) printf("%3o", value);
- else if (nbase == HEX) printf("%2X", value);
- else printf("%u" , value);
- }
- void print(int value, int nbase = 0) {
- if (nbase == BIN) print_bin(value, 16);
- else if (nbase == OCT) printf("%6o", value);
- else if (nbase == HEX) printf("%4X", value);
- else printf("%d", value);
- }
- void print(unsigned int value, int nbase = 0) {
- if (nbase == BIN) print_bin(value, 16);
- else if (nbase == OCT) printf("%6o", value);
- else if (nbase == HEX) printf("%4X", value);
- else printf("%u" , value);
- }
- void print(long value, int nbase = 0) {
- if (nbase == BIN) print_bin(value, 32);
- else if (nbase == OCT) printf("%11o", value);
- else if (nbase == HEX) printf("%8X", value);
- else printf("%ld" , value);
- }
- void print(unsigned long value, int nbase = 0) {
- if (nbase == BIN) print_bin(value, 32);
- else if (nbase == OCT) printf("%11o", value);
- else if (nbase == HEX) printf("%8X", value);
- else printf("%lu" , value);
- }
- void print(float value, int round = 6) { printf("%f" , value); }
- void print(double value, int round = 6) { printf("%f" , value); }
-
- void println(const char value[]) { printf("%s\n" , value); }
- void println(char value, int nbase = 0) { print(value, nbase); println(); }
- void println(unsigned char value, int nbase = 0) { print(value, nbase); println(); }
- void println(int value, int nbase = 0) { print(value, nbase); println(); }
- void println(unsigned int value, int nbase = 0) { print(value, nbase); println(); }
- void println(long value, int nbase = 0) { print(value, nbase); println(); }
- void println(unsigned long value, int nbase = 0) { print(value, nbase); println(); }
- void println(float value, int round = 6) { printf("%f\n" , value); }
- void println(double value, int round = 6) { printf("%f\n" , value); }
- void println() { print('\n'); }
-
volatile RingBuffer receive_buffer;
volatile RingBuffer transmit_buffer;
volatile bool host_connected;
};
+
+typedef Serial1Class MSerialT;
diff --git a/Marlin/src/HAL/LINUX/main.cpp b/Marlin/src/HAL/LINUX/main.cpp
index eadc409324c9..31f6de98ee8e 100644
--- a/Marlin/src/HAL/LINUX/main.cpp
+++ b/Marlin/src/HAL/LINUX/main.cpp
@@ -1,6 +1,5 @@
/**
* Marlin 3D Printer Firmware
- *
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* This program is free software: you can redistribute it and/or modify
@@ -106,8 +105,8 @@ int main() {
std::thread write_serial (write_serial_thread);
std::thread read_serial (read_serial_thread);
- #ifdef MYSERIAL0
- MYSERIAL0.begin(BAUDRATE);
+ #ifdef MYSERIAL1
+ MYSERIAL1.begin(BAUDRATE);
SERIAL_ECHOLNPGM("x86_64 Initialized");
SERIAL_FLUSHTX();
#endif
diff --git a/Marlin/src/HAL/LPC1768/DebugMonitor.cpp b/Marlin/src/HAL/LPC1768/DebugMonitor.cpp
deleted file mode 100644
index 783b10cfac16..000000000000
--- a/Marlin/src/HAL/LPC1768/DebugMonitor.cpp
+++ /dev/null
@@ -1,322 +0,0 @@
-/**
- * Marlin 3D Printer Firmware
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
- *
- * Based on Sprinter and grbl.
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
- *
- * This program is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * This program is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
- *
- */
-#ifdef TARGET_LPC1768
-
-#include "../../core/macros.h"
-#include "../../core/serial.h"
-#include
-
-#include "../shared/backtrace/unwinder.h"
-#include "../shared/backtrace/unwmemaccess.h"
-#include "watchdog.h"
-#include
-
-
-// Debug monitor that dumps to the Programming port all status when
-// an exception or WDT timeout happens - And then resets the board
-
-// All the Monitor routines must run with interrupts disabled and
-// under an ISR execution context. That is why we cannot reuse the
-// Serial interrupt routines or any C runtime, as we don't know the
-// state we are when running them
-
-// A SW memory barrier, to ensure GCC does not overoptimize loops
-#define sw_barrier() __asm__ volatile("": : :"memory");
-
-// (re)initialize UART0 as a monitor output to 250000,n,8,1
-static void TXBegin() {
-}
-
-// Send character through UART with no interrupts
-static void TX(char c) {
- _DBC(c);
-}
-
-// Send String through UART
-static void TX(const char* s) {
- while (*s) TX(*s++);
-}
-
-static void TXDigit(uint32_t d) {
- if (d < 10) TX((char)(d+'0'));
- else if (d < 16) TX((char)(d+'A'-10));
- else TX('?');
-}
-
-// Send Hex number thru UART
-static void TXHex(uint32_t v) {
- TX("0x");
- for (uint8_t i = 0; i < 8; i++, v <<= 4)
- TXDigit((v >> 28) & 0xF);
-}
-
-// Send Decimal number thru UART
-static void TXDec(uint32_t v) {
- if (!v) {
- TX('0');
- return;
- }
-
- char nbrs[14];
- char *p = &nbrs[0];
- while (v != 0) {
- *p++ = '0' + (v % 10);
- v /= 10;
- }
- do {
- p--;
- TX(*p);
- } while (p != &nbrs[0]);
-}
-
-// Dump a backtrace entry
-static bool UnwReportOut(void* ctx, const UnwReport* bte) {
- int* p = (int*)ctx;
-
- (*p)++;
- TX('#'); TXDec(*p); TX(" : ");
- TX(bte->name?bte->name:"unknown"); TX('@'); TXHex(bte->function);
- TX('+'); TXDec(bte->address - bte->function);
- TX(" PC:");TXHex(bte->address); TX('\n');
- return true;
-}
-
-#ifdef UNW_DEBUG
- void UnwPrintf(const char* format, ...) {
- char dest[256];
- va_list argptr;
- va_start(argptr, format);
- vsprintf(dest, format, argptr);
- va_end(argptr);
- TX(&dest[0]);
- }
-#endif
-
-/* Table of function pointers for passing to the unwinder */
-static const UnwindCallbacks UnwCallbacks = {
- UnwReportOut,
- UnwReadW,
- UnwReadH,
- UnwReadB
- #ifdef UNW_DEBUG
- ,UnwPrintf
- #endif
-};
-
-
-/**
- * HardFaultHandler_C:
- * This is called from the HardFault_HandlerAsm with a pointer the Fault stack
- * as the parameter. We can then read the values from the stack and place them
- * into local variables for ease of reading.
- * We then read the various Fault Status and Address Registers to help decode
- * cause of the fault.
- * The function ends with a BKPT instruction to force control back into the debugger
- */
-extern "C"
-void HardFault_HandlerC(unsigned long *sp, unsigned long lr, unsigned long cause) {
-
- static const char* causestr[] = {
- "NMI","Hard","Mem","Bus","Usage","Debug","WDT","RSTC"
- };
-
- UnwindFrame btf;
-
- // Dump report to the Programming port (interrupts are DISABLED)
- TXBegin();
- TX("\n\n## Software Fault detected ##\n");
- TX("Cause: "); TX(causestr[cause]); TX('\n');
-
- TX("R0 : "); TXHex(((unsigned long)sp[0])); TX('\n');
- TX("R1 : "); TXHex(((unsigned long)sp[1])); TX('\n');
- TX("R2 : "); TXHex(((unsigned long)sp[2])); TX('\n');
- TX("R3 : "); TXHex(((unsigned long)sp[3])); TX('\n');
- TX("R12 : "); TXHex(((unsigned long)sp[4])); TX('\n');
- TX("LR : "); TXHex(((unsigned long)sp[5])); TX('\n');
- TX("PC : "); TXHex(((unsigned long)sp[6])); TX('\n');
- TX("PSR : "); TXHex(((unsigned long)sp[7])); TX('\n');
-
- // Configurable Fault Status Register
- // Consists of MMSR, BFSR and UFSR
- TX("CFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED28)))); TX('\n');
-
- // Hard Fault Status Register
- TX("HFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED2C)))); TX('\n');
-
- // Debug Fault Status Register
- TX("DFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED30)))); TX('\n');
-
- // Auxiliary Fault Status Register
- TX("AFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED3C)))); TX('\n');
-
- // Read the Fault Address Registers. These may not contain valid values.
- // Check BFARVALID/MMARVALID to see if they are valid values
- // MemManage Fault Address Register
- TX("MMAR : "); TXHex((*((volatile unsigned long *)(0xE000ED34)))); TX('\n');
-
- // Bus Fault Address Register
- TX("BFAR : "); TXHex((*((volatile unsigned long *)(0xE000ED38)))); TX('\n');
-
- TX("ExcLR: "); TXHex(lr); TX('\n');
- TX("ExcSP: "); TXHex((unsigned long)sp); TX('\n');
-
- btf.sp = ((unsigned long)sp) + 8*4; // The original stack pointer
- btf.fp = btf.sp;
- btf.lr = ((unsigned long)sp[5]);
- btf.pc = ((unsigned long)sp[6]) | 1; // Force Thumb, as CORTEX only support it
-
- // Perform a backtrace
- TX("\nBacktrace:\n\n");
- int ctr = 0;
- UnwindStart(&btf, &UnwCallbacks, &ctr);
-
- // Disable all NVIC interrupts
- NVIC->ICER[0] = 0xFFFFFFFF;
- NVIC->ICER[1] = 0xFFFFFFFF;
-
- // Relocate VTOR table to default position
- SCB->VTOR = 0;
-
- // Clear cause of reset to prevent entering smoothie bootstrap
- HAL_clear_reset_source();
-
- // Restart watchdog
- #if ENABLED(USE_WATCHDOG)
- //WDT_Restart(WDT);
- watchdog_init();
- #endif
-
- // Reset controller
- NVIC_SystemReset();
-
- // Nothing below here is compiled because NVIC_SystemReset loops forever
-
- for (;;) { TERN_(USE_WATCHDOG, watchdog_init()); }
-}
-
-extern "C" {
-__attribute__((naked)) void NMI_Handler() {
- __asm__ __volatile__ (
- ".syntax unified" "\n\t"
- A("tst lr, #4")
- A("ite eq")
- A("mrseq r0, msp")
- A("mrsne r0, psp")
- A("mov r1,lr")
- A("mov r2,#0")
- A("b HardFault_HandlerC")
- );
-}
-
-__attribute__((naked)) void HardFault_Handler() {
- __asm__ __volatile__ (
- ".syntax unified" "\n\t"
- A("tst lr, #4")
- A("ite eq")
- A("mrseq r0, msp")
- A("mrsne r0, psp")
- A("mov r1,lr")
- A("mov r2,#1")
- A("b HardFault_HandlerC")
- );
-}
-
-__attribute__((naked)) void MemManage_Handler() {
- __asm__ __volatile__ (
- ".syntax unified" "\n\t"
- A("tst lr, #4")
- A("ite eq")
- A("mrseq r0, msp")
- A("mrsne r0, psp")
- A("mov r1,lr")
- A("mov r2,#2")
- A("b HardFault_HandlerC")
- );
-}
-
-__attribute__((naked)) void BusFault_Handler() {
- __asm__ __volatile__ (
- ".syntax unified" "\n\t"
- A("tst lr, #4")
- A("ite eq")
- A("mrseq r0, msp")
- A("mrsne r0, psp")
- A("mov r1,lr")
- A("mov r2,#3")
- A("b HardFault_HandlerC")
- );
-}
-
-__attribute__((naked)) void UsageFault_Handler() {
- __asm__ __volatile__ (
- ".syntax unified" "\n\t"
- A("tst lr, #4")
- A("ite eq")
- A("mrseq r0, msp")
- A("mrsne r0, psp")
- A("mov r1,lr")
- A("mov r2,#4")
- A("b HardFault_HandlerC")
- );
-}
-
-__attribute__((naked)) void DebugMon_Handler() {
- __asm__ __volatile__ (
- ".syntax unified" "\n\t"
- A("tst lr, #4")
- A("ite eq")
- A("mrseq r0, msp")
- A("mrsne r0, psp")
- A("mov r1,lr")
- A("mov r2,#5")
- A("b HardFault_HandlerC")
- );
-}
-
-/* This is NOT an exception, it is an interrupt handler - Nevertheless, the framing is the same */
-__attribute__((naked)) void WDT_IRQHandler() {
- __asm__ __volatile__ (
- ".syntax unified" "\n\t"
- A("tst lr, #4")
- A("ite eq")
- A("mrseq r0, msp")
- A("mrsne r0, psp")
- A("mov r1,lr")
- A("mov r2,#6")
- A("b HardFault_HandlerC")
- );
-}
-
-__attribute__((naked)) void RSTC_Handler() {
- __asm__ __volatile__ (
- ".syntax unified" "\n\t"
- A("tst lr, #4")
- A("ite eq")
- A("mrseq r0, msp")
- A("mrsne r0, psp")
- A("mov r1,lr")
- A("mov r2,#7")
- A("b HardFault_HandlerC")
- );
-}
-}
-#endif // TARGET_LPC1768
diff --git a/Marlin/src/HAL/LPC1768/HAL.cpp b/Marlin/src/HAL/LPC1768/HAL.cpp
index 3614e953851c..cee9cfc5f744 100644
--- a/Marlin/src/HAL/LPC1768/HAL.cpp
+++ b/Marlin/src/HAL/LPC1768/HAL.cpp
@@ -29,6 +29,8 @@
#include "watchdog.h"
#endif
+DefaultSerial1 USBSerial(false, UsbSerial);
+
uint32_t HAL_adc_reading = 0;
// U8glib required functions
@@ -61,7 +63,12 @@ int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
return ind > -1 ? ind : dval;
}
-void flashFirmware(const int16_t) { NVIC_SystemReset(); }
+void flashFirmware(const int16_t) {
+ delay(500); // Give OS time to disconnect
+ USB_Connect(false); // USB clear connection
+ delay(1000); // Give OS time to notice
+ HAL_reboot();
+}
void HAL_clear_reset_source(void) {
TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag());
@@ -74,4 +81,6 @@ uint8_t HAL_get_reset_source(void) {
return RST_POWER_ON;
}
+void HAL_reboot() { NVIC_SystemReset(); }
+
#endif // TARGET_LPC1768
diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h
index f2347bf5a7fe..3f9cd2dfbd02 100644
--- a/Marlin/src/HAL/LPC1768/HAL.h
+++ b/Marlin/src/HAL/LPC1768/HAL.h
@@ -60,35 +60,60 @@ extern "C" volatile uint32_t _millis;
#define ST7920_DELAY_3 DELAY_NS(750)
#endif
+typedef ForwardSerial1Class< decltype(UsbSerial) > DefaultSerial1;
+extern DefaultSerial1 USBSerial;
+
#define _MSERIAL(X) MSerial##X
#define MSERIAL(X) _MSERIAL(X)
-#define MSerial0 MSerial
#if SERIAL_PORT == -1
- #define MYSERIAL0 UsbSerial
+ #define MYSERIAL1 USBSerial
#elif WITHIN(SERIAL_PORT, 0, 3)
- #define MYSERIAL0 MSERIAL(SERIAL_PORT)
+ #define MYSERIAL1 MSERIAL(SERIAL_PORT)
#else
- #error "SERIAL_PORT must be from -1 to 3. Please update your configuration."
+ #error "SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB."
#endif
#ifdef SERIAL_PORT_2
#if SERIAL_PORT_2 == -1
- #define MYSERIAL1 UsbSerial
+ #define MYSERIAL2 USBSerial
#elif WITHIN(SERIAL_PORT_2, 0, 3)
- #define MYSERIAL1 MSERIAL(SERIAL_PORT_2)
+ #define MYSERIAL2 MSERIAL(SERIAL_PORT_2)
+ #else
+ #error "SERIAL_PORT_2 must be from 0 to 3. You can also use -1 if the board supports Native USB."
+ #endif
+#endif
+
+#ifdef SERIAL_PORT_3
+ #if SERIAL_PORT_3 == -1
+ #define MYSERIAL3 USBSerial
+ #elif WITHIN(SERIAL_PORT_3, 0, 3)
+ #define MYSERIAL3 MSERIAL(SERIAL_PORT_3)
+ #else
+ #error "SERIAL_PORT_3 must be from 0 to 3. You can also use -1 if the board supports Native USB."
+ #endif
+#endif
+
+#ifdef MMU2_SERIAL_PORT
+ #if MMU2_SERIAL_PORT == -1
+ #define MMU2_SERIAL USBSerial
+ #elif WITHIN(MMU2_SERIAL_PORT, 0, 3)
+ #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT)
#else
- #error "SERIAL_PORT_2 must be from -1 to 3. Please update your configuration."
+ #error "MMU2_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB."
#endif
#endif
#ifdef LCD_SERIAL_PORT
#if LCD_SERIAL_PORT == -1
- #define LCD_SERIAL UsbSerial
+ #define LCD_SERIAL USBSerial
#elif WITHIN(LCD_SERIAL_PORT, 0, 3)
#define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT)
#else
- #error "LCD_SERIAL_PORT must be from -1 to 3. Please update your configuration."
+ #error "LCD_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB."
+ #endif
+ #if HAS_DGUS_LCD
+ #define SERIAL_GET_TX_BUFFER_FREE() MSerial0.available()
#endif
#endif
@@ -173,7 +198,7 @@ constexpr pin_t GET_PIN_MAP_PIN(const int16_t index) {
// Parse a G-code word into a pin index
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
// P0.6 thru P0.9 are for the onboard SD card
-#define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09
+#define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09,
#define HAL_IDLETASK 1
void HAL_idletask();
@@ -203,17 +228,4 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255,
void HAL_clear_reset_source(void);
uint8_t HAL_get_reset_source(void);
-inline void HAL_reboot() {} // reboot the board or restart the bootloader
-
-// Add strcmp_P if missing
-#ifndef strcmp_P
- #define strcmp_P(a, b) strcmp((a), (b))
-#endif
-
-#ifndef strcat_P
- #define strcat_P(a, b) strcat((a), (b))
-#endif
-
-#ifndef strcpy_P
- #define strcpy_P(a, b) strcpy((a), (b))
-#endif
+void HAL_reboot();
diff --git a/Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp b/Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp
new file mode 100644
index 000000000000..57065c49ac83
--- /dev/null
+++ b/Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp
@@ -0,0 +1,51 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#ifdef TARGET_LPC1768
+
+#include "../../inc/MarlinConfig.h"
+#include "HAL.h"
+
+#if ENABLED(POSTMORTEM_DEBUGGING)
+
+#include "../shared/HAL_MinSerial.h"
+#include
+
+static void TX(char c) { _DBC(c); }
+void install_min_serial() { HAL_min_serial_out = &TX; }
+
+#if DISABLED(DYNAMIC_VECTORTABLE)
+extern "C" {
+ __attribute__((naked)) void JumpHandler_ASM() {
+ __asm__ __volatile__ (
+ "b CommonHandler_ASM\n"
+ );
+ }
+ void __attribute__((naked, alias("JumpHandler_ASM"))) HardFault_Handler();
+ void __attribute__((naked, alias("JumpHandler_ASM"))) BusFault_Handler();
+ void __attribute__((naked, alias("JumpHandler_ASM"))) UsageFault_Handler();
+ void __attribute__((naked, alias("JumpHandler_ASM"))) MemManage_Handler();
+ void __attribute__((naked, alias("JumpHandler_ASM"))) NMI_Handler();
+}
+#endif
+
+#endif // POSTMORTEM_DEBUGGING
+#endif // TARGET_LPC1768
diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp
index dbc89a33f547..29f9b43afef0 100644
--- a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp
+++ b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp
@@ -66,11 +66,7 @@
#include
- #ifndef HAL_SPI_SPEED
- #define HAL_SPI_SPEED SPI_FULL_SPEED
- #endif
-
- static uint8_t SPI_speed = HAL_SPI_SPEED;
+ static uint8_t SPI_speed = SPI_FULL_SPEED;
static uint8_t spiTransfer(uint8_t b) {
return swSpiTransfer(b, SPI_speed, SD_SCK_PIN, SD_MISO_PIN, SD_MOSI_PIN);
@@ -93,12 +89,12 @@
void spiSend(uint8_t b) { (void)spiTransfer(b); }
- void spiSend(const uint8_t* buf, size_t nbyte) {
+ void spiSend(const uint8_t *buf, size_t nbyte) {
for (uint16_t i = 0; i < nbyte; i++)
(void)spiTransfer(buf[i]);
}
- void spiSendBlock(uint8_t token, const uint8_t* buf) {
+ void spiSendBlock(uint8_t token, const uint8_t *buf) {
(void)spiTransfer(token);
for (uint16_t i = 0; i < 512; i++)
(void)spiTransfer(buf[i]);
@@ -106,15 +102,13 @@
#else
- #ifndef HAL_SPI_SPEED
- #ifdef SD_SPI_SPEED
- #define HAL_SPI_SPEED SD_SPI_SPEED
- #else
- #define HAL_SPI_SPEED SPI_FULL_SPEED
- #endif
+ #ifdef SD_SPI_SPEED
+ #define INIT_SPI_SPEED SD_SPI_SPEED
+ #else
+ #define INIT_SPI_SPEED SPI_FULL_SPEED
#endif
- void spiBegin() { spiInit(HAL_SPI_SPEED); } // Set up SCK, MOSI & MISO pins for SSP0
+ void spiBegin() { spiInit(INIT_SPI_SPEED); } // Set up SCK, MOSI & MISO pins for SSP0
void spiInit(uint8_t spiRate) {
#if SD_MISO_PIN == BOARD_SPI1_MISO_PIN
@@ -135,13 +129,13 @@
void spiSend(uint8_t b) { doio(b); }
- void spiSend(const uint8_t* buf, size_t nbyte) {
+ void spiSend(const uint8_t *buf, size_t nbyte) {
for (uint16_t i = 0; i < nbyte; i++) doio(buf[i]);
}
void spiSend(uint32_t chan, byte b) {}
- void spiSend(uint32_t chan, const uint8_t* buf, size_t nbyte) {}
+ void spiSend(uint32_t chan, const uint8_t *buf, size_t nbyte) {}
// Read single byte from SPI
uint8_t spiRec() { return doio(0xFF); }
@@ -156,7 +150,7 @@
uint8_t spiTransfer(uint8_t b) { return doio(b); }
// Write from buffer to SPI
- void spiSendBlock(uint8_t token, const uint8_t* buf) {
+ void spiSendBlock(uint8_t token, const uint8_t *buf) {
(void)spiTransfer(token);
for (uint16_t i = 0; i < 512; i++)
(void)spiTransfer(buf[i]);
diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.cpp b/Marlin/src/HAL/LPC1768/MarlinSerial.cpp
index baad3f8f26b7..f2aecf54a050 100644
--- a/Marlin/src/HAL/LPC1768/MarlinSerial.cpp
+++ b/Marlin/src/HAL/LPC1768/MarlinSerial.cpp
@@ -21,24 +21,51 @@
*/
#ifdef TARGET_LPC1768
-#include "../../inc/MarlinConfigPre.h"
#include "MarlinSerial.h"
-#if USING_SERIAL_0
- MarlinSerial MSerial(LPC_UART0);
- extern "C" void UART0_IRQHandler() { MSerial.IRQHandler(); }
+#include "../../inc/MarlinConfig.h"
+
+#if USING_HW_SERIAL0
+ MarlinSerial _MSerial0(LPC_UART0);
+ MSerialT MSerial0(true, _MSerial0);
+ extern "C" void UART0_IRQHandler() { _MSerial0.IRQHandler(); }
+#endif
+#if USING_HW_SERIAL1
+ MarlinSerial _MSerial1((LPC_UART_TypeDef *) LPC_UART1);
+ MSerialT MSerial1(true, _MSerial1);
+ extern "C" void UART1_IRQHandler() { _MSerial1.IRQHandler(); }
#endif
-#if USING_SERIAL_1
- MarlinSerial MSerial1((LPC_UART_TypeDef *) LPC_UART1);
- extern "C" void UART1_IRQHandler() { MSerial1.IRQHandler(); }
+#if USING_HW_SERIAL2
+ MarlinSerial _MSerial2(LPC_UART2);
+ MSerialT MSerial2(true, _MSerial2);
+ extern "C" void UART2_IRQHandler() { _MSerial2.IRQHandler(); }
#endif
-#if USING_SERIAL_2
- MarlinSerial MSerial2(LPC_UART2);
- extern "C" void UART2_IRQHandler() { MSerial2.IRQHandler(); }
+#if USING_HW_SERIAL3
+ MarlinSerial _MSerial3(LPC_UART3);
+ MSerialT MSerial3(true, _MSerial3);
+ extern "C" void UART3_IRQHandler() { _MSerial3.IRQHandler(); }
#endif
-#if USING_SERIAL_3
- MarlinSerial MSerial3(LPC_UART3);
- extern "C" void UART3_IRQHandler() { MSerial3.IRQHandler(); }
+
+#if ENABLED(EMERGENCY_PARSER)
+
+ bool MarlinSerial::recv_callback(const char c) {
+ // Need to figure out which serial port we are and react in consequence (Marlin does not have CONTAINER_OF macro)
+ if (false) {}
+ #if USING_HW_SERIAL0
+ else if (this == &_MSerial0) emergency_parser.update(MSerial0.emergency_state, c);
+ #endif
+ #if USING_HW_SERIAL1
+ else if (this == &_MSerial1) emergency_parser.update(MSerial1.emergency_state, c);
+ #endif
+ #if USING_HW_SERIAL2
+ else if (this == &_MSerial2) emergency_parser.update(MSerial2.emergency_state, c);
+ #endif
+ #if USING_HW_SERIAL3
+ else if (this == &_MSerial3) emergency_parser.update(MSerial3.emergency_state, c);
+ #endif
+ return true;
+ }
+
#endif
#endif // TARGET_LPC1768
diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.h b/Marlin/src/HAL/LPC1768/MarlinSerial.h
index 8d6b64378a0a..808d19f8c52a 100644
--- a/Marlin/src/HAL/LPC1768/MarlinSerial.h
+++ b/Marlin/src/HAL/LPC1768/MarlinSerial.h
@@ -28,6 +28,7 @@
#if ENABLED(EMERGENCY_PARSER)
#include "../../feature/e_parser.h"
#endif
+#include "../../core/serial_hook.h"
#ifndef SERIAL_PORT
#define SERIAL_PORT 0
@@ -41,27 +42,26 @@
class MarlinSerial : public HardwareSerial {
public:
- MarlinSerial(LPC_UART_TypeDef *UARTx) :
- HardwareSerial(UARTx)
- #if ENABLED(EMERGENCY_PARSER)
- , emergency_state(EmergencyParser::State::EP_RESET)
- #endif
- { }
+ MarlinSerial(LPC_UART_TypeDef *UARTx) : HardwareSerial(UARTx) { }
void end() {}
#if ENABLED(EMERGENCY_PARSER)
- bool recv_callback(const char c) override {
- emergency_parser.update(emergency_state, c);
- return true; // do not discard character
- }
-
- EmergencyParser::State emergency_state;
- static inline bool emergency_parser_enabled() { return true; }
+ bool recv_callback(const char c) override;
#endif
};
-extern MarlinSerial MSerial;
-extern MarlinSerial MSerial1;
-extern MarlinSerial MSerial2;
-extern MarlinSerial MSerial3;
+// On LPC176x framework, HardwareSerial does not implement the same interface as Arduino's Serial, so overloads
+// of 'available' and 'read' method are not used in this multiple inheritance scenario.
+// Instead, use a ForwardSerial here that adapts the interface.
+typedef ForwardSerial1Class MSerialT;
+extern MSerialT MSerial0;
+extern MSerialT MSerial1;
+extern MSerialT MSerial2;
+extern MSerialT MSerial3;
+
+// Consequently, we can't use a RuntimeSerial either. The workaround would be to use
+// a RuntimeSerial> type here. Ignore for now until it's actually required.
+#if ENABLED(SERIAL_RUNTIME_HOOK)
+ #error "SERIAL_RUNTIME_HOOK is not yet supported for LPC176x."
+#endif
diff --git a/Marlin/src/HAL/LPC1768/eeprom_flash.cpp b/Marlin/src/HAL/LPC1768/eeprom_flash.cpp
index 3c0c3c8ec30e..38d2705d519a 100644
--- a/Marlin/src/HAL/LPC1768/eeprom_flash.cpp
+++ b/Marlin/src/HAL/LPC1768/eeprom_flash.cpp
@@ -25,7 +25,7 @@
* Emulate EEPROM storage using Flash Memory
*
* Use a single 32K flash sector to store EEPROM data. To reduce the
- * number of erase operations a simple "levelling" scheme is used that
+ * number of erase operations a simple "leveling" scheme is used that
* maintains a number of EEPROM "slots" within the larger flash sector.
* Each slot is used in turn and the entire sector is only erased when all
* slots have been used.
diff --git a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp
index 54a64ccd72f1..70395251df25 100644
--- a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp
+++ b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp
@@ -83,17 +83,16 @@ bool PersistentStore::access_finish() {
static void debug_rw(const bool write, int &pos, const uint8_t *value, const size_t size, const FRESULT s, const size_t total=0) {
PGM_P const rw_str = write ? PSTR("write") : PSTR("read");
SERIAL_CHAR(' ');
- serialprintPGM(rw_str);
- SERIAL_ECHOLNPAIR("_data(", pos, ",", int(value), ",", int(size), ", ...)");
+ SERIAL_ECHOPGM_P(rw_str);
+ SERIAL_ECHOLNPAIR("_data(", pos, ",", value, ",", size, ", ...)");
if (total) {
SERIAL_ECHOPGM(" f_");
- serialprintPGM(rw_str);
- SERIAL_ECHOPAIR("()=", int(s), "\n size=", int(size), "\n bytes_");
- serialprintPGM(write ? PSTR("written=") : PSTR("read="));
- SERIAL_ECHOLN(total);
+ SERIAL_ECHOPGM_P(rw_str);
+ SERIAL_ECHOPAIR("()=", s, "\n size=", size, "\n bytes_");
+ SERIAL_ECHOLNPAIR_P(write ? PSTR("written=") : PSTR("read="), total);
}
else
- SERIAL_ECHOLNPAIR(" f_lseek()=", int(s));
+ SERIAL_ECHOLNPAIR(" f_lseek()=", s);
}
// File function return codes for type FRESULT. This goes away soon, but
diff --git a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp
index d94aba6119f1..f9286a74ac88 100644
--- a/Marlin/src/HAL/LPC1768/eeprom_wired.cpp
+++ b/Marlin/src/HAL/LPC1768/eeprom_wired.cpp
@@ -42,25 +42,22 @@ bool PersistentStore::access_start() { eeprom_init(); return true; }
bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ uint16_t written = 0;
while (size--) {
uint8_t v = *value;
-
- // EEPROM has only ~100,000 write cycles,
- // so only write bytes that have changed!
uint8_t * const p = (uint8_t * const)pos;
- if (v != eeprom_read_byte(p)) {
+ if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed!
eeprom_write_byte(p, v);
+ if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes
if (eeprom_read_byte(p) != v) {
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
return true;
}
}
-
crc16(crc, &v, 1);
pos++;
value++;
- };
-
+ }
return false;
}
@@ -68,7 +65,6 @@ bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t
do {
// Read from external EEPROM
const uint8_t c = eeprom_read_byte((uint8_t*)pos);
-
if (writing) *value = c;
crc16(crc, &c, 1);
pos++;
diff --git a/Marlin/src/HAL/LPC1768/endstop_interrupts.h b/Marlin/src/HAL/LPC1768/endstop_interrupts.h
index 126d6e7d5bb2..23bd0cc982b2 100644
--- a/Marlin/src/HAL/LPC1768/endstop_interrupts.h
+++ b/Marlin/src/HAL/LPC1768/endstop_interrupts.h
@@ -122,4 +122,37 @@ void setup_endstop_interrupts() {
#endif
_ATTACH(Z_MIN_PROBE_PIN);
#endif
+ #if HAS_I_MAX
+ #if !LPC1768_PIN_INTERRUPT_M(I_MAX_PIN)
+ #error "I_MAX_PIN is not INTERRUPT-capable."
+ #endif
+ _ATTACH(I_MAX_PIN);
+ #elif HAS_I_MIN
+ #if !LPC1768_PIN_INTERRUPT_M(I_MIN_PIN)
+ #error "I_MIN_PIN is not INTERRUPT-capable."
+ #endif
+ _ATTACH(I_MIN_PIN);
+ #endif
+ #if HAS_J_MAX
+ #if !LPC1768_PIN_INTERRUPT_M(J_MAX_PIN)
+ #error "J_MAX_PIN is not INTERRUPT-capable."
+ #endif
+ _ATTACH(J_MAX_PIN);
+ #elif HAS_J_MIN
+ #if !LPC1768_PIN_INTERRUPT_M(J_MIN_PIN)
+ #error "J_MIN_PIN is not INTERRUPT-capable."
+ #endif
+ _ATTACH(J_MIN_PIN);
+ #endif
+ #if HAS_K_MAX
+ #if !LPC1768_PIN_INTERRUPT_M(K_MAX_PIN)
+ #error "K_MAX_PIN is not INTERRUPT-capable."
+ #endif
+ _ATTACH(K_MAX_PIN);
+ #elif HAS_K_MIN
+ #if !LPC1768_PIN_INTERRUPT_M(K_MIN_PIN)
+ #error "K_MIN_PIN is not INTERRUPT-capable."
+ #endif
+ _ATTACH(K_MIN_PIN);
+ #endif
}
diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h
index ce6d3fdde27f..be574a96e4ed 100644
--- a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h
+++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h
@@ -26,3 +26,9 @@
#elif EITHER(I2C_EEPROM, SPI_EEPROM)
#define USE_SHARED_EEPROM 1
#endif
+
+// LPC1768 boards seem to lose steps when saving to EEPROM during print (issue #20785)
+// TODO: Which other boards are incompatible?
+#if defined(MCU_LPC1768) && PRINTCOUNTER_SAVE_INTERVAL > 0
+ #define PRINTCOUNTER_SYNC 1
+#endif
diff --git a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h
index 11b8761550d7..46a876a836ca 100644
--- a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h
+++ b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h
@@ -31,7 +31,7 @@
/**
* Detect an old pins file by checking for old ADC pins values.
*/
-#define _OLD_TEMP_PIN(P) PIN_EXISTS(P) && _CAT(P,_PIN) <= 7 && _CAT(P,_PIN) != 2 && _CAT(P,_PIN) != 3
+#define _OLD_TEMP_PIN(P) PIN_EXISTS(P) && _CAT(P,_PIN) <= 7 && !WITHIN(_CAT(P,_PIN), TERN(LPC1768_IS_SKRV1_3, 0, 2), 3) // Include P0_00 and P0_01 for SKR V1.3 board
#if _OLD_TEMP_PIN(TEMP_BED)
#error "TEMP_BED_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)."
#elif _OLD_TEMP_PIN(TEMP_0)
@@ -92,7 +92,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o
#define ANY_TX(N,V...) DO(IS_TX##N,||,V)
#define ANY_RX(N,V...) DO(IS_RX##N,||,V)
-#if USING_SERIAL_0
+#if USING_HW_SERIAL0
#define IS_TX0(P) (P == P0_02)
#define IS_RX0(P) (P == P0_03)
#if IS_TX0(TMC_SW_MISO) || IS_RX0(TMC_SW_MOSI)
@@ -106,7 +106,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o
#undef IS_RX0
#endif
-#if USING_SERIAL_1
+#if USING_HW_SERIAL1
#define IS_TX1(P) (P == P0_15)
#define IS_RX1(P) (P == P0_16)
#define _IS_TX1_1 IS_TX1
@@ -116,7 +116,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o
#elif HAS_WIRED_LCD
#if IS_TX1(BTN_EN2) || IS_RX1(BTN_EN1)
#error "Serial port pins (1) conflict with Encoder Buttons!"
- #elif ANY_TX(1, SD_SCK_PIN, LCD_PINS_D4, DOGLCD_SCK, LCD_RESET_PIN, LCD_PINS_RS, SHIFT_CLK) \
+ #elif ANY_TX(1, SD_SCK_PIN, LCD_PINS_D4, DOGLCD_SCK, LCD_RESET_PIN, LCD_PINS_RS, SHIFT_CLK_PIN) \
|| ANY_RX(1, LCD_SDSS, LCD_PINS_RS, SD_MISO_PIN, DOGLCD_A0, SD_SS_PIN, LCD_SDSS, DOGLCD_CS, LCD_RESET_PIN, LCD_BACKLIGHT_PIN)
#error "Serial port pins (1) conflict with LCD pins!"
#endif
@@ -127,7 +127,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o
#undef _IS_RX1_1
#endif
-#if USING_SERIAL_2
+#if USING_HW_SERIAL2
#define IS_TX2(P) (P == P0_10)
#define IS_RX2(P) (P == P0_11)
#define _IS_TX2_1 IS_TX2
@@ -144,7 +144,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o
#error "Serial port pins (2) conflict with Z4 pins!"
#elif ANY_RX(2, X_DIR_PIN, Y_DIR_PIN)
#error "Serial port pins (2) conflict with other pins!"
- #elif Y_HOME_DIR < 0 && IS_TX2(Y_STOP_PIN)
+ #elif Y_HOME_TO_MIN && IS_TX2(Y_STOP_PIN)
#error "Serial port pins (2) conflict with Y endstop pin!"
#elif HAS_CUSTOM_PROBE_PIN && IS_TX2(Z_MIN_PROBE_PIN)
#error "Serial port pins (2) conflict with probe pin!"
@@ -161,7 +161,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o
#undef _IS_RX2_1
#endif
-#if USING_SERIAL_3
+#if USING_HW_SERIAL3
#define PIN_IS_TX3(P) (PIN_EXISTS(P) && P##_PIN == P0_00)
#define PIN_IS_RX3(P) (P##_PIN == P0_01)
#if PIN_IS_TX3(X_MIN) || PIN_IS_RX3(X_MAX)
@@ -270,7 +270,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o
#endif
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
- #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on this platform."
+ #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on LPC176x."
#elif ENABLED(SERIAL_STATS_DROPPED_RX)
- #error "SERIAL_STATS_DROPPED_RX is not supported on this platform."
+ #error "SERIAL_STATS_DROPPED_RX is not supported on LPX176x."
#endif
diff --git a/Marlin/src/HAL/LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp
index f41a57637639..ef0dc42c78ca 100644
--- a/Marlin/src/HAL/LPC1768/main.cpp
+++ b/Marlin/src/HAL/LPC1768/main.cpp
@@ -46,6 +46,8 @@ extern "C" {
void SysTick_Callback() { disk_timerproc(); }
+TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
+
void HAL_init() {
// Init LEDs
@@ -115,17 +117,15 @@ void HAL_init() {
PinCfg.Pinmode = 2; // no pull-up/pull-down
PINSEL_ConfigPin(&PinCfg);
// now set CLKOUT_EN bit
- LPC_SC->CLKOUTCFG |= (1<<8);
+ SBI(LPC_SC->CLKOUTCFG, 8);
#endif
USB_Init(); // USB Initialization
- USB_Connect(FALSE); // USB clear connection
+ USB_Connect(false); // USB clear connection
delay(1000); // Give OS time to notice
- USB_Connect(TRUE);
+ USB_Connect(true);
- #if HAS_SD_HOST_DRIVE
- MSC_SD_Init(0); // Enable USB SD card access
- #endif
+ TERN_(HAS_SD_HOST_DRIVE, MSC_SD_Init(0)); // Enable USB SD card access
const millis_t usb_timeout = millis() + 2000;
while (!USB_Configuration && PENDING(millis(), usb_timeout)) {
@@ -137,6 +137,8 @@ void HAL_init() {
}
HAL_timer_init();
+
+ TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler
}
// HAL idle task
diff --git a/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp b/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp
index cf14405484ff..9c1e158981da 100644
--- a/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp
+++ b/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp
@@ -22,7 +22,7 @@
#include "../../../inc/MarlinConfig.h"
-#if HAS_TFT_XPT2046 || HAS_TOUCH_BUTTONS
+#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS
#include "xpt2046.h"
#include
diff --git a/Marlin/src/HAL/LPC1768/tft/xpt2046.h b/Marlin/src/HAL/LPC1768/tft/xpt2046.h
index 65602bda0f40..aba0799e445f 100644
--- a/Marlin/src/HAL/LPC1768/tft/xpt2046.h
+++ b/Marlin/src/HAL/LPC1768/tft/xpt2046.h
@@ -54,7 +54,7 @@ enum XPTCoordinate : uint8_t {
XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE,
};
-#if !defined(XPT2046_Z1_THRESHOLD)
+#ifndef XPT2046_Z1_THRESHOLD
#define XPT2046_Z1_THRESHOLD 10
#endif
diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h
index e6744fb005bf..4b638546856f 100644
--- a/Marlin/src/HAL/LPC1768/timers.h
+++ b/Marlin/src/HAL/LPC1768/timers.h
@@ -152,7 +152,7 @@ FORCE_INLINE static void HAL_timer_disable_interrupt(const uint8_t timer_num) {
// This function is missing from CMSIS
FORCE_INLINE static bool NVIC_GetEnableIRQ(IRQn_Type IRQn) {
- return (NVIC->ISER[((uint32_t)IRQn) >> 5] & (1 << ((uint32_t)IRQn) & 0x1F)) != 0;
+ return TEST(NVIC->ISER[uint32_t(IRQn) >> 5], uint32_t(IRQn) & 0x1F);
}
FORCE_INLINE static bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp
index 592e27f6c006..0b0626de798f 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
@@ -66,7 +66,7 @@
void spiBegin();
void spiInit(uint8_t spiRate);
void spiSend(uint8_t b);
-void spiSend(const uint8_t* buf, size_t n);
+void spiSend(const uint8_t *buf, size_t n);
static uint8_t rs_last_state = 255;
diff --git a/Marlin/src/HAL/LPC1768/upload_extra_script.py b/Marlin/src/HAL/LPC1768/upload_extra_script.py
index 1daaa883ed6b..fb3aaef7cd38 100755
--- a/Marlin/src/HAL/LPC1768/upload_extra_script.py
+++ b/Marlin/src/HAL/LPC1768/upload_extra_script.py
@@ -8,9 +8,7 @@
target_filename = "FIRMWARE.CUR"
target_drive = "REARM"
-import os
-import getpass
-import platform
+import os,getpass,platform
current_OS = platform.system()
Import("env")
@@ -22,102 +20,104 @@ def print_error(e):
'or copy the firmware (.pio/build/%s/firmware.bin) manually to the appropriate disk\n' \
%(e, env.get('PIOENV')))
-try:
- #
- # Find a disk for upload
- #
- upload_disk = 'Disk not found'
- target_file_found = False
- target_drive_found = False
- if current_OS == 'Windows':
+def before_upload(source, target, env):
+ try:
#
- # platformio.ini will accept this for a Windows upload port designation: 'upload_port = L:'
- # Windows - doesn't care about the disk's name, only cares about the drive letter
- import subprocess
- from ctypes import windll
- import string
+ # Find a disk for upload
+ #
+ upload_disk = 'Disk not found'
+ target_file_found = False
+ target_drive_found = False
+ if current_OS == 'Windows':
+ #
+ # platformio.ini will accept this for a Windows upload port designation: 'upload_port = L:'
+ # Windows - doesn't care about the disk's name, only cares about the drive letter
+ import subprocess,string
+ from ctypes import windll
- # getting list of drives
- # https://stackoverflow.com/questions/827371/is-there-a-way-to-list-all-the-available-drive-letters-in-python
- drives = []
- bitmask = windll.kernel32.GetLogicalDrives()
- for letter in string.ascii_uppercase:
- if bitmask & 1:
- drives.append(letter)
- bitmask >>= 1
+ # getting list of drives
+ # https://stackoverflow.com/questions/827371/is-there-a-way-to-list-all-the-available-drive-letters-in-python
+ drives = []
+ bitmask = windll.kernel32.GetLogicalDrives()
+ for letter in string.ascii_uppercase:
+ if bitmask & 1:
+ drives.append(letter)
+ bitmask >>= 1
- for drive in drives:
- final_drive_name = drive + ':\\'
- # print ('disc check: {}'.format(final_drive_name))
- try:
- volume_info = str(subprocess.check_output('cmd /C dir ' + final_drive_name, stderr=subprocess.STDOUT))
- except Exception as e:
- print ('error:{}'.format(e))
- continue
- else:
- if target_drive in volume_info and not target_file_found: # set upload if not found target file yet
- target_drive_found = True
- upload_disk = final_drive_name
- if target_filename in volume_info:
- if not target_file_found:
+ for drive in drives:
+ final_drive_name = drive + ':\\'
+ # print ('disc check: {}'.format(final_drive_name))
+ try:
+ volume_info = str(subprocess.check_output('cmd /C dir ' + final_drive_name, stderr=subprocess.STDOUT))
+ except Exception as e:
+ print ('error:{}'.format(e))
+ continue
+ else:
+ if target_drive in volume_info and not target_file_found: # set upload if not found target file yet
+ target_drive_found = True
upload_disk = final_drive_name
- target_file_found = True
+ if target_filename in volume_info:
+ if not target_file_found:
+ upload_disk = final_drive_name
+ target_file_found = True
- elif current_OS == 'Linux':
- #
- # platformio.ini will accept this for a Linux upload port designation: 'upload_port = /media/media_name/drive'
- #
- drives = os.listdir(os.path.join(os.sep, 'media', getpass.getuser()))
- if target_drive in drives: # If target drive is found, use it.
- target_drive_found = True
- upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), target_drive) + os.sep
- else:
+ elif current_OS == 'Linux':
+ #
+ # platformio.ini will accept this for a Linux upload port designation: 'upload_port = /media/media_name/drive'
+ #
+ drives = os.listdir(os.path.join(os.sep, 'media', getpass.getuser()))
+ if target_drive in drives: # If target drive is found, use it.
+ target_drive_found = True
+ upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), target_drive) + os.sep
+ else:
+ for drive in drives:
+ try:
+ files = os.listdir(os.path.join(os.sep, 'media', getpass.getuser(), drive))
+ except:
+ continue
+ else:
+ if target_filename in files:
+ upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), drive) + os.sep
+ target_file_found = True
+ break
+ #
+ # set upload_port to drive if found
+ #
+
+ if target_file_found or target_drive_found:
+ env.Replace(
+ UPLOAD_FLAGS="-P$UPLOAD_PORT"
+ )
+
+ elif current_OS == 'Darwin': # MAC
+ #
+ # platformio.ini will accept this for a OSX upload port designation: 'upload_port = /media/media_name/drive'
+ #
+ drives = os.listdir('/Volumes') # human readable names
+ if target_drive in drives and not target_file_found: # set upload if not found target file yet
+ target_drive_found = True
+ upload_disk = '/Volumes/' + target_drive + '/'
for drive in drives:
try:
- files = os.listdir(os.path.join(os.sep, 'media', getpass.getuser(), drive))
+ filenames = os.listdir('/Volumes/' + drive + '/') # will get an error if the drive is protected
except:
continue
else:
- if target_filename in files:
- upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), drive) + os.sep
+ if target_filename in filenames:
+ if not target_file_found:
+ upload_disk = '/Volumes/' + drive + '/'
target_file_found = True
- break
- #
- # set upload_port to drive if found
- #
- if target_file_found or target_drive_found:
- env.Replace(
- UPLOAD_FLAGS="-P$UPLOAD_PORT"
- )
-
- elif current_OS == 'Darwin': # MAC
#
- # platformio.ini will accept this for a OSX upload port designation: 'upload_port = /media/media_name/drive'
+ # Set upload_port to drive if found
#
- drives = os.listdir('/Volumes') # human readable names
- if target_drive in drives and not target_file_found: # set upload if not found target file yet
- target_drive_found = True
- upload_disk = '/Volumes/' + target_drive + '/'
- for drive in drives:
- try:
- filenames = os.listdir('/Volumes/' + drive + '/') # will get an error if the drive is protected
- except:
- continue
- else:
- if target_filename in filenames:
- if not target_file_found:
- upload_disk = '/Volumes/' + drive + '/'
- target_file_found = True
+ if target_file_found or target_drive_found:
+ env.Replace(UPLOAD_PORT=upload_disk)
+ print('\nUpload disk: ', upload_disk, '\n')
+ else:
+ print_error('Autodetect Error')
- #
- # Set upload_port to drive if found
- #
- if target_file_found or target_drive_found:
- env.Replace(UPLOAD_PORT=upload_disk)
- print('\nUpload disk: ', upload_disk, '\n')
- else:
- print_error('Autodetect Error')
+ except Exception as e:
+ print_error(str(e))
-except Exception as e:
- print_error(str(e))
+env.AddPreAction("upload", before_upload)
diff --git a/Marlin/src/HAL/LPC1768/usb_serial.cpp b/Marlin/src/HAL/LPC1768/usb_serial.cpp
index d225ce418860..3c1fce54f95f 100644
--- a/Marlin/src/HAL/LPC1768/usb_serial.cpp
+++ b/Marlin/src/HAL/LPC1768/usb_serial.cpp
@@ -29,8 +29,8 @@
EmergencyParser::State emergency_state;
-bool CDC_RecvCallback(const char buffer) {
- emergency_parser.update(emergency_state, buffer);
+bool CDC_RecvCallback(const char c) {
+ emergency_parser.update(emergency_state, c);
return true;
}
diff --git a/Marlin/src/HAL/SAMD51/HAL.cpp b/Marlin/src/HAL/SAMD51/HAL.cpp
index d985ef37871f..5aa23cdaebe8 100644
--- a/Marlin/src/HAL/SAMD51/HAL.cpp
+++ b/Marlin/src/HAL/SAMD51/HAL.cpp
@@ -24,6 +24,24 @@
#include
#include
+#ifdef ADAFRUIT_GRAND_CENTRAL_M4
+ #if USING_HW_SERIALUSB
+ DefaultSerial1 MSerial0(false, Serial);
+ #endif
+ #if USING_HW_SERIAL0
+ DefaultSerial2 MSerial1(false, Serial1);
+ #endif
+ #if USING_HW_SERIAL1
+ DefaultSerial3 MSerial2(false, Serial2);
+ #endif
+ #if USING_HW_SERIAL2
+ DefaultSerial4 MSerial3(false, Serial3);
+ #endif
+ #if USING_HW_SERIAL3
+ DefaultSerial5 MSerial4(false, Serial4);
+ #endif
+#endif
+
// ------------------------
// Local defines
// ------------------------
@@ -39,6 +57,7 @@
#define GET_PROBE_ADC() TERN(HAS_TEMP_PROBE, PIN_TO_ADC(TEMP_PROBE_PIN), -1)
#define GET_BED_ADC() TERN(HAS_TEMP_ADC_BED, PIN_TO_ADC(TEMP_BED_PIN), -1)
#define GET_CHAMBER_ADC() TERN(HAS_TEMP_ADC_CHAMBER, PIN_TO_ADC(TEMP_CHAMBER_PIN), -1)
+#define GET_COOLER_ADC() TERN(HAS_TEMP_ADC_COOLER, PIN_TO_ADC(TEMP_COOLER_PIN), -1)
#define GET_FILAMENT_WIDTH_ADC() TERN(FILAMENT_WIDTH_SENSOR, PIN_TO_ADC(FILWIDTH_PIN), -1)
#define GET_BUTTONS_ADC() TERN(HAS_ADC_BUTTONS, PIN_TO_ADC(ADC_KEYPAD_PIN), -1)
@@ -48,6 +67,7 @@
|| GET_PROBE_ADC() == n \
|| GET_BED_ADC() == n \
|| GET_CHAMBER_ADC() == n \
+ || GET_COOLER_ADC() == n \
|| GET_FILAMENT_WIDTH_ADC() == n \
|| GET_BUTTONS_ADC() == n \
)
@@ -126,6 +146,9 @@ uint16_t HAL_adc_result;
#if GET_CHAMBER_ADC() == 0
TEMP_CHAMBER_PIN,
#endif
+ #if GET_COOLER_ADC() == 0
+ TEMP_COOLER_PIN,
+ #endif
#if GET_FILAMENT_WIDTH_ADC() == 0
FILWIDTH_PIN,
#endif
@@ -166,6 +189,9 @@ uint16_t HAL_adc_result;
#if GET_CHAMBER_ADC() == 1
TEMP_CHAMBER_PIN,
#endif
+ #if GET_COOLER_ADC() == 1
+ TEMP_COOLER_PIN,
+ #endif
#if GET_FILAMENT_WIDTH_ADC() == 1
FILWIDTH_PIN,
#endif
@@ -214,6 +240,9 @@ uint16_t HAL_adc_result;
#if GET_CHAMBER_ADC() == 0
{ PIN_TO_INPUTCTRL(TEMP_CHAMBER_PIN) },
#endif
+ #if GET_COOLER_ADC() == 0
+ { PIN_TO_INPUTCTRL(TEMP_COOLER_PIN) },
+ #endif
#if GET_FILAMENT_WIDTH_ADC() == 0
{ PIN_TO_INPUTCTRL(FILWIDTH_PIN) },
#endif
@@ -263,6 +292,9 @@ uint16_t HAL_adc_result;
#if GET_CHAMBER_ADC() == 1
{ PIN_TO_INPUTCTRL(TEMP_CHAMBER_PIN) },
#endif
+ #if GET_COOLER_ADC() == 1
+ { PIN_TO_INPUTCTRL(TEMP_COOLER_PIN) },
+ #endif
#if GET_FILAMENT_WIDTH_ADC() == 1
{ PIN_TO_INPUTCTRL(FILWIDTH_PIN) },
#endif
@@ -404,6 +436,8 @@ uint8_t HAL_get_reset_source() {
}
#pragma pop_macro("WDT")
+void HAL_reboot() { NVIC_SystemReset(); }
+
extern "C" {
void * _sbrk(int incr);
diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h
index ff9310114641..491c3f82c4a6 100644
--- a/Marlin/src/HAL/SAMD51/HAL.h
+++ b/Marlin/src/HAL/SAMD51/HAL.h
@@ -32,38 +32,56 @@
#include "MarlinSerial_AGCM4.h"
// Serial ports
-
- // MYSERIAL0 required before MarlinSerial includes!
-
- #define __MSERIAL(X) Serial##X
+ typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1;
+ typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2;
+ typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3;
+ typedef ForwardSerial1Class< decltype(Serial3) > DefaultSerial4;
+ typedef ForwardSerial1Class< decltype(Serial4) > DefaultSerial5;
+ extern DefaultSerial1 MSerial0;
+ extern DefaultSerial2 MSerial1;
+ extern DefaultSerial3 MSerial2;
+ extern DefaultSerial4 MSerial3;
+ extern DefaultSerial5 MSerial4;
+
+ #define __MSERIAL(X) MSerial##X
#define _MSERIAL(X) __MSERIAL(X)
#define MSERIAL(X) _MSERIAL(INCREMENT(X))
#if SERIAL_PORT == -1
- #define MYSERIAL0 Serial
+ #define MYSERIAL1 MSerial0
#elif WITHIN(SERIAL_PORT, 0, 3)
- #define MYSERIAL0 MSERIAL(SERIAL_PORT)
+ #define MYSERIAL1 MSERIAL(SERIAL_PORT)
#else
- #error "SERIAL_PORT must be from -1 to 3. Please update your configuration."
+ #error "SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB."
#endif
#ifdef SERIAL_PORT_2
#if SERIAL_PORT_2 == -1
- #define MYSERIAL1 Serial
+ #define MYSERIAL2 MSerial0
#elif WITHIN(SERIAL_PORT_2, 0, 3)
- #define MYSERIAL1 MSERIAL(SERIAL_PORT_2)
+ #define MYSERIAL2 MSERIAL(SERIAL_PORT_2)
+ #else
+ #error "SERIAL_PORT_2 must be from 0 to 3. You can also use -1 if the board supports Native USB."
+ #endif
+ #endif
+
+ #ifdef MMU2_SERIAL_PORT
+ #if MMU2_SERIAL_PORT == -1
+ #define MMU2_SERIAL MSerial0
+ #elif WITHIN(MMU2_SERIAL_PORT, 0, 3)
+ #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT)
#else
- #error "SERIAL_PORT_2 must be from -1 to 3. Please update your configuration."
+ #error "MMU2_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB."
#endif
#endif
#ifdef LCD_SERIAL_PORT
#if LCD_SERIAL_PORT == -1
- #define LCD_SERIAL Serial
+ #define LCD_SERIAL MSerial0
#elif WITHIN(LCD_SERIAL_PORT, 0, 3)
#define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT)
#else
- #error "LCD_SERIAL_PORT must be from -1 to 3. Please update your configuration."
+ #error "LCD_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB."
#endif
#endif
@@ -89,7 +107,7 @@ typedef int8_t pin_t;
void HAL_clear_reset_source(); // clear reset reason
uint8_t HAL_get_reset_source(); // get reset reason
-inline void HAL_reboot() {} // reboot the board or restart the bootloader
+void HAL_reboot();
//
// ADC
diff --git a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp
index c3acd38237c6..77f4d5ecd513 100644
--- a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp
+++ b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp
@@ -103,7 +103,7 @@
* @param nbyte Number of bytes to receive.
* @return Nothing
*/
- void spiRead(uint8_t* buf, uint16_t nbyte) {
+ void spiRead(uint8_t *buf, uint16_t nbyte) {
if (nbyte == 0) return;
memset(buf, 0xFF, nbyte);
sdSPI.beginTransaction(spiConfig);
@@ -132,7 +132,7 @@
*
* @details Uses DMA
*/
- void spiSendBlock(uint8_t token, const uint8_t* buf) {
+ void spiSendBlock(uint8_t token, const uint8_t *buf) {
sdSPI.beginTransaction(spiConfig);
sdSPI.transfer(token);
sdSPI.transfer((uint8_t*)buf, nullptr, 512);
diff --git a/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp
index abc5f3acbf77..a16ea2f75821 100644
--- a/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp
+++ b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp
@@ -21,30 +21,30 @@
#ifdef ADAFRUIT_GRAND_CENTRAL_M4
/**
- * Framework doesn't define some serial to save sercom resources
+ * Framework doesn't define some serials to save sercom resources
* hence if these are used I need to define them
*/
#include "../../inc/MarlinConfig.h"
-#if SERIAL_PORT == 1 || SERIAL_PORT_2 == 1
- Uart Serial2(&sercom4, PIN_SERIAL2_RX, PIN_SERIAL2_TX, PAD_SERIAL2_RX, PAD_SERIAL2_TX);
+#if USING_HW_SERIAL1
+ UartT Serial2(false, &sercom4, PIN_SERIAL2_RX, PIN_SERIAL2_TX, PAD_SERIAL2_RX, PAD_SERIAL2_TX);
void SERCOM4_0_Handler() { Serial2.IrqHandler(); }
void SERCOM4_1_Handler() { Serial2.IrqHandler(); }
void SERCOM4_2_Handler() { Serial2.IrqHandler(); }
void SERCOM4_3_Handler() { Serial2.IrqHandler(); }
#endif
-#if SERIAL_PORT == 2 || SERIAL_PORT_2 == 2
- Uart Serial3(&sercom1, PIN_SERIAL3_RX, PIN_SERIAL3_TX, PAD_SERIAL3_RX, PAD_SERIAL3_TX);
+#if USING_HW_SERIAL2
+ UartT Serial3(false, &sercom1, PIN_SERIAL3_RX, PIN_SERIAL3_TX, PAD_SERIAL3_RX, PAD_SERIAL3_TX);
void SERCOM1_0_Handler() { Serial3.IrqHandler(); }
void SERCOM1_1_Handler() { Serial3.IrqHandler(); }
void SERCOM1_2_Handler() { Serial3.IrqHandler(); }
void SERCOM1_3_Handler() { Serial3.IrqHandler(); }
#endif
-#if SERIAL_PORT == 3 || SERIAL_PORT_2 == 3
- Uart Serial4(&sercom5, PIN_SERIAL4_RX, PIN_SERIAL4_TX, PAD_SERIAL4_RX, PAD_SERIAL4_TX);
+#if USING_HW_SERIAL3
+ UartT Serial4(false, &sercom5, PIN_SERIAL4_RX, PIN_SERIAL4_TX, PAD_SERIAL4_RX, PAD_SERIAL4_TX);
void SERCOM5_0_Handler() { Serial4.IrqHandler(); }
void SERCOM5_1_Handler() { Serial4.IrqHandler(); }
void SERCOM5_2_Handler() { Serial4.IrqHandler(); }
diff --git a/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.h b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.h
index f3821d8d5a84..ac5a3793983e 100644
--- a/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.h
+++ b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.h
@@ -20,6 +20,10 @@
*/
#pragma once
-extern Uart Serial2;
-extern Uart Serial3;
-extern Uart Serial4;
+#include "../../core/serial_hook.h"
+
+typedef Serial1Class UartT;
+
+extern UartT Serial2;
+extern UartT Serial3;
+extern UartT Serial4;
diff --git a/Marlin/src/HAL/SAMD51/eeprom_wired.cpp b/Marlin/src/HAL/SAMD51/eeprom_wired.cpp
index d9a0225a7ae4..3481fe539c3e 100644
--- a/Marlin/src/HAL/SAMD51/eeprom_wired.cpp
+++ b/Marlin/src/HAL/SAMD51/eeprom_wired.cpp
@@ -41,12 +41,13 @@ bool PersistentStore::access_start() { eeprom_init(); return true; }
bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ uint16_t written = 0;
while (size--) {
const uint8_t v = *value;
uint8_t * const p = (uint8_t * const)pos;
- if (v != eeprom_read_byte(p)) {
+ if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed!
eeprom_write_byte(p, v);
- delay(2);
+ if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes
if (eeprom_read_byte(p) != v) {
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
return true;
diff --git a/Marlin/src/HAL/SAMD51/endstop_interrupts.h b/Marlin/src/HAL/SAMD51/endstop_interrupts.h
index daac7733875b..c46b6e072f90 100644
--- a/Marlin/src/HAL/SAMD51/endstop_interrupts.h
+++ b/Marlin/src/HAL/SAMD51/endstop_interrupts.h
@@ -47,80 +47,38 @@
#include "../../module/endstops.h"
-#define MATCH_EILINE(P1,P2) (P1 != P2 && PIN_TO_EILINE(P1) == PIN_TO_EILINE(P2))
-#if HAS_X_MAX
- #define MATCH_X_MAX_EILINE(P) MATCH_EILINE(P, X_MAX_PIN)
-#else
- #define MATCH_X_MAX_EILINE(P) false
-#endif
-#if HAS_X_MIN
- #define MATCH_X_MIN_EILINE(P) MATCH_EILINE(P, X_MIN_PIN)
-#else
- #define MATCH_X_MIN_EILINE(P) false
-#endif
-#if HAS_Y_MAX
- #define MATCH_Y_MAX_EILINE(P) MATCH_EILINE(P, Y_MAX_PIN)
-#else
- #define MATCH_Y_MAX_EILINE(P) false
-#endif
-#if HAS_Y_MIN
- #define MATCH_Y_MIN_EILINE(P) MATCH_EILINE(P, Y_MIN_PIN)
-#else
- #define MATCH_Y_MIN_EILINE(P) false
-#endif
-#if HAS_Z_MAX
- #define MATCH_Z_MAX_EILINE(P) MATCH_EILINE(P, Z_MAX_PIN)
-#else
- #define MATCH_Z_MAX_EILINE(P) false
-#endif
-#if HAS_Z_MIN
- #define MATCH_Z_MIN_EILINE(P) MATCH_EILINE(P, Z_MIN_PIN)
-#else
- #define MATCH_Z_MIN_EILINE(P) false
-#endif
-#if HAS_Z2_MAX
- #define MATCH_Z2_MAX_EILINE(P) MATCH_EILINE(P, Z2_MAX_PIN)
-#else
- #define MATCH_Z2_MAX_EILINE(P) false
-#endif
-#if HAS_Z2_MIN
- #define MATCH_Z2_MIN_EILINE(P) MATCH_EILINE(P, Z2_MIN_PIN)
-#else
- #define MATCH_Z2_MIN_EILINE(P) false
-#endif
-#if HAS_Z3_MAX
- #define MATCH_Z3_MAX_EILINE(P) MATCH_EILINE(P, Z3_MAX_PIN)
-#else
- #define MATCH_Z3_MAX_EILINE(P) false
-#endif
-#if HAS_Z3_MIN
- #define MATCH_Z3_MIN_EILINE(P) MATCH_EILINE(P, Z3_MIN_PIN)
-#else
- #define MATCH_Z3_MIN_EILINE(P) false
-#endif
-#if HAS_Z4_MAX
- #define MATCH_Z4_MAX_EILINE(P) MATCH_EILINE(P, Z4_MAX_PIN)
-#else
- #define MATCH_Z4_MAX_EILINE(P) false
-#endif
-#if HAS_Z4_MIN
- #define MATCH_Z4_MIN_EILINE(P) MATCH_EILINE(P, Z4_MIN_PIN)
-#else
- #define MATCH_Z4_MIN_EILINE(P) false
-#endif
-#if HAS_Z_MIN_PROBE_PIN
- #define MATCH_Z_MIN_PROBE_EILINE(P) MATCH_EILINE(P, Z_MIN_PROBE_PIN)
-#else
- #define MATCH_Z_MIN_PROBE_EILINE(P) false
-#endif
-#define AVAILABLE_EILINE(P) (PIN_TO_EILINE(P) != -1 \
- && !MATCH_X_MAX_EILINE(P) && !MATCH_X_MIN_EILINE(P) \
- && !MATCH_Y_MAX_EILINE(P) && !MATCH_Y_MIN_EILINE(P) \
- && !MATCH_Z_MAX_EILINE(P) && !MATCH_Z_MIN_EILINE(P) \
- && !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \
- && !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \
- && !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P) \
- && !MATCH_Z_MIN_PROBE_EILINE(P))
+#define MATCH_EILINE(P1,P2) (P1 != P2 && PIN_TO_EILINE(P1) == PIN_TO_EILINE(P2))
+#define MATCH_X_MAX_EILINE(P) TERN0(HAS_X_MAX, DEFER4(MATCH_EILINE)(P, X_MAX_PIN))
+#define MATCH_X_MIN_EILINE(P) TERN0(HAS_X_MIN, DEFER4(MATCH_EILINE)(P, X_MIN_PIN))
+#define MATCH_Y_MAX_EILINE(P) TERN0(HAS_Y_MAX, DEFER4(MATCH_EILINE)(P, Y_MAX_PIN))
+#define MATCH_Y_MIN_EILINE(P) TERN0(HAS_Y_MIN, DEFER4(MATCH_EILINE)(P, Y_MIN_PIN))
+#define MATCH_Z_MAX_EILINE(P) TERN0(HAS_Z_MAX, DEFER4(MATCH_EILINE)(P, Z_MAX_PIN))
+#define MATCH_Z_MIN_EILINE(P) TERN0(HAS_Z_MIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PIN))
+#define MATCH_I_MAX_EILINE(P) TERN0(HAS_I_MAX, DEFER4(MATCH_EILINE)(P, I_MAX_PIN))
+#define MATCH_I_MIN_EILINE(P) TERN0(HAS_I_MIN, DEFER4(MATCH_EILINE)(P, I_MIN_PIN))
+#define MATCH_J_MAX_EILINE(P) TERN0(HAS_J_MAX, DEFER4(MATCH_EILINE)(P, J_MAX_PIN))
+#define MATCH_J_MIN_EILINE(P) TERN0(HAS_J_MIN, DEFER4(MATCH_EILINE)(P, J_MIN_PIN))
+#define MATCH_K_MAX_EILINE(P) TERN0(HAS_K_MAX, DEFER4(MATCH_EILINE)(P, K_MAX_PIN))
+#define MATCH_K_MIN_EILINE(P) TERN0(HAS_K_MIN, DEFER4(MATCH_EILINE)(P, K_MIN_PIN))
+#define MATCH_Z2_MAX_EILINE(P) TERN0(HAS_Z2_MAX, DEFER4(MATCH_EILINE)(P, Z2_MAX_PIN))
+#define MATCH_Z2_MIN_EILINE(P) TERN0(HAS_Z2_MIN, DEFER4(MATCH_EILINE)(P, Z2_MIN_PIN))
+#define MATCH_Z3_MAX_EILINE(P) TERN0(HAS_Z3_MAX, DEFER4(MATCH_EILINE)(P, Z3_MAX_PIN))
+#define MATCH_Z3_MIN_EILINE(P) TERN0(HAS_Z3_MIN, DEFER4(MATCH_EILINE)(P, Z3_MIN_PIN))
+#define MATCH_Z4_MAX_EILINE(P) TERN0(HAS_Z4_MAX, DEFER4(MATCH_EILINE)(P, Z4_MAX_PIN))
+#define MATCH_Z4_MIN_EILINE(P) TERN0(HAS_Z4_MIN, DEFER4(MATCH_EILINE)(P, Z4_MIN_PIN))
+#define MATCH_Z_MIN_PROBE_EILINE(P) TERN0(HAS_Z_MIN_PROBE_PIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PROBE_PIN))
+
+#define AVAILABLE_EILINE(P) ( PIN_TO_EILINE(P) != -1 \
+ && !MATCH_X_MAX_EILINE(P) && !MATCH_X_MIN_EILINE(P) \
+ && !MATCH_Y_MAX_EILINE(P) && !MATCH_Y_MIN_EILINE(P) \
+ && !MATCH_Z_MAX_EILINE(P) && !MATCH_Z_MIN_EILINE(P) \
+ && !MATCH_I_MAX_EILINE(P) && !MATCH_I_MIN_EILINE(P) \
+ && !MATCH_J_MAX_EILINE(P) && !MATCH_J_MIN_EILINE(P) \
+ && !MATCH_K_MAX_EILINE(P) && !MATCH_K_MIN_EILINE(P) \
+ && !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \
+ && !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \
+ && !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P) \
+ && !MATCH_Z_MIN_PROBE_EILINE(P) )
// One ISR for all EXT-Interrupts
void endstop_ISR() { endstops.update(); }
@@ -204,5 +162,37 @@ void setup_endstop_interrupts() {
#error "Z_MIN_PROBE_PIN has no EXTINT line available."
#endif
_ATTACH(Z_MIN_PROBE_PIN);
+ #elif HAS_I_MAX
+ #if !AVAILABLE_EILINE(I_MAX_PIN)
+ #error "I_MAX_PIN has no EXTINT line available."
+ #endif
+ attachInterrupt(I_MAX_PIN, endstop_ISR, CHANGE);
+ #elif HAS_I_MIN
+ #if !AVAILABLE_EILINE(I_MIN_PIN)
+ #error "I_MIN_PIN has no EXTINT line available."
+ #endif
+ attachInterrupt(I_MIN_PIN, endstop_ISR, CHANGE);
+ #endif
+ #if HAS_J_MAX
+ #if !AVAILABLE_EILINE(J_MAX_PIN)
+ #error "J_MAX_PIN has no EXTINT line available."
+ #endif
+ attachInterrupt(J_MAX_PIN, endstop_ISR, CHANGE);
+ #elif HAS_J_MIN
+ #if !AVAILABLE_EILINE(J_MIN_PIN)
+ #error "J_MIN_PIN has no EXTINT line available."
+ #endif
+ attachInterrupt(J_MIN_PIN, endstop_ISR, CHANGE);
+ #endif
+ #if HAS_K_MAX
+ #if !AVAILABLE_EILINE(K_MAX_PIN)
+ #error "K_MAX_PIN has no EXTINT line available."
+ #endif
+ attachInterrupt(K_MAX_PIN, endstop_ISR, CHANGE);
+ #elif HAS_K_MIN
+ #if !AVAILABLE_EILINE(K_MIN_PIN)
+ #error "K_MIN_PIN has no EXTINT line available."
+ #endif
+ attachInterrupt(K_MIN_PIN, endstop_ISR, CHANGE);
#endif
}
diff --git a/Marlin/src/HAL/SAMD51/fastio.h b/Marlin/src/HAL/SAMD51/fastio.h
index c456dfce30cb..a95b7cac0ce9 100644
--- a/Marlin/src/HAL/SAMD51/fastio.h
+++ b/Marlin/src/HAL/SAMD51/fastio.h
@@ -31,7 +31,7 @@
*/
#ifndef MASK
- #define MASK(PIN) (1 << PIN)
+ #define MASK(PIN) _BV(PIN)
#endif
/**
diff --git a/Marlin/src/HAL/SAMD51/inc/SanityCheck.h b/Marlin/src/HAL/SAMD51/inc/SanityCheck.h
index 5d610acac85c..2a4bde98e6cb 100644
--- a/Marlin/src/HAL/SAMD51/inc/SanityCheck.h
+++ b/Marlin/src/HAL/SAMD51/inc/SanityCheck.h
@@ -50,3 +50,7 @@
#if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY
#error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported on SAMD51."
#endif
+
+#if ENABLED(POSTMORTEM_DEBUGGING)
+ #error "POSTMORTEM_DEBUGGING is not yet supported on AGCM4."
+#endif
diff --git a/Marlin/src/HAL/SAMD51/timers.cpp b/Marlin/src/HAL/SAMD51/timers.cpp
index a68af2e074ae..5c55d324079a 100644
--- a/Marlin/src/HAL/SAMD51/timers.cpp
+++ b/Marlin/src/HAL/SAMD51/timers.cpp
@@ -157,7 +157,7 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num) {
// missing from CMSIS: Check if interrupt is enabled or not
static bool NVIC_GetEnabledIRQ(IRQn_Type IRQn) {
- return (NVIC->ISER[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F))) != 0;
+ return TEST(NVIC->ISER[uint32_t(IRQn) >> 5], uint32_t(IRQn) & 0x1F);
}
bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp
index c886f9c0b988..e09b52f7db5a 100644
--- a/Marlin/src/HAL/STM32/HAL.cpp
+++ b/Marlin/src/HAL/STM32/HAL.cpp
@@ -28,6 +28,10 @@
#include "../../inc/MarlinConfig.h"
#include "../shared/Delay.h"
+#ifdef USBCON
+ DefaultSerial1 MSerial0(false, SerialUSB);
+#endif
+
#if ENABLED(SRAM_EEPROM_EMULATION)
#if STM32F7xx
#include
@@ -38,6 +42,11 @@
#endif
#endif
+#if HAS_SD_HOST_DRIVE
+ #include "msc_sd.h"
+ #include "usbd_cdc_if.h"
+#endif
+
// ------------------------
// Public Variables
// ------------------------
@@ -48,21 +57,18 @@ uint16_t HAL_adc_result;
// Public functions
// ------------------------
-// Needed for DELAY_NS() / DELAY_US() on CORTEX-M7
-#if (defined(__arm__) || defined(__thumb__)) && __CORTEX_M == 7
- // HAL pre-initialization task
- // Force the preinit function to run between the premain() and main() function
- // of the STM32 arduino core
- __attribute__((constructor (102)))
- void HAL_preinit() {
- enableCycleCounter();
- }
-#endif
+TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
// HAL initialization task
void HAL_init() {
FastIO_init();
+ // Ensure F_CPU is a constant expression.
+ // If the compiler breaks here, it means that delay code that should compute at compile time will not work.
+ // So better safe than sorry here.
+ constexpr int cpuFreq = F_CPU;
+ UNUSED(cpuFreq);
+
#if ENABLED(SDSUPPORT) && DISABLED(SDIO_SUPPORT) && (defined(SDSS) && SDSS != -1)
OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up
#endif
@@ -84,6 +90,27 @@ void HAL_init() {
#if ENABLED(EMERGENCY_PARSER) && USBD_USE_CDC
USB_Hook_init();
#endif
+
+ TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler
+
+ #if HAS_SD_HOST_DRIVE
+ MSC_SD_init(); // Enable USB SD card access
+ #endif
+
+ #if PIN_EXISTS(USB_CONNECT)
+ OUT_WRITE(USB_CONNECT_PIN, !USB_CONNECT_INVERTING); // USB clear connection
+ delay(1000); // Give OS time to notice
+ WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING);
+ #endif
+}
+
+// HAL idle task
+void HAL_idletask() {
+ #if HAS_SHARED_MEDIA
+ // Stm32duino currently doesn't have a "loop/idle" method
+ CDC_resume_receive();
+ CDC_continue_transmit();
+ #endif
}
void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); }
@@ -112,6 +139,8 @@ uint8_t HAL_get_reset_source() {
;
}
+void HAL_reboot() { NVIC_SystemReset(); }
+
void _delay_ms(const int delay_ms) { delay(delay_ms); }
extern "C" {
@@ -126,8 +155,8 @@ extern "C" {
void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); }
uint16_t HAL_adc_get_result() { return HAL_adc_result; }
-// Reset the system (to initiate a firmware flash)
-void flashFirmware(const int16_t) { NVIC_SystemReset(); }
+// Reset the system to initiate a firmware flash
+void flashFirmware(const int16_t) { HAL_reboot(); }
// Maple Compatibility
volatile uint32_t systick_uptime_millis = 0;
diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h
index b1c27e4ec5fb..02bee57ba3ac 100644
--- a/Marlin/src/HAL/STM32/HAL.h
+++ b/Marlin/src/HAL/STM32/HAL.h
@@ -37,41 +37,64 @@
#include
+//
+// Serial Ports
+//
#ifdef USBCON
#include
+ #include "../../core/serial_hook.h"
+ typedef ForwardSerial1Class< decltype(SerialUSB) > DefaultSerial1;
+ extern DefaultSerial1 MSerial0;
#endif
-// ------------------------
-// Defines
-// ------------------------
#define _MSERIAL(X) MSerial##X
#define MSERIAL(X) _MSERIAL(X)
#if SERIAL_PORT == -1
- #define MYSERIAL0 SerialUSB
+ #define MYSERIAL1 MSerial0
#elif WITHIN(SERIAL_PORT, 1, 6)
- #define MYSERIAL0 MSERIAL(SERIAL_PORT)
+ #define MYSERIAL1 MSERIAL(SERIAL_PORT)
#else
- #error "SERIAL_PORT must be -1 or from 1 to 6. Please update your configuration."
+ #error "SERIAL_PORT must be from 1 to 6. You can also use -1 if the board supports Native USB."
#endif
#ifdef SERIAL_PORT_2
#if SERIAL_PORT_2 == -1
- #define MYSERIAL1 SerialUSB
+ #define MYSERIAL2 MSerial0
#elif WITHIN(SERIAL_PORT_2, 1, 6)
- #define MYSERIAL1 MSERIAL(SERIAL_PORT_2)
+ #define MYSERIAL2 MSERIAL(SERIAL_PORT_2)
+ #else
+ #error "SERIAL_PORT_2 must be from 1 to 6. You can also use -1 if the board supports Native USB."
+ #endif
+#endif
+
+#ifdef SERIAL_PORT_3
+ #if SERIAL_PORT_3 == -1
+ #define MYSERIAL3 MSerial0
+ #elif WITHIN(SERIAL_PORT_3, 1, 6)
+ #define MYSERIAL3 MSERIAL(SERIAL_PORT_3)
#else
- #error "SERIAL_PORT_2 must be -1 or from 1 to 6. Please update your configuration."
+ #error "SERIAL_PORT_3 must be from 1 to 6. You can also use -1 if the board supports Native USB."
+ #endif
+#endif
+
+#ifdef MMU2_SERIAL_PORT
+ #if MMU2_SERIAL_PORT == -1
+ #define MMU2_SERIAL MSerial0
+ #elif WITHIN(MMU2_SERIAL_PORT, 1, 6)
+ #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT)
+ #else
+ #error "MMU2_SERIAL_PORT must be from 1 to 6. You can also use -1 if the board supports Native USB."
#endif
#endif
#ifdef LCD_SERIAL_PORT
#if LCD_SERIAL_PORT == -1
- #define LCD_SERIAL SerialUSB
+ #define LCD_SERIAL MSerial0
#elif WITHIN(LCD_SERIAL_PORT, 1, 6)
#define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT)
#else
- #error "LCD_SERIAL_PORT must be -1 or from 1 to 6. Please update your configuration."
+ #error "LCD_SERIAL_PORT must be from 1 to 6. You can also use -1 if the board supports Native USB."
#endif
#if HAS_DGUS_LCD
#define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite()
@@ -96,14 +119,6 @@
// On AVR this is in math.h?
#define square(x) ((x)*(x))
-#ifndef strncpy_P
- #define strncpy_P(dest, src, num) strncpy((dest), (src), (num))
-#endif
-
-// Fix bug in pgm_read_ptr
-#undef pgm_read_ptr
-#define pgm_read_ptr(addr) (*(addr))
-
// ------------------------
// Types
// ------------------------
@@ -130,6 +145,8 @@ extern uint16_t HAL_adc_result;
// Enable hooks into setup for HAL
void HAL_init();
+#define HAL_IDLETASK 1
+void HAL_idletask();
// Clear reset reason
void HAL_clear_reset_source();
@@ -137,7 +154,7 @@ void HAL_clear_reset_source();
// Reset reason
uint8_t HAL_get_reset_source();
-inline void HAL_reboot() {} // reboot the board or restart the bootloader
+void HAL_reboot();
void _delay_ms(const int delay);
@@ -178,6 +195,7 @@ uint16_t HAL_adc_get_result();
#ifdef STM32F1xx
#define JTAG_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_JTAGDISABLE)
#define JTAGSWD_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_DISABLE)
+ #define JTAGSWD_RESET() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_RESET); // Reset: FULL SWD+JTAG
#endif
#define PLATFORM_M997_SUPPORT
@@ -187,6 +205,7 @@ void flashFirmware(const int16_t);
typedef void (*systickCallback_t)(void);
void systick_attach_callback(systickCallback_t cb);
void HAL_SYSTICK_Callback();
+
extern volatile uint32_t systick_uptime_millis;
#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment
diff --git a/Marlin/src/HAL/STM32/HAL_MinSerial.cpp b/Marlin/src/HAL/STM32/HAL_MinSerial.cpp
new file mode 100644
index 000000000000..7268eed5919c
--- /dev/null
+++ b/Marlin/src/HAL/STM32/HAL_MinSerial.cpp
@@ -0,0 +1,152 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ * Copyright (c) 2017 Victor Perez
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../inc/MarlinConfigPre.h"
+
+#if ENABLED(POSTMORTEM_DEBUGGING)
+
+#include "../shared/HAL_MinSerial.h"
+#include "watchdog.h"
+
+/* Instruction Synchronization Barrier */
+#define isb() __asm__ __volatile__ ("isb" : : : "memory")
+
+/* Data Synchronization Barrier */
+#define dsb() __asm__ __volatile__ ("dsb" : : : "memory")
+
+// Dumb mapping over the registers of a USART device on STM32
+struct USARTMin {
+ volatile uint32_t SR;
+ volatile uint32_t DR;
+ volatile uint32_t BRR;
+ volatile uint32_t CR1;
+ volatile uint32_t CR2;
+};
+
+#if WITHIN(SERIAL_PORT, 1, 6)
+ // Depending on the CPU, the serial port is different for USART1
+ static const uintptr_t regsAddr[] = {
+ TERN(STM32F1xx, 0x40013800, 0x40011000), // USART1
+ 0x40004400, // USART2
+ 0x40004800, // USART3
+ 0x40004C00, // UART4_BASE
+ 0x40005000, // UART5_BASE
+ 0x40011400 // USART6
+ };
+ static USARTMin * regs = (USARTMin*)regsAddr[SERIAL_PORT - 1];
+#endif
+
+static void TXBegin() {
+ #if !WITHIN(SERIAL_PORT, 1, 6)
+ #warning "Using POSTMORTEM_DEBUGGING requires a physical U(S)ART hardware in case of severe error."
+ #warning "Disabling the severe error reporting feature currently because the used serial port is not a HW port."
+ #else
+ // This is common between STM32F1/STM32F2 and STM32F4
+ const int nvicUART[] = { /* NVIC_USART1 */ 37, /* NVIC_USART2 */ 38, /* NVIC_USART3 */ 39, /* NVIC_UART4 */ 52, /* NVIC_UART5 */ 53, /* NVIC_USART6 */ 71 };
+ int nvicIndex = nvicUART[SERIAL_PORT - 1];
+
+ struct NVICMin {
+ volatile uint32_t ISER[32];
+ volatile uint32_t ICER[32];
+ };
+
+ NVICMin *nvicBase = (NVICMin*)0xE000E100;
+ SBI32(nvicBase->ICER[nvicIndex >> 5], nvicIndex & 0x1F);
+
+ // We NEED memory barriers to ensure Interrupts are actually disabled!
+ // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
+ dsb();
+ isb();
+
+ // Example for USART1 disable: (RCC->APB2ENR &= ~(RCC_APB2ENR_USART1EN))
+ // Too difficult to reimplement here, let's query the STM32duino macro here
+ #if SERIAL_PORT == 1
+ __HAL_RCC_USART1_CLK_DISABLE();
+ __HAL_RCC_USART1_CLK_ENABLE();
+ #elif SERIAL_PORT == 2
+ __HAL_RCC_USART2_CLK_DISABLE();
+ __HAL_RCC_USART2_CLK_ENABLE();
+ #elif SERIAL_PORT == 3
+ __HAL_RCC_USART3_CLK_DISABLE();
+ __HAL_RCC_USART3_CLK_ENABLE();
+ #elif SERIAL_PORT == 4
+ __HAL_RCC_UART4_CLK_DISABLE(); // BEWARE: UART4 and not USART4 here
+ __HAL_RCC_UART4_CLK_ENABLE();
+ #elif SERIAL_PORT == 5
+ __HAL_RCC_UART5_CLK_DISABLE(); // BEWARE: UART5 and not USART5 here
+ __HAL_RCC_UART5_CLK_ENABLE();
+ #elif SERIAL_PORT == 6
+ __HAL_RCC_USART6_CLK_DISABLE();
+ __HAL_RCC_USART6_CLK_ENABLE();
+ #endif
+
+ uint32_t brr = regs->BRR;
+ regs->CR1 = 0; // Reset the USART
+ regs->CR2 = 0; // 1 stop bit
+
+ // If we don't touch the BRR (baudrate register), we don't need to recompute.
+ regs->BRR = brr;
+
+ regs->CR1 = _BV(3) | _BV(13); // 8 bits, no parity, 1 stop bit (TE | UE)
+ #endif
+}
+
+// A SW memory barrier, to ensure GCC does not overoptimize loops
+#define sw_barrier() __asm__ volatile("": : :"memory");
+static void TX(char c) {
+ #if WITHIN(SERIAL_PORT, 1, 6)
+ constexpr uint32_t usart_sr_txe = _BV(7);
+ while (!(regs->SR & usart_sr_txe)) {
+ TERN_(USE_WATCHDOG, HAL_watchdog_refresh());
+ sw_barrier();
+ }
+ regs->DR = c;
+ #else
+ // Let's hope a mystical guru will fix this, one day by writting interrupt-free USB CDC ACM code (or, at least, by polling the registers since interrupt will be queued but will never trigger)
+ // For now, it's completely lost to oblivion.
+ #endif
+}
+
+void install_min_serial() {
+ HAL_min_serial_init = &TXBegin;
+ HAL_min_serial_out = &TX;
+}
+
+#if DISABLED(DYNAMIC_VECTORTABLE) && DISABLED(STM32F0xx) // Cortex M0 can't jump to a symbol that's too far from the current function, so we work around this in exception_arm.cpp
+extern "C" {
+ __attribute__((naked)) void JumpHandler_ASM() {
+ __asm__ __volatile__ (
+ "b CommonHandler_ASM\n"
+ );
+ }
+ void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) HardFault_Handler();
+ void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) BusFault_Handler();
+ void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) UsageFault_Handler();
+ void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) MemManage_Handler();
+ void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) NMI_Handler();
+}
+#endif
+
+#endif // POSTMORTEM_DEBUGGING
+#endif // ARDUINO_ARCH_STM32
diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp
index eef480777bb7..bd36562de9ca 100644
--- a/Marlin/src/HAL/STM32/HAL_SPI.cpp
+++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp
@@ -51,18 +51,28 @@ static SPISettings spiConfig;
OUT_WRITE(SD_MOSI_PIN, HIGH);
}
- static uint16_t delay_STM32_soft_spi;
+ // Use function with compile-time value so we can actually reach the desired frequency
+ // Need to adjust this a little bit: on a 72MHz clock, we have 14ns/clock
+ // and we'll use ~3 cycles to jump to the method and going back, so it'll take ~40ns from the given clock here
+ #define CALLING_COST_NS (3U * 1000000000U) / (F_CPU)
+ void (*delaySPIFunc)();
+ void delaySPI_125() { DELAY_NS(125 - CALLING_COST_NS); }
+ void delaySPI_250() { DELAY_NS(250 - CALLING_COST_NS); }
+ void delaySPI_500() { DELAY_NS(500 - CALLING_COST_NS); }
+ void delaySPI_1000() { DELAY_NS(1000 - CALLING_COST_NS); }
+ void delaySPI_2000() { DELAY_NS(2000 - CALLING_COST_NS); }
+ void delaySPI_4000() { DELAY_NS(4000 - CALLING_COST_NS); }
void spiInit(uint8_t spiRate) {
// Use datarates Marlin uses
switch (spiRate) {
- case SPI_FULL_SPEED: delay_STM32_soft_spi = 125; break; // desired: 8,000,000 actual: ~1.1M
- case SPI_HALF_SPEED: delay_STM32_soft_spi = 125; break; // desired: 4,000,000 actual: ~1.1M
- case SPI_QUARTER_SPEED:delay_STM32_soft_spi = 250; break; // desired: 2,000,000 actual: ~890K
- case SPI_EIGHTH_SPEED: delay_STM32_soft_spi = 500; break; // desired: 1,000,000 actual: ~590K
- case SPI_SPEED_5: delay_STM32_soft_spi = 1000; break; // desired: 500,000 actual: ~360K
- case SPI_SPEED_6: delay_STM32_soft_spi = 2000; break; // desired: 250,000 actual: ~210K
- default: delay_STM32_soft_spi = 4000; break; // desired: 125,000 actual: ~123K
+ case SPI_FULL_SPEED: delaySPIFunc = &delaySPI_125; break; // desired: 8,000,000 actual: ~1.1M
+ case SPI_HALF_SPEED: delaySPIFunc = &delaySPI_125; break; // desired: 4,000,000 actual: ~1.1M
+ case SPI_QUARTER_SPEED:delaySPIFunc = &delaySPI_250; break; // desired: 2,000,000 actual: ~890K
+ case SPI_EIGHTH_SPEED: delaySPIFunc = &delaySPI_500; break; // desired: 1,000,000 actual: ~590K
+ case SPI_SPEED_5: delaySPIFunc = &delaySPI_1000; break; // desired: 500,000 actual: ~360K
+ case SPI_SPEED_6: delaySPIFunc = &delaySPI_2000; break; // desired: 250,000 actual: ~210K
+ default: delaySPIFunc = &delaySPI_4000; break; // desired: 125,000 actual: ~123K
}
SPI.begin();
}
@@ -75,9 +85,9 @@ static SPISettings spiConfig;
WRITE(SD_SCK_PIN, LOW);
WRITE(SD_MOSI_PIN, b & 0x80);
- DELAY_NS(delay_STM32_soft_spi);
+ delaySPIFunc();
WRITE(SD_SCK_PIN, HIGH);
- DELAY_NS(delay_STM32_soft_spi);
+ delaySPIFunc();
b <<= 1; // little setup time
b |= (READ(SD_MISO_PIN) != 0);
@@ -153,11 +163,9 @@ static SPISettings spiConfig;
}
spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0);
- #if ENABLED(CUSTOM_SPI_PINS)
- SPI.setMISO(SD_MISO_PIN);
- SPI.setMOSI(SD_MOSI_PIN);
- SPI.setSCLK(SD_SCK_PIN);
- #endif
+ SPI.setMISO(SD_MISO_PIN);
+ SPI.setMOSI(SD_MOSI_PIN);
+ SPI.setSCLK(SD_SCK_PIN);
SPI.begin();
}
@@ -183,7 +191,7 @@ static SPISettings spiConfig;
*
* @details Uses DMA
*/
- void spiRead(uint8_t* buf, uint16_t nbyte) {
+ void spiRead(uint8_t *buf, uint16_t nbyte) {
if (nbyte == 0) return;
memset(buf, 0xFF, nbyte);
SPI.transfer(buf, nbyte);
@@ -208,7 +216,7 @@ static SPISettings spiConfig;
*
* @details Use DMA
*/
- void spiSendBlock(uint8_t token, const uint8_t* buf) {
+ void spiSendBlock(uint8_t token, const uint8_t *buf) {
uint8_t rxBuf[512];
SPI.transfer(token);
SPI.transfer((uint8_t*)buf, &rxBuf, 512);
diff --git a/Marlin/src/HAL/STM32/MarlinSPI.cpp b/Marlin/src/HAL/STM32/MarlinSPI.cpp
index 5086b4178461..896ec1433f40 100644
--- a/Marlin/src/HAL/STM32/MarlinSPI.cpp
+++ b/Marlin/src/HAL/STM32/MarlinSPI.cpp
@@ -19,7 +19,7 @@
* along with this program. If not, see .
*
*/
-#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(STM32H7xx)
#include "MarlinSPI.h"
diff --git a/Marlin/src/HAL/STM32/MarlinSerial.cpp b/Marlin/src/HAL/STM32/MarlinSerial.cpp
index 50765ee9958e..265e8b5ab61b 100644
--- a/Marlin/src/HAL/STM32/MarlinSerial.cpp
+++ b/Marlin/src/HAL/STM32/MarlinSerial.cpp
@@ -28,28 +28,47 @@
#ifndef USART4
#define USART4 UART4
#endif
-
#ifndef USART5
#define USART5 UART5
#endif
#define DECLARE_SERIAL_PORT(ser_num) \
void _rx_complete_irq_ ## ser_num (serial_t * obj); \
- MarlinSerial MSerial ## ser_num (USART ## ser_num, &_rx_complete_irq_ ## ser_num); \
+ MSerialT MSerial ## ser_num (true, USART ## ser_num, &_rx_complete_irq_ ## ser_num); \
void _rx_complete_irq_ ## ser_num (serial_t * obj) { MSerial ## ser_num ._rx_complete_irq(obj); }
-#define DECLARE_SERIAL_PORT_EXP(ser_num) DECLARE_SERIAL_PORT(ser_num)
-
-#if defined(SERIAL_PORT) && SERIAL_PORT >= 0
- DECLARE_SERIAL_PORT_EXP(SERIAL_PORT)
+#if USING_HW_SERIAL1
+ DECLARE_SERIAL_PORT(1)
#endif
-
-#if defined(SERIAL_PORT_2) && SERIAL_PORT_2 >= 0
- DECLARE_SERIAL_PORT_EXP(SERIAL_PORT_2)
+#if USING_HW_SERIAL2
+ DECLARE_SERIAL_PORT(2)
#endif
-
-#if defined(LCD_SERIAL_PORT) && LCD_SERIAL_PORT >= 0
- DECLARE_SERIAL_PORT_EXP(LCD_SERIAL_PORT)
+#if USING_HW_SERIAL3
+ DECLARE_SERIAL_PORT(3)
+#endif
+#if USING_HW_SERIAL4
+ DECLARE_SERIAL_PORT(4)
+#endif
+#if USING_HW_SERIAL5
+ DECLARE_SERIAL_PORT(5)
+#endif
+#if USING_HW_SERIAL6
+ DECLARE_SERIAL_PORT(6)
+#endif
+#if USING_HW_SERIAL7
+ DECLARE_SERIAL_PORT(7)
+#endif
+#if USING_HW_SERIAL8
+ DECLARE_SERIAL_PORT(8)
+#endif
+#if USING_HW_SERIAL9
+ DECLARE_SERIAL_PORT(9)
+#endif
+#if USING_HW_SERIAL10
+ DECLARE_SERIAL_PORT(10)
+#endif
+#if USING_HW_SERIALLP1
+ DECLARE_SERIAL_PORT(LP1)
#endif
void MarlinSerial::begin(unsigned long baud, uint8_t config) {
@@ -77,7 +96,7 @@ void MarlinSerial::_rx_complete_irq(serial_t *obj) {
}
#if ENABLED(EMERGENCY_PARSER)
- emergency_parser.update(emergency_state, c);
+ emergency_parser.update(static_cast(this)->emergency_state, c);
#endif
}
}
diff --git a/Marlin/src/HAL/STM32/MarlinSerial.h b/Marlin/src/HAL/STM32/MarlinSerial.h
index 3611cc78d7ce..ab5c4260af2d 100644
--- a/Marlin/src/HAL/STM32/MarlinSerial.h
+++ b/Marlin/src/HAL/STM32/MarlinSerial.h
@@ -24,41 +24,33 @@
#include "../../feature/e_parser.h"
#endif
+#include "../../core/serial_hook.h"
+
typedef void (*usart_rx_callback_t)(serial_t * obj);
-class MarlinSerial : public HardwareSerial {
-public:
- MarlinSerial(void* peripheral, usart_rx_callback_t rx_callback) :
+struct MarlinSerial : public HardwareSerial {
+ MarlinSerial(void *peripheral, usart_rx_callback_t rx_callback) :
HardwareSerial(peripheral), _rx_callback(rx_callback)
- #if ENABLED(EMERGENCY_PARSER)
- , emergency_state(EmergencyParser::State::EP_RESET)
- #endif
{ }
- #if ENABLED(EMERGENCY_PARSER)
- static inline bool emergency_parser_enabled() { return true; }
- #endif
-
void begin(unsigned long baud, uint8_t config);
inline void begin(unsigned long baud) { begin(baud, SERIAL_8N1); }
- void _rx_complete_irq(serial_t* obj);
+ void _rx_complete_irq(serial_t *obj);
protected:
usart_rx_callback_t _rx_callback;
- #if ENABLED(EMERGENCY_PARSER)
- EmergencyParser::State emergency_state;
- #endif
};
-extern MarlinSerial MSerial1;
-extern MarlinSerial MSerial2;
-extern MarlinSerial MSerial3;
-extern MarlinSerial MSerial4;
-extern MarlinSerial MSerial5;
-extern MarlinSerial MSerial6;
-extern MarlinSerial MSerial7;
-extern MarlinSerial MSerial8;
-extern MarlinSerial MSerial9;
-extern MarlinSerial MSerial10;
-extern MarlinSerial MSerialLP1;
+typedef Serial1Class MSerialT;
+extern MSerialT MSerial1;
+extern MSerialT MSerial2;
+extern MSerialT MSerial3;
+extern MSerialT MSerial4;
+extern MSerialT MSerial5;
+extern MSerialT MSerial6;
+extern MSerialT MSerial7;
+extern MSerialT MSerial8;
+extern MSerialT MSerial9;
+extern MSerialT MSerial10;
+extern MSerialT MSerialLP1;
diff --git a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp
index e00fb9b16f7a..3353f8c36b8c 100644
--- a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp
+++ b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp
@@ -36,9 +36,10 @@
// use USB drivers
- extern "C" { int8_t SD_MSC_Read(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len);
- int8_t SD_MSC_Write(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len);
- extern SD_HandleTypeDef hsd;
+ extern "C" {
+ int8_t SD_MSC_Read(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len);
+ int8_t SD_MSC_Write(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len);
+ extern SD_HandleTypeDef hsd;
}
bool SDIO_Init() {
@@ -75,7 +76,18 @@
#error "ERROR - Only STM32F103xE, STM32F103xG, STM32F4xx or STM32F7xx CPUs supported"
#endif
+ // Fixed
+ #define SDIO_D0_PIN PC8
+ #define SDIO_D1_PIN PC9
+ #define SDIO_D2_PIN PC10
+ #define SDIO_D3_PIN PC11
+ #define SDIO_CK_PIN PC12
+ #define SDIO_CMD_PIN PD2
+
SD_HandleTypeDef hsd; // create SDIO structure
+ // F4 supports one DMA for RX and another for TX, but Marlin will never
+ // do read and write at same time, so we use the same DMA for both.
+ DMA_HandleTypeDef hdma_sdio;
/*
SDIO_INIT_CLK_DIV is 118
@@ -96,12 +108,12 @@
// Target Clock, configurable. Default is 18MHz, from STM32F1
#ifndef SDIO_CLOCK
- #define SDIO_CLOCK 18000000 /* 18 MHz */
+ #define SDIO_CLOCK 18000000 // 18 MHz
#endif
// SDIO retries, configurable. Default is 3, from STM32F1
#ifndef SDIO_READ_RETRIES
- #define SDIO_READ_RETRIES 3
+ #define SDIO_READ_RETRIES 3
#endif
// SDIO Max Clock (naming from STM Manual, don't change)
@@ -120,24 +132,21 @@
}
void go_to_transfer_speed() {
- SD_InitTypeDef Init;
-
/* Default SDIO peripheral configuration for SD card initialization */
- Init.ClockEdge = hsd.Init.ClockEdge;
- Init.ClockBypass = hsd.Init.ClockBypass;
- Init.ClockPowerSave = hsd.Init.ClockPowerSave;
- Init.BusWide = hsd.Init.BusWide;
- Init.HardwareFlowControl = hsd.Init.HardwareFlowControl;
- Init.ClockDiv = clock_to_divider(SDIO_CLOCK);
+ hsd.Init.ClockEdge = hsd.Init.ClockEdge;
+ hsd.Init.ClockBypass = hsd.Init.ClockBypass;
+ hsd.Init.ClockPowerSave = hsd.Init.ClockPowerSave;
+ hsd.Init.BusWide = hsd.Init.BusWide;
+ hsd.Init.HardwareFlowControl = hsd.Init.HardwareFlowControl;
+ hsd.Init.ClockDiv = clock_to_divider(SDIO_CLOCK);
/* Initialize SDIO peripheral interface with default configuration */
- SDIO_Init(hsd.Instance, Init);
+ SDIO_Init(hsd.Instance, hsd.Init);
}
void SD_LowLevel_Init(void) {
uint32_t tempreg;
- __HAL_RCC_SDIO_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE(); //enable GPIO clocks
__HAL_RCC_GPIOD_CLK_ENABLE(); //enable GPIO clocks
@@ -163,12 +172,45 @@
GPIO_InitStruct.Pin = GPIO_PIN_2;
HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
-
- #if DISABLED(STM32F1xx)
- // TODO: use __HAL_RCC_SDIO_RELEASE_RESET() and __HAL_RCC_SDIO_CLK_ENABLE();
- RCC->APB2RSTR &= ~RCC_APB2RSTR_SDIORST_Msk; // take SDIO out of reset
- RCC->APB2ENR |= RCC_APB2RSTR_SDIORST_Msk; // enable SDIO clock
- // Enable the DMA2 Clock
+ // Setup DMA
+ #if defined(STM32F1xx)
+ hdma_sdio.Init.Mode = DMA_NORMAL;
+ hdma_sdio.Instance = DMA2_Channel4;
+ HAL_NVIC_EnableIRQ(DMA2_Channel4_5_IRQn);
+ #elif defined(STM32F4xx)
+ hdma_sdio.Init.Mode = DMA_PFCTRL;
+ hdma_sdio.Instance = DMA2_Stream3;
+ hdma_sdio.Init.Channel = DMA_CHANNEL_4;
+ hdma_sdio.Init.FIFOMode = DMA_FIFOMODE_ENABLE;
+ hdma_sdio.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL;
+ hdma_sdio.Init.MemBurst = DMA_MBURST_INC4;
+ hdma_sdio.Init.PeriphBurst = DMA_PBURST_INC4;
+ HAL_NVIC_EnableIRQ(DMA2_Stream3_IRQn);
+ #endif
+ HAL_NVIC_EnableIRQ(SDIO_IRQn);
+ hdma_sdio.Init.PeriphInc = DMA_PINC_DISABLE;
+ hdma_sdio.Init.MemInc = DMA_MINC_ENABLE;
+ hdma_sdio.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD;
+ hdma_sdio.Init.MemDataAlignment = DMA_MDATAALIGN_WORD;
+ hdma_sdio.Init.Priority = DMA_PRIORITY_LOW;
+ __HAL_LINKDMA(&hsd, hdmarx, hdma_sdio);
+ __HAL_LINKDMA(&hsd, hdmatx, hdma_sdio);
+
+ #if defined(STM32F1xx)
+ __HAL_RCC_SDIO_CLK_ENABLE();
+ __HAL_RCC_DMA2_CLK_ENABLE();
+ #else
+ __HAL_RCC_SDIO_FORCE_RESET();
+ delay(2);
+ __HAL_RCC_SDIO_RELEASE_RESET();
+ delay(2);
+ __HAL_RCC_SDIO_CLK_ENABLE();
+
+ __HAL_RCC_DMA2_FORCE_RESET();
+ delay(2);
+ __HAL_RCC_DMA2_RELEASE_RESET();
+ delay(2);
+ __HAL_RCC_DMA2_CLK_ENABLE();
#endif
//Initialize the SDIO (with initial <400Khz Clock)
@@ -180,6 +222,7 @@
// Power up the SDIO
SDIO_PowerState_ON(SDIO);
+ hsd.Instance = SDIO;
}
void HAL_SD_MspInit(SD_HandleTypeDef *hsd) { // application specific init
@@ -223,107 +266,81 @@
if (!status) break;
if (!--retry_Cnt) return false; // return failing status if retries are exhausted
}
+ go_to_transfer_speed();
}
#endif
return true;
}
- /*
- void init_SDIO_pins(void) {
- GPIO_InitTypeDef GPIO_InitStruct = {0};
-
- // SDIO GPIO Configuration
- // PC8 ------> SDIO_D0
- // PC12 ------> SDIO_CK
- // PD2 ------> SDIO_CMD
-
- GPIO_InitStruct.Pin = GPIO_PIN_8;
- GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
- GPIO_InitStruct.Pull = GPIO_NOPULL;
- GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
- GPIO_InitStruct.Alternate = GPIO_AF12_SDIO;
- HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
-
- 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);}
+ static bool SDIO_ReadWriteBlock_DMA(uint32_t block, const uint8_t *src, uint8_t *dst) {
+ if (HAL_SD_GetCardState(&hsd) != HAL_SD_CARD_TRANSFER) return false;
- bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) {
- hsd.Instance = SDIO;
- uint8_t retryCnt = SDIO_READ_RETRIES;
+ TERN_(USE_WATCHDOG, HAL_watchdog_refresh());
- bool status;
- for (;;) {
- TERN_(USE_WATCHDOG, HAL_watchdog_refresh());
- status = (bool) HAL_SD_ReadBlocks(&hsd, (uint8_t*)dst, block, 1, 1000); // read one 512 byte block with 500mS timeout
- status |= (bool) HAL_SD_GetCardState(&hsd); // make sure all is OK
- if (!status) break; // return passing status
- if (!--retryCnt) break; // return failing status if retries are exhausted
+ HAL_StatusTypeDef ret;
+ if (src) {
+ hdma_sdio.Init.Direction = DMA_MEMORY_TO_PERIPH;
+ HAL_DMA_Init(&hdma_sdio);
+ ret = HAL_SD_WriteBlocks_DMA(&hsd, (uint8_t *)src, block, 1);
+ }
+ else {
+ hdma_sdio.Init.Direction = DMA_PERIPH_TO_MEMORY;
+ HAL_DMA_Init(&hdma_sdio);
+ ret = HAL_SD_ReadBlocks_DMA(&hsd, (uint8_t *)dst, block, 1);
}
- return status;
-
- /*
- 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);
+ if (ret != HAL_OK) {
+ HAL_DMA_Abort_IT(&hdma_sdio);
+ HAL_DMA_DeInit(&hdma_sdio);
return false;
}
- while (!SDIO_GET_FLAG(SDIO_STA_DATAEND | SDIO_STA_TRX_ERROR_FLAGS)) {}
+ millis_t timeout = millis() + 500;
+ // Wait the transfer
+ while (hsd.State != HAL_SD_STATE_READY) {
+ if (ELAPSED(millis(), timeout)) {
+ HAL_DMA_Abort_IT(&hdma_sdio);
+ HAL_DMA_DeInit(&hdma_sdio);
+ return false;
+ }
+ }
- dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
+ while (__HAL_DMA_GET_FLAG(&hdma_sdio, __HAL_DMA_GET_TC_FLAG_INDEX(&hdma_sdio)) != 0
+ || __HAL_DMA_GET_FLAG(&hdma_sdio, __HAL_DMA_GET_TE_FLAG_INDEX(&hdma_sdio)) != 0) { /* nada */ }
- if (SDIO->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;
- }
+ HAL_DMA_Abort_IT(&hdma_sdio);
+ HAL_DMA_DeInit(&hdma_sdio);
- 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);
- */
+ timeout = millis() + 500;
+ while (HAL_SD_GetCardState(&hsd) != HAL_SD_CARD_TRANSFER) if (ELAPSED(millis(), timeout)) return false;
return true;
}
+ bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) {
+ uint8_t retries = SDIO_READ_RETRIES;
+ while (retries--) if (SDIO_ReadWriteBlock_DMA(block, NULL, dst)) return true;
+ return false;
+ }
+
bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) {
- hsd.Instance = SDIO;
- uint8_t retryCnt = SDIO_READ_RETRIES;
- 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;
+ uint8_t retries = SDIO_READ_RETRIES;
+ while (retries--) if (SDIO_ReadWriteBlock_DMA(block, src, NULL)) return true;
+ return false;
}
+ #if defined(STM32F1xx)
+ #define DMA_IRQ_HANDLER DMA2_Channel4_5_IRQHandler
+ #elif defined(STM32F4xx)
+ #define DMA_IRQ_HANDLER DMA2_Stream3_IRQHandler
+ #else
+ #error "Unknown STM32 architecture."
+ #endif
+
+ extern "C" void SDIO_IRQHandler(void) { HAL_SD_IRQHandler(&hsd); }
+ extern "C" void DMA_IRQ_HANDLER(void) { HAL_DMA_IRQHandler(&hdma_sdio); }
+
#endif // !USBD_USE_CDC_COMPOSITE
#endif // SDIO_SUPPORT
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp b/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp
new file mode 100644
index 000000000000..165b3c6bab2e
--- /dev/null
+++ b/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp
@@ -0,0 +1,82 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#ifdef STM32F1
+
+/**
+ * PersistentStore for Arduino-style EEPROM interface
+ * with simple implementations supplied by Marlin.
+ */
+
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(IIC_BL24CXX_EEPROM)
+
+#include "../shared/eeprom_if.h"
+#include "../shared/eeprom_api.h"
+
+//
+// PersistentStore
+//
+
+#ifndef MARLIN_EEPROM_SIZE
+ #error "MARLIN_EEPROM_SIZE is required for IIC_BL24CXX_EEPROM."
+#endif
+
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+
+bool PersistentStore::access_start() { eeprom_init(); return true; }
+bool PersistentStore::access_finish() { return true; }
+
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ uint16_t written = 0;
+ while (size--) {
+ uint8_t v = *value;
+ uint8_t * const p = (uint8_t * const)pos;
+ if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed!
+ eeprom_write_byte(p, v);
+ if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes
+ if (eeprom_read_byte(p) != v) {
+ SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
+ return true;
+ }
+ }
+ crc16(crc, &v, 1);
+ pos++;
+ value++;
+ }
+ return false;
+}
+
+bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
+ do {
+ uint8_t * const p = (uint8_t * const)pos;
+ uint8_t c = eeprom_read_byte(p);
+ if (writing) *value = c;
+ crc16(crc, &c, 1);
+ pos++;
+ value++;
+ } while (--size);
+ return false;
+}
+
+#endif // IIC_BL24CXX_EEPROM
+#endif // STM32F1
diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp
index 8cd62879a5c6..dfeae9e9e5e6 100644
--- a/Marlin/src/HAL/STM32/eeprom_flash.cpp
+++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp
@@ -28,6 +28,10 @@
#include "../shared/eeprom_api.h"
+// Better: "utility/stm32_eeprom.h", but only after updating stm32duino to 2.0.0
+// Use EEPROM.h for compatibility, for now.
+#include
+
/**
* The STM32 HAL supports chips that deal with "pages" and some with "sectors" and some that
* even have multiple "banks" of flash.
@@ -48,7 +52,7 @@
#include "stm32_def.h"
#define DEBUG_OUT ENABLED(EEPROM_CHITCHAT)
- #include "src/core/debug_out.h"
+ #include "../../core/debug_out.h"
#ifndef MARLIN_EEPROM_SIZE
#define MARLIN_EEPROM_SIZE 0x1000 // 4KB
@@ -61,7 +65,9 @@
#define FLASH_UNIT_SIZE 0x20000 // 128kB
#endif
- #define FLASH_ADDRESS_START (FLASH_END - ((FLASH_SECTOR_TOTAL - (FLASH_SECTOR)) * (FLASH_UNIT_SIZE)) + 1)
+ #ifndef FLASH_ADDRESS_START
+ #define FLASH_ADDRESS_START (FLASH_END - ((FLASH_SECTOR_TOTAL - (FLASH_SECTOR)) * (FLASH_UNIT_SIZE)) + 1)
+ #endif
#define FLASH_ADDRESS_END (FLASH_ADDRESS_START + FLASH_UNIT_SIZE - 1)
#define EEPROM_SLOTS ((FLASH_UNIT_SIZE) / (MARLIN_EEPROM_SIZE))
diff --git a/Marlin/src/HAL/STM32/eeprom_if_iic.cpp b/Marlin/src/HAL/STM32/eeprom_if_iic.cpp
new file mode 100644
index 000000000000..5c6cc802a6d0
--- /dev/null
+++ b/Marlin/src/HAL/STM32/eeprom_if_iic.cpp
@@ -0,0 +1,54 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+
+/**
+ * Platform-independent Arduino functions for I2C EEPROM.
+ * Enable USE_SHARED_EEPROM if not supplied by the framework.
+ */
+
+#ifdef STM32F1
+
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(IIC_BL24CXX_EEPROM)
+
+#include "../../libs/BL24CXX.h"
+#include "../shared/eeprom_if.h"
+
+void eeprom_init() { BL24CXX::init(); }
+
+// ------------------------
+// Public functions
+// ------------------------
+
+void eeprom_write_byte(uint8_t *pos, uint8_t value) {
+ const unsigned eeprom_address = (unsigned)pos;
+ return BL24CXX::writeOneByte(eeprom_address, value);
+}
+
+uint8_t eeprom_read_byte(uint8_t *pos) {
+ const unsigned eeprom_address = (unsigned)pos;
+ return BL24CXX::readOneByte(eeprom_address);
+}
+
+#endif // IIC_BL24CXX_EEPROM
+#endif // STM32F1
diff --git a/Marlin/src/HAL/STM32/eeprom_wired.cpp b/Marlin/src/HAL/STM32/eeprom_wired.cpp
index ad54c12c471f..6aa2f1d360f8 100644
--- a/Marlin/src/HAL/STM32/eeprom_wired.cpp
+++ b/Marlin/src/HAL/STM32/eeprom_wired.cpp
@@ -43,25 +43,22 @@ bool PersistentStore::access_start() { eeprom_init(); return true; }
bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ uint16_t written = 0;
while (size--) {
uint8_t v = *value;
-
- // EEPROM has only ~100,000 write cycles,
- // so only write bytes that have changed!
uint8_t * const p = (uint8_t * const)pos;
- if (v != eeprom_read_byte(p)) {
+ if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed!
eeprom_write_byte(p, v);
+ if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes
if (eeprom_read_byte(p) != v) {
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
return true;
}
}
-
crc16(crc, &v, 1);
pos++;
value++;
- };
-
+ }
return false;
}
diff --git a/Marlin/src/HAL/STM32/endstop_interrupts.h b/Marlin/src/HAL/STM32/endstop_interrupts.h
index fdff8cc644cd..90870881fe66 100644
--- a/Marlin/src/HAL/STM32/endstop_interrupts.h
+++ b/Marlin/src/HAL/STM32/endstop_interrupts.h
@@ -46,4 +46,10 @@ void setup_endstop_interrupts() {
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
+ TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
+ TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
+ TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
+ TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
+ TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
+ TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
}
diff --git a/Marlin/src/HAL/STM32/fastio.h b/Marlin/src/HAL/STM32/fastio.h
index ea28b8f3bfaa..17751c44dd8d 100644
--- a/Marlin/src/HAL/STM32/fastio.h
+++ b/Marlin/src/HAL/STM32/fastio.h
@@ -59,7 +59,7 @@ void FastIO_init(); // Must be called before using fast io macros
#endif
#define _READ(IO) bool(READ_BIT(FastIOPortMap[STM_PORT(digitalPinToPinName(IO))]->IDR, _BV32(STM_PIN(digitalPinToPinName(IO)))))
-#define _TOGGLE(IO) (FastIOPortMap[STM_PORT(digitalPinToPinName(IO))]->ODR ^= _BV32(STM_PIN(digitalPinToPinName(IO))))
+#define _TOGGLE(IO) TBI32(FastIOPortMap[STM_PORT(digitalPinToPinName(IO))]->ODR, STM_PIN(digitalPinToPinName(IO)))
#define _GET_MODE(IO)
#define _SET_MODE(IO,M) pinMode(IO, M)
diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_adv.h b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h
index e07c0d9cda5e..451c94f25d1f 100644
--- a/Marlin/src/HAL/STM32/inc/Conditionals_adv.h
+++ b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h
@@ -21,6 +21,15 @@
*/
#pragma once
-#if defined(USBD_USE_CDC_COMPOSITE) && DISABLED(NO_SD_HOST_DRIVE)
+#if BOTH(SDSUPPORT, USBD_USE_CDC_MSC) && DISABLED(NO_SD_HOST_DRIVE)
#define HAS_SD_HOST_DRIVE 1
#endif
+
+// Fix F_CPU not being a compile-time constant in STSTM32 framework
+#ifdef BOARD_F_CPU
+ #undef F_CPU
+ #define F_CPU BOARD_F_CPU
+#endif
+
+// The Sensitive Pins array is not optimizable
+#define RUNTIME_ONLY_ANALOG_TO_DIGITAL
diff --git a/Marlin/src/HAL/STM32/inc/SanityCheck.h b/Marlin/src/HAL/STM32/inc/SanityCheck.h
index 4df75a050558..12ff2abec7ac 100644
--- a/Marlin/src/HAL/STM32/inc/SanityCheck.h
+++ b/Marlin/src/HAL/STM32/inc/SanityCheck.h
@@ -47,11 +47,11 @@
#endif
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
- #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on this platform."
+ #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on STM32."
#elif ENABLED(SERIAL_STATS_DROPPED_RX)
- #error "SERIAL_STATS_DROPPED_RX is not supported on this platform."
+ #error "SERIAL_STATS_DROPPED_RX is not supported on STM32."
#endif
-#if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) && NOT_TARGET(STM32F4xx, STM32F1xx)
- #error "TFT_COLOR_UI, TFT_LVGL_UI and TFT_CLASSIC_UI are currently only supported on STM32F4 and STM32F1 hardware."
+#if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) && NOT_TARGET(STM32H7xx, STM32F4xx, STM32F1xx)
+ #error "TFT_COLOR_UI, TFT_LVGL_UI and TFT_CLASSIC_UI are currently only supported on STM32H7, STM32F4 and STM32F1 hardware."
#endif
diff --git a/Marlin/src/HAL/STM32/msc_sd.cpp b/Marlin/src/HAL/STM32/msc_sd.cpp
new file mode 100644
index 000000000000..64f2533002d8
--- /dev/null
+++ b/Marlin/src/HAL/STM32/msc_sd.cpp
@@ -0,0 +1,124 @@
+/**
+ * Marlin 3D Printer Firmware
+ *
+ * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech]
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#include "../../inc/MarlinConfigPre.h"
+
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && HAS_SD_HOST_DRIVE
+
+#include "msc_sd.h"
+#include "../shared/Marduino.h"
+#include "usbd_core.h"
+#include
+#include
+
+#define BLOCK_SIZE 512
+#define PRODUCT_ID 0x29
+
+#include "../../sd/cardreader.h"
+
+class Sd2CardUSBMscHandler : public USBMscHandler {
+public:
+ DiskIODriver* diskIODriver() {
+ #if ENABLED(MULTI_VOLUME)
+ #if SHARED_VOLUME_IS(SD_ONBOARD)
+ return &card.media_driver_sdcard;
+ #elif SHARED_VOLUME_IS(USB_FLASH_DRIVE)
+ return &card.media_driver_usbFlash;
+ #endif
+ #else
+ return card.diskIODriver();
+ #endif
+ }
+
+ bool GetCapacity(uint32_t *pBlockNum, uint16_t *pBlockSize) {
+ *pBlockNum = diskIODriver()->cardSize();
+ *pBlockSize = BLOCK_SIZE;
+ return true;
+ }
+
+ bool Write(uint8_t *pBuf, uint32_t blkAddr, uint16_t blkLen) {
+ auto sd2card = diskIODriver();
+ // single block
+ if (blkLen == 1) {
+ watchdog_refresh();
+ sd2card->writeBlock(blkAddr, pBuf);
+ return true;
+ }
+
+ // multi block optmization
+ sd2card->writeStart(blkAddr, blkLen);
+ while (blkLen--) {
+ watchdog_refresh();
+ sd2card->writeData(pBuf);
+ pBuf += BLOCK_SIZE;
+ }
+ sd2card->writeStop();
+ return true;
+ }
+
+ bool Read(uint8_t *pBuf, uint32_t blkAddr, uint16_t blkLen) {
+ auto sd2card = diskIODriver();
+ // single block
+ if (blkLen == 1) {
+ watchdog_refresh();
+ sd2card->readBlock(blkAddr, pBuf);
+ return true;
+ }
+
+ // multi block optmization
+ sd2card->readStart(blkAddr);
+ while (blkLen--) {
+ watchdog_refresh();
+ sd2card->readData(pBuf);
+ pBuf += BLOCK_SIZE;
+ }
+ sd2card->readStop();
+ return true;
+ }
+
+ bool IsReady() {
+ return diskIODriver()->isReady();
+ }
+};
+
+Sd2CardUSBMscHandler usbMscHandler;
+
+/* USB Mass storage Standard Inquiry Data */
+uint8_t Marlin_STORAGE_Inquirydata[] = { /* 36 */
+ /* LUN 0 */
+ 0x00,
+ 0x80,
+ 0x02,
+ 0x02,
+ (STANDARD_INQUIRY_DATA_LEN - 5),
+ 0x00,
+ 0x00,
+ 0x00,
+ 'M', 'A', 'R', 'L', 'I', 'N', ' ', ' ', /* Manufacturer : 8 bytes */
+ 'P', 'r', 'o', 'd', 'u', 'c', 't', ' ', /* Product : 16 Bytes */
+ ' ', ' ', ' ', ' ', ' ', ' ', ' ', ' ',
+ '0', '.', '0', '1', /* Version : 4 Bytes */
+};
+
+USBMscHandler *pSingleMscHandler = &usbMscHandler;
+
+void MSC_SD_init() {
+ USBDevice.end();
+ delay(200);
+ USBDevice.registerMscHandlers(1, &pSingleMscHandler, Marlin_STORAGE_Inquirydata);
+ USBDevice.begin();
+}
+
+#endif // __STM32F1__ && HAS_SD_HOST_DRIVE
diff --git a/Marlin/src/HAL/STM32/msc_sd.h b/Marlin/src/HAL/STM32/msc_sd.h
new file mode 100644
index 000000000000..a8e5349f7cd3
--- /dev/null
+++ b/Marlin/src/HAL/STM32/msc_sd.h
@@ -0,0 +1,18 @@
+/**
+ * Marlin 3D Printer Firmware
+ *
+ * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech]
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#pragma once
+
+void MSC_SD_init();
diff --git a/Marlin/src/HAL/STM32/tft/gt911.cpp b/Marlin/src/HAL/STM32/tft/gt911.cpp
new file mode 100644
index 000000000000..f99fa46e1946
--- /dev/null
+++ b/Marlin/src/HAL/STM32/tft/gt911.cpp
@@ -0,0 +1,202 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../../inc/MarlinConfig.h"
+
+#if ENABLED(TFT_TOUCH_DEVICE_GT911)
+
+#include "gt911.h"
+#include "pinconfig.h"
+
+SW_IIC::SW_IIC(uint16_t sda, uint16_t scl) {
+ scl_pin = scl;
+ sda_pin = sda;
+}
+
+// Software I2C hardware io init
+void SW_IIC::init() {
+ OUT_WRITE(scl_pin, HIGH);
+ OUT_WRITE(sda_pin, HIGH);
+}
+
+// Software I2C start signal
+void SW_IIC::start() {
+ write_sda(HIGH); // SDA = 1
+ write_scl(HIGH); // SCL = 1
+ iic_delay(2);
+ write_sda(LOW); // SDA = 0
+ iic_delay(1);
+ write_scl(LOW); // SCL = 0 // keep SCL low, avoid false stop caused by level jump caused by SDA switching IN/OUT
+}
+
+// Software I2C stop signal
+void SW_IIC::stop() {
+ write_scl(LOW); // SCL = 0
+ iic_delay(2);
+ write_sda(LOW); // SDA = 0
+ iic_delay(2);
+ write_scl(HIGH); // SCL = 1
+ iic_delay(2);
+ write_sda(HIGH); // SDA = 1
+}
+
+// Software I2C sends ACK or NACK signal
+void SW_IIC::send_ack(bool ack) {
+ write_sda(ack ? LOW : HIGH); // SDA = !ack
+ iic_delay(2);
+ write_scl(HIGH); // SCL = 1
+ iic_delay(2);
+ write_scl(LOW); // SCL = 0
+}
+
+// Software I2C read ACK or NACK signal
+bool SW_IIC::read_ack() {
+ bool error = 0;
+ set_sda_in();
+
+ iic_delay(2);
+
+ write_scl(HIGH); // SCL = 1
+ error = read_sda();
+
+ iic_delay(2);
+
+ write_scl(LOW); // SCL = 0
+
+ set_sda_out();
+ return error;
+}
+
+void SW_IIC::send_byte(uint8_t txd) {
+ LOOP_L_N(i, 8) {
+ write_sda(txd & 0x80); // write data bit
+ txd <<= 1;
+ iic_delay(1);
+ write_scl(HIGH); // SCL = 1
+ iic_delay(2);
+ write_scl(LOW); // SCL = 0
+ iic_delay(1);
+ }
+
+ read_ack(); // wait ack
+}
+
+uint8_t SW_IIC::read_byte(bool ack) {
+ uint8_t data = 0;
+
+ set_sda_in();
+ LOOP_L_N(i, 8) {
+ write_scl(HIGH); // SCL = 1
+ iic_delay(1);
+ data <<= 1;
+ if (read_sda()) data++;
+ write_scl(LOW); // SCL = 0
+ iic_delay(2);
+ }
+ set_sda_out();
+
+ send_ack(ack);
+
+ return data;
+}
+
+GT911_REG_MAP GT911::reg;
+SW_IIC GT911::sw_iic = SW_IIC(GT911_SW_I2C_SDA_PIN, GT911_SW_I2C_SCL_PIN);
+
+void GT911::write_reg(uint16_t reg, uint8_t reg_len, uint8_t* w_data, uint8_t w_len) {
+ sw_iic.start();
+ sw_iic.send_byte(gt911_slave_address); // Set IIC Slave address
+ LOOP_L_N(i, reg_len) { // Set reg address
+ uint8_t r = (reg >> (8 * (reg_len - 1 - i))) & 0xFF;
+ sw_iic.send_byte(r);
+ }
+
+ LOOP_L_N(i, w_len) { // Write data to reg
+ sw_iic.send_byte(w_data[i]);
+ }
+ sw_iic.stop();
+}
+
+void GT911::read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_len) {
+ sw_iic.start();
+ sw_iic.send_byte(gt911_slave_address); // Set IIC Slave address
+ LOOP_L_N(i, reg_len) { // Set reg address
+ uint8_t r = (reg >> (8 * (reg_len - 1 - i))) & 0xFF;
+ sw_iic.send_byte(r);
+ }
+
+ sw_iic.start();
+ sw_iic.send_byte(gt911_slave_address + 1); // Set read mode
+
+ LOOP_L_N(i, r_len) {
+ r_data[i] = sw_iic.read_byte(1); // Read data from reg
+ }
+ sw_iic.stop();
+}
+
+void GT911::Init() {
+ OUT_WRITE(GT911_RST_PIN, LOW);
+ OUT_WRITE(GT911_INT_PIN, LOW);
+ delay(20);
+ WRITE(GT911_RST_PIN, HIGH);
+ SET_INPUT(GT911_INT_PIN);
+
+ sw_iic.init();
+
+ uint8_t clear_reg = 0x0000;
+ write_reg(0x814E, 2, &clear_reg, 2); // Reset to 0 for start
+}
+
+bool GT911::getFirstTouchPoint(int16_t *x, int16_t *y) {
+ read_reg(0x814E, 2, ®.REG.status, 1);
+
+ if (reg.REG.status & 0x80) {
+ uint8_t clear_reg = 0x00;
+ write_reg(0x814E, 2, &clear_reg, 1); // Reset to 0 for start
+ read_reg(0x8150, 2, reg.map + 2, 8 * (reg.REG.status & 0x0F));
+
+ // First touch point
+ *x = ((reg.REG.point[0].xh & 0x0F) << 8) | reg.REG.point[0].xl;
+ *y = ((reg.REG.point[0].yh & 0x0F) << 8) | reg.REG.point[0].yl;
+ return true;
+ }
+ return false;
+}
+
+bool GT911::getPoint(int16_t *x, int16_t *y) {
+ static bool touched = 0;
+ static int16_t read_x = 0, read_y = 0;
+ static millis_t next_time = 0;
+
+ if (ELAPSED(millis(), next_time)) {
+ touched = getFirstTouchPoint(&read_x, &read_y);
+ next_time = millis() + 20;
+ }
+
+ *x = read_x;
+ *y = read_y;
+ return touched;
+}
+
+#endif // TFT_TOUCH_DEVICE_GT911
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/tft/gt911.h b/Marlin/src/HAL/STM32/tft/gt911.h
new file mode 100644
index 000000000000..752a554d98ed
--- /dev/null
+++ b/Marlin/src/HAL/STM32/tft/gt911.h
@@ -0,0 +1,120 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#pragma once
+
+#include "../../../inc/MarlinConfig.h"
+
+#define GT911_SLAVE_ADDRESS 0xBA
+
+#if !PIN_EXISTS(GT911_RST)
+ #error "GT911_RST_PIN is not defined."
+#elif !PIN_EXISTS(GT911_INT)
+ #error "GT911_INT_PIN is not defined."
+#elif !PIN_EXISTS(GT911_SW_I2C_SCL)
+ #error "GT911_SW_I2C_SCL_PIN is not defined."
+#elif !PIN_EXISTS(GT911_SW_I2C_SDA)
+ #error "GT911_SW_I2C_SDA_PIN is not defined."
+#endif
+
+class SW_IIC {
+ private:
+ uint16_t scl_pin;
+ uint16_t sda_pin;
+ void write_scl(bool level)
+ {
+ WRITE(scl_pin, level);
+ }
+ void write_sda(bool level)
+ {
+ WRITE(sda_pin, level);
+ }
+ bool read_sda()
+ {
+ return READ(sda_pin);
+ }
+ void set_sda_out()
+ {
+ SET_OUTPUT(sda_pin);
+ }
+ void set_sda_in()
+ {
+ SET_INPUT_PULLUP(sda_pin);
+ }
+ static void iic_delay(uint8_t t)
+ {
+ delayMicroseconds(t);
+ }
+
+ public:
+ SW_IIC(uint16_t sda, uint16_t scl);
+ // setSCL/SDA have to be called before begin()
+ void setSCL(uint16_t scl)
+ {
+ scl_pin = scl;
+ };
+ void setSDA(uint16_t sda)
+ {
+ sda_pin = sda;
+ };
+ void init(); // Initialize the IO port of IIC
+ void start(); // Send IIC start signal
+ void stop(); // Send IIC stop signal
+ void send_byte(uint8_t txd); // IIC sends a byte
+ uint8_t read_byte(bool ack); // IIC reads a byte
+ void send_ack(bool ack); // IIC sends ACK or NACK signal
+ bool read_ack();
+};
+
+typedef struct __attribute__((__packed__)) {
+ uint8_t xl;
+ uint8_t xh;
+ uint8_t yl;
+ uint8_t yh;
+ uint8_t sizel;
+ uint8_t sizeh;
+ uint8_t reserved;
+ uint8_t track_id;
+} GT911_POINT;
+
+typedef union __attribute__((__packed__)) {
+ uint8_t map[42];
+ struct {
+ uint8_t status; // 0x814E
+ uint8_t track_id; // 0x814F
+
+ GT911_POINT point[5]; // [0]:0x8150 - 0x8157 / [1]:0x8158 - 0x815F / [2]:0x8160 - 0x8167 / [3]:0x8168 - 0x816F / [4]:0x8170 - 0x8177
+ } REG;
+} GT911_REG_MAP;
+
+class GT911 {
+ private:
+ static const uint8_t gt911_slave_address = GT911_SLAVE_ADDRESS;
+ static GT911_REG_MAP reg;
+ static SW_IIC sw_iic;
+ static void write_reg(uint16_t reg, uint8_t reg_len, uint8_t* w_data, uint8_t w_len);
+ static void read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_len);
+
+ public:
+ static void Init();
+ static bool getFirstTouchPoint(int16_t *x, int16_t *y);
+ static bool getPoint(int16_t *x, int16_t *y);
+};
diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.h b/Marlin/src/HAL/STM32/tft/tft_fsmc.h
index 7c40151e2bdf..2200abaa10e8 100644
--- a/Marlin/src/HAL/STM32/tft/tft_fsmc.h
+++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.h
@@ -84,7 +84,6 @@ class TFT_FSMC {
}
};
-
#ifdef STM32F1xx
#define FSMC_PIN_DATA STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_NONE)
#elif defined(STM32F4xx)
diff --git a/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp
new file mode 100644
index 000000000000..f2509ce5e4db
--- /dev/null
+++ b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp
@@ -0,0 +1,387 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../../inc/MarlinConfig.h"
+
+#if HAS_LTDC_TFT
+
+#include "tft_ltdc.h"
+#include "pinconfig.h"
+
+#define FRAME_BUFFER_ADDRESS 0XC0000000 // SDRAM address
+
+#define SDRAM_TIMEOUT ((uint32_t)0xFFFF)
+#define REFRESH_COUNT ((uint32_t)0x02A5) // SDRAM refresh counter
+
+#define SDRAM_MODEREG_BURST_LENGTH_1 ((uint16_t)0x0000)
+#define SDRAM_MODEREG_BURST_LENGTH_2 ((uint16_t)0x0001)
+#define SDRAM_MODEREG_BURST_LENGTH_4 ((uint16_t)0x0002)
+#define SDRAM_MODEREG_BURST_LENGTH_8 ((uint16_t)0x0004)
+#define SDRAM_MODEREG_BURST_TYPE_SEQUENTIAL ((uint16_t)0x0000)
+#define SDRAM_MODEREG_BURST_TYPE_INTERLEAVED ((uint16_t)0x0008)
+#define SDRAM_MODEREG_CAS_LATENCY_2 ((uint16_t)0x0020)
+#define SDRAM_MODEREG_CAS_LATENCY_3 ((uint16_t)0x0030)
+#define SDRAM_MODEREG_OPERATING_MODE_STANDARD ((uint16_t)0x0000)
+#define SDRAM_MODEREG_WRITEBURST_MODE_PROGRAMMED ((uint16_t)0x0000)
+#define SDRAM_MODEREG_WRITEBURST_MODE_SINGLE ((uint16_t)0x0200)
+
+void SDRAM_Initialization_Sequence(SDRAM_HandleTypeDef *hsdram, FMC_SDRAM_CommandTypeDef *Command) {
+
+ __IO uint32_t tmpmrd =0;
+ /* Step 1: Configure a clock configuration enable command */
+ Command->CommandMode = FMC_SDRAM_CMD_CLK_ENABLE;
+ Command->CommandTarget = FMC_SDRAM_CMD_TARGET_BANK1;
+ Command->AutoRefreshNumber = 1;
+ Command->ModeRegisterDefinition = 0;
+ /* Send the command */
+ HAL_SDRAM_SendCommand(hsdram, Command, SDRAM_TIMEOUT);
+
+ /* Step 2: Insert 100 us minimum delay */
+ /* Inserted delay is equal to 1 ms due to systick time base unit (ms) */
+ HAL_Delay(1);
+
+ /* Step 3: Configure a PALL (precharge all) command */
+ Command->CommandMode = FMC_SDRAM_CMD_PALL;
+ Command->CommandTarget = FMC_SDRAM_CMD_TARGET_BANK1;
+ Command->AutoRefreshNumber = 1;
+ Command->ModeRegisterDefinition = 0;
+ /* Send the command */
+ HAL_SDRAM_SendCommand(hsdram, Command, SDRAM_TIMEOUT);
+
+ /* Step 4 : Configure a Auto-Refresh command */
+ Command->CommandMode = FMC_SDRAM_CMD_AUTOREFRESH_MODE;
+ Command->CommandTarget = FMC_SDRAM_CMD_TARGET_BANK1;
+ Command->AutoRefreshNumber = 8;
+ Command->ModeRegisterDefinition = 0;
+ /* Send the command */
+ HAL_SDRAM_SendCommand(hsdram, Command, SDRAM_TIMEOUT);
+
+ /* Step 5: Program the external memory mode register */
+ tmpmrd = (uint32_t)(SDRAM_MODEREG_BURST_LENGTH_1 |
+ SDRAM_MODEREG_BURST_TYPE_SEQUENTIAL |
+ SDRAM_MODEREG_CAS_LATENCY_2 |
+ SDRAM_MODEREG_OPERATING_MODE_STANDARD |
+ SDRAM_MODEREG_WRITEBURST_MODE_SINGLE);
+
+ Command->CommandMode = FMC_SDRAM_CMD_LOAD_MODE;
+ Command->CommandTarget = FMC_SDRAM_CMD_TARGET_BANK1;
+ Command->AutoRefreshNumber = 1;
+ Command->ModeRegisterDefinition = tmpmrd;
+ /* Send the command */
+ HAL_SDRAM_SendCommand(hsdram, Command, SDRAM_TIMEOUT);
+
+ /* Step 6: Set the refresh rate counter */
+ /* Set the device refresh rate */
+ HAL_SDRAM_ProgramRefreshRate(hsdram, REFRESH_COUNT);
+}
+
+void SDRAM_Config() {
+
+ __HAL_RCC_SYSCFG_CLK_ENABLE();
+ __HAL_RCC_FMC_CLK_ENABLE();
+
+ SDRAM_HandleTypeDef hsdram;
+ FMC_SDRAM_TimingTypeDef SDRAM_Timing;
+ FMC_SDRAM_CommandTypeDef command;
+
+ /* Configure the SDRAM device */
+ hsdram.Instance = FMC_SDRAM_DEVICE;
+ hsdram.Init.SDBank = FMC_SDRAM_BANK1;
+ hsdram.Init.ColumnBitsNumber = FMC_SDRAM_COLUMN_BITS_NUM_9;
+ hsdram.Init.RowBitsNumber = FMC_SDRAM_ROW_BITS_NUM_13;
+ hsdram.Init.MemoryDataWidth = FMC_SDRAM_MEM_BUS_WIDTH_16;
+ hsdram.Init.InternalBankNumber = FMC_SDRAM_INTERN_BANKS_NUM_4;
+ hsdram.Init.CASLatency = FMC_SDRAM_CAS_LATENCY_2;
+ hsdram.Init.WriteProtection = FMC_SDRAM_WRITE_PROTECTION_DISABLE;
+ hsdram.Init.SDClockPeriod = FMC_SDRAM_CLOCK_PERIOD_2;
+ hsdram.Init.ReadBurst = FMC_SDRAM_RBURST_ENABLE;
+ hsdram.Init.ReadPipeDelay = FMC_SDRAM_RPIPE_DELAY_0;
+
+ /* Timing configuration for 100Mhz as SDRAM clock frequency (System clock is up to 200Mhz) */
+ SDRAM_Timing.LoadToActiveDelay = 2;
+ SDRAM_Timing.ExitSelfRefreshDelay = 8;
+ SDRAM_Timing.SelfRefreshTime = 6;
+ SDRAM_Timing.RowCycleDelay = 6;
+ SDRAM_Timing.WriteRecoveryTime = 2;
+ SDRAM_Timing.RPDelay = 2;
+ SDRAM_Timing.RCDDelay = 2;
+
+ /* Initialize the SDRAM controller */
+ if (HAL_SDRAM_Init(&hsdram, &SDRAM_Timing) != HAL_OK)
+ {
+ /* Initialization Error */
+ }
+
+ /* Program the SDRAM external device */
+ SDRAM_Initialization_Sequence(&hsdram, &command);
+}
+
+void LTDC_Config() {
+
+ __HAL_RCC_LTDC_CLK_ENABLE();
+ __HAL_RCC_DMA2D_CLK_ENABLE();
+
+ RCC_PeriphCLKInitTypeDef PeriphClkInitStruct;
+
+ /* The PLL3R is configured to provide the LTDC PCLK clock */
+ /* PLL3_VCO Input = HSE_VALUE / PLL3M = 25Mhz / 5 = 5 Mhz */
+ /* PLL3_VCO Output = PLL3_VCO Input * PLL3N = 5Mhz * 160 = 800 Mhz */
+ /* PLLLCDCLK = PLL3_VCO Output/PLL3R = 800Mhz / 16 = 50Mhz */
+ /* LTDC clock frequency = PLLLCDCLK = 50 Mhz */
+ PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_LTDC;
+ PeriphClkInitStruct.PLL3.PLL3M = 5;
+ PeriphClkInitStruct.PLL3.PLL3N = 160;
+ PeriphClkInitStruct.PLL3.PLL3FRACN = 0;
+ PeriphClkInitStruct.PLL3.PLL3P = 2;
+ PeriphClkInitStruct.PLL3.PLL3Q = 2;
+ PeriphClkInitStruct.PLL3.PLL3R = (800 / LTDC_LCD_CLK);
+ PeriphClkInitStruct.PLL3.PLL3VCOSEL = RCC_PLL3VCOWIDE;
+ PeriphClkInitStruct.PLL3.PLL3RGE = RCC_PLL3VCIRANGE_2;
+ HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct);
+
+ LTDC_HandleTypeDef hltdc_F;
+ LTDC_LayerCfgTypeDef pLayerCfg;
+
+ /* LTDC Initialization -------------------------------------------------------*/
+
+ /* Polarity configuration */
+ /* Initialize the horizontal synchronization polarity as active low */
+ hltdc_F.Init.HSPolarity = LTDC_HSPOLARITY_AL;
+ /* Initialize the vertical synchronization polarity as active low */
+ hltdc_F.Init.VSPolarity = LTDC_VSPOLARITY_AL;
+ /* Initialize the data enable polarity as active low */
+ hltdc_F.Init.DEPolarity = LTDC_DEPOLARITY_AL;
+ /* Initialize the pixel clock polarity as input pixel clock */
+ hltdc_F.Init.PCPolarity = LTDC_PCPOLARITY_IPC;
+
+ /* Timing configuration */
+ hltdc_F.Init.HorizontalSync = (LTDC_LCD_HSYNC - 1);
+ hltdc_F.Init.VerticalSync = (LTDC_LCD_VSYNC - 1);
+ hltdc_F.Init.AccumulatedHBP = (LTDC_LCD_HSYNC + LTDC_LCD_HBP - 1);
+ hltdc_F.Init.AccumulatedVBP = (LTDC_LCD_VSYNC + LTDC_LCD_VBP - 1);
+ hltdc_F.Init.AccumulatedActiveH = (TFT_HEIGHT + LTDC_LCD_VSYNC + LTDC_LCD_VBP - 1);
+ hltdc_F.Init.AccumulatedActiveW = (TFT_WIDTH + LTDC_LCD_HSYNC + LTDC_LCD_HBP - 1);
+ hltdc_F.Init.TotalHeigh = (TFT_HEIGHT + LTDC_LCD_VSYNC + LTDC_LCD_VBP + LTDC_LCD_VFP - 1);
+ hltdc_F.Init.TotalWidth = (TFT_WIDTH + LTDC_LCD_HSYNC + LTDC_LCD_HBP + LTDC_LCD_HFP - 1);
+
+ /* Configure R,G,B component values for LCD background color : all black background */
+ hltdc_F.Init.Backcolor.Blue = 0;
+ hltdc_F.Init.Backcolor.Green = 0;
+ hltdc_F.Init.Backcolor.Red = 0;
+
+ hltdc_F.Instance = LTDC;
+
+ /* Layer0 Configuration ------------------------------------------------------*/
+
+ /* Windowing configuration */
+ pLayerCfg.WindowX0 = 0;
+ pLayerCfg.WindowX1 = TFT_WIDTH;
+ pLayerCfg.WindowY0 = 0;
+ pLayerCfg.WindowY1 = TFT_HEIGHT;
+
+ /* Pixel Format configuration*/
+ pLayerCfg.PixelFormat = LTDC_PIXEL_FORMAT_RGB565;
+
+ /* Start Address configuration : frame buffer is located at SDRAM memory */
+ pLayerCfg.FBStartAdress = (uint32_t)(FRAME_BUFFER_ADDRESS);
+
+ /* Alpha constant (255 == totally opaque) */
+ pLayerCfg.Alpha = 255;
+
+ /* Default Color configuration (configure A,R,G,B component values) : no background color */
+ pLayerCfg.Alpha0 = 0; /* fully transparent */
+ pLayerCfg.Backcolor.Blue = 0;
+ pLayerCfg.Backcolor.Green = 0;
+ pLayerCfg.Backcolor.Red = 0;
+
+ /* Configure blending factors */
+ pLayerCfg.BlendingFactor1 = LTDC_BLENDING_FACTOR1_CA;
+ pLayerCfg.BlendingFactor2 = LTDC_BLENDING_FACTOR2_CA;
+
+ /* Configure the number of lines and number of pixels per line */
+ pLayerCfg.ImageWidth = TFT_WIDTH;
+ pLayerCfg.ImageHeight = TFT_HEIGHT;
+
+ /* Configure the LTDC */
+ if (HAL_LTDC_Init(&hltdc_F) != HAL_OK)
+ {
+ /* Initialization Error */
+ }
+
+ /* Configure the Layer*/
+ if (HAL_LTDC_ConfigLayer(&hltdc_F, &pLayerCfg, 0) != HAL_OK)
+ {
+ /* Initialization Error */
+ }
+}
+
+uint16_t TFT_LTDC::x_min = 0;
+uint16_t TFT_LTDC::x_max = 0;
+uint16_t TFT_LTDC::y_min = 0;
+uint16_t TFT_LTDC::y_max = 0;
+uint16_t TFT_LTDC::x_cur = 0;
+uint16_t TFT_LTDC::y_cur = 0;
+uint8_t TFT_LTDC::reg = 0;
+volatile uint16_t* TFT_LTDC::framebuffer = (volatile uint16_t* )FRAME_BUFFER_ADDRESS;
+
+void TFT_LTDC::Init() {
+
+ // SDRAM pins init
+ for (uint16_t i = 0; PinMap_SDRAM[i].pin != NC; i++)
+ pinmap_pinout(PinMap_SDRAM[i].pin, PinMap_SDRAM);
+
+ // SDRAM peripheral config
+ SDRAM_Config();
+
+ // LTDC pins init
+ for (uint16_t i = 0; PinMap_LTDC[i].pin != NC; i++)
+ pinmap_pinout(PinMap_LTDC[i].pin, PinMap_LTDC);
+
+ // LTDC peripheral config
+ LTDC_Config();
+}
+
+uint32_t TFT_LTDC::GetID() {
+ return 0xABAB;
+}
+
+uint32_t TFT_LTDC::ReadID(tft_data_t Reg) {
+ return 0xABAB;
+}
+
+bool TFT_LTDC::isBusy() {
+ return false;
+}
+
+uint16_t TFT_LTDC::ReadPoint(uint16_t x, uint16_t y) {
+ return framebuffer[(TFT_WIDTH * y) + x];
+}
+
+void TFT_LTDC::DrawPoint(uint16_t x, uint16_t y, uint16_t color) {
+ framebuffer[(TFT_WIDTH * y) + x] = color;
+}
+
+void TFT_LTDC::DrawRect(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t color) {
+
+ if (sx == ex || sy == ey) return;
+
+ uint16_t offline = TFT_WIDTH - (ex - sx);
+ uint32_t addr = (uint32_t)&framebuffer[(TFT_WIDTH * sy) + sx];
+
+ CBI(DMA2D->CR, 0);
+ DMA2D->CR = 3 << 16;
+ DMA2D->OPFCCR = 0X02;
+ DMA2D->OOR = offline;
+ DMA2D->OMAR = addr;
+ DMA2D->NLR = (ey - sy) | ((ex - sx) << 16);
+ DMA2D->OCOLR = color;
+ SBI(DMA2D->CR, 0);
+
+ uint32_t timeout = 0;
+ while (!TEST(DMA2D->ISR, 1)) {
+ timeout++;
+ if (timeout > 0x1FFFFF) break;
+ }
+ SBI(DMA2D->IFCR, 1);
+}
+
+void TFT_LTDC::DrawImage(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t *colors) {
+
+ if (sx == ex || sy == ey) return;
+
+ uint16_t offline = TFT_WIDTH - (ex - sx);
+ uint32_t addr = (uint32_t)&framebuffer[(TFT_WIDTH * sy) + sx];
+
+ CBI(DMA2D->CR, 0);
+ DMA2D->CR = 0 << 16;
+ DMA2D->FGPFCCR = 0X02;
+ DMA2D->FGOR = 0;
+ DMA2D->OOR = offline;
+ DMA2D->FGMAR = (uint32_t)colors;
+ DMA2D->OMAR = addr;
+ DMA2D->NLR = (ey - sy) | ((ex - sx) << 16);
+ SBI(DMA2D->CR, 0);
+
+ uint32_t timeout = 0;
+ while (!TEST(DMA2D->ISR, 1)) {
+ timeout++;
+ if (timeout > 0x1FFFFF) break;
+ }
+ SBI(DMA2D->IFCR, 1);
+}
+
+void TFT_LTDC::WriteData(uint16_t data) {
+ switch (reg) {
+ case 0x01: x_cur = x_min = data; return;
+ case 0x02: x_max = data; return;
+ case 0x03: y_cur = y_min = data; return;
+ case 0x04: y_max = data; return;
+ }
+ Transmit(data);
+}
+
+void TFT_LTDC::Transmit(tft_data_t Data) {
+ DrawPoint(x_cur, y_cur, Data);
+ x_cur++;
+ if (x_cur > x_max) {
+ x_cur = x_min;
+ y_cur++;
+ if (y_cur > y_max) y_cur = y_min;
+ }
+}
+
+void TFT_LTDC::WriteReg(uint16_t Reg) {
+ reg = Reg;
+}
+
+void TFT_LTDC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
+
+ while (x_cur != x_min && Count) {
+ Transmit(*Data);
+ if (MemoryIncrease == DMA_PINC_ENABLE) Data++;
+ Count--;
+ }
+
+ uint16_t width = x_max - x_min + 1;
+ uint16_t height = Count / width;
+ uint16_t x_end_cnt = Count - (width * height);
+
+ if (height) {
+ if (MemoryIncrease == DMA_PINC_ENABLE) {
+ DrawImage(x_min, y_cur, x_min + width, y_cur + height, Data);
+ Data += width * height;
+ } else {
+ DrawRect(x_min, y_cur, x_min + width, y_cur + height, *Data);
+ }
+ y_cur += height;
+ }
+
+ while (x_end_cnt) {
+ Transmit(*Data);
+ if (MemoryIncrease == DMA_PINC_ENABLE) Data++;
+ x_end_cnt--;
+ }
+}
+
+#endif // HAS_LTDC_TFT
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/tft/tft_ltdc.h b/Marlin/src/HAL/STM32/tft/tft_ltdc.h
new file mode 100644
index 000000000000..7b63d6929b31
--- /dev/null
+++ b/Marlin/src/HAL/STM32/tft/tft_ltdc.h
@@ -0,0 +1,155 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#pragma once
+
+#include "../../../inc/MarlinConfig.h"
+
+#ifdef STM32H7xx
+ #include "stm32h7xx_hal.h"
+#else
+ #error "LTDC TFT is currently only supported on STM32H7 hardware."
+#endif
+
+#define DATASIZE_8BIT SPI_DATASIZE_8BIT
+#define DATASIZE_16BIT SPI_DATASIZE_16BIT
+#define TFT_IO_DRIVER TFT_LTDC
+
+#define TFT_DATASIZE DATASIZE_16BIT
+typedef uint16_t tft_data_t;
+
+class TFT_LTDC {
+ private:
+ static volatile uint16_t *framebuffer;
+ static uint16_t x_min, x_max, y_min, y_max, x_cur, y_cur;
+ static uint8_t reg;
+
+ static uint32_t ReadID(tft_data_t Reg);
+
+ static uint16_t ReadPoint(uint16_t x, uint16_t y);
+ static void DrawPoint(uint16_t x, uint16_t y, uint16_t color);
+ static void DrawRect(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t color);
+ static void DrawImage(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t *colors);
+ static void Transmit(tft_data_t Data);
+ static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count);
+
+ public:
+ static void Init();
+ static uint32_t GetID();
+ static bool isBusy();
+ static void Abort() { /*__HAL_DMA_DISABLE(&DMAtx);*/ }
+
+ static void DataTransferBegin(uint16_t DataWidth = TFT_DATASIZE) {}
+ static void DataTransferEnd() {};
+
+ static void WriteData(uint16_t Data);
+ static void WriteReg(uint16_t Reg);
+
+ static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_PINC_ENABLE, Data, Count); }
+ static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_PINC_DISABLE, &Data, Count); }
+ static void WriteMultiple(uint16_t Color, uint32_t Count) {
+ static uint16_t Data; Data = Color;
+ while (Count > 0) {
+ TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count);
+ Count = Count > 0xFFFF ? Count - 0xFFFF : 0;
+ }
+ }
+};
+
+const PinMap PinMap_LTDC[] = {
+ {PF_10, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_DE
+ {PG_7, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_CLK
+ {PI_9, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_VSYNC
+ {PI_10, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_HSYNC
+
+ {PG_6, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_R7
+ {PH_12, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_R6
+ {PH_11, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_R5
+ {PH_10, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_R4
+ {PH_9, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_R3
+
+ {PI_2, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_G7
+ {PI_1, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_G6
+ {PI_0, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_G5
+ {PH_15, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_G4
+ {PH_14, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_G3
+ {PH_13, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_G2
+
+ {PI_7, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_B7
+ {PI_6, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_B6
+ {PI_5, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_B5
+ {PI_4, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_B4
+ {PG_11, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_B3
+ {NC, NP, 0}
+};
+
+const PinMap PinMap_SDRAM[] = {
+ {PC_0, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDNWE
+ {PC_2, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDNE0
+ {PC_3, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDCKE0
+ {PE_0, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_NBL0
+ {PE_1, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_NBL1
+ {PF_11, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDNRAS
+ {PG_8, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDCLK
+ {PG_15, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDNCAS
+ {PG_4, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_BA0
+ {PG_5, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_BA1
+ {PD_14, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D0
+ {PD_15, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D1
+ {PD_0, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D2
+ {PD_1, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D3
+ {PE_7, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D4
+ {PE_8, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D5
+ {PE_9, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D6
+ {PE_10, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D7
+ {PE_11, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D8
+ {PE_12, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D9
+ {PE_13, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D10
+ {PE_14, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D11
+ {PE_15, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D12
+ {PD_8, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D13
+ {PD_9, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D14
+ {PD_10, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D15
+ {PF_0, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A0
+ {PF_1, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A1
+ {PF_2, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A2
+ {PF_3, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A3
+ {PF_4, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A4
+ {PF_5, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A5
+ {PF_12, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A6
+ {PF_13, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A7
+ {PF_14, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A8
+ {PF_15, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A9
+ {PG_0, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A10
+ {PG_1, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A11
+ {PG_2, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A12
+ {NC, NP, 0}
+};
+
+const PinMap PinMap_QUADSPI[] = {
+ {PB_2, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_CLK
+ {PB_10, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_BK1_NCS
+ {PF_6, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_BK1_IO3
+ {PF_7, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_BK1_IO2
+ {PF_8, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QUADSPI)}, // QUADSPI_BK1_IO0
+ {PF_9, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QUADSPI)}, // QUADSPI_BK1_IO1
+ {NC, NP, 0}
+};
diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.cpp b/Marlin/src/HAL/STM32/tft/tft_spi.cpp
index 3cb797d5f2a9..6bfce81f1a53 100644
--- a/Marlin/src/HAL/STM32/tft/tft_spi.cpp
+++ b/Marlin/src/HAL/STM32/tft/tft_spi.cpp
@@ -125,12 +125,20 @@ void TFT_SPI::DataTransferBegin(uint16_t DataSize) {
WRITE(TFT_CS_PIN, LOW);
}
+#ifdef TFT_DEFAULT_DRIVER
+ #include "../../../lcd/tft_io/tft_ids.h"
+#endif
+
uint32_t TFT_SPI::GetID() {
uint32_t id;
id = ReadID(LCD_READ_ID);
-
- if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF)
+ if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) {
id = ReadID(LCD_READ_ID4);
+ #ifdef TFT_DEFAULT_DRIVER
+ if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF)
+ id = TFT_DEFAULT_DRIVER;
+ #endif
+ }
return id;
}
@@ -207,12 +215,12 @@ void TFT_SPI::Transmit(uint16_t Data) {
while ((SPIx.Instance->SR & SPI_FLAG_BSY) == SPI_FLAG_BSY) {}
if (TFT_MISO_PIN != TFT_MOSI_PIN)
- __HAL_SPI_CLEAR_OVRFLAG(&SPIx); /* Clear overrun flag in 2 Lines communication mode because received is not read */
+ __HAL_SPI_CLEAR_OVRFLAG(&SPIx); // Clear overrun flag in 2 Lines communication mode because received is not read
}
void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
// Wait last dma finish, to start another
- while(isBusy()) { }
+ while (isBusy()) { /* nada */ }
DMAtx.Init.MemInc = MemoryIncrease;
HAL_DMA_Init(&DMAtx);
@@ -225,7 +233,7 @@ void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Coun
HAL_DMA_Start(&DMAtx, (uint32_t)Data, (uint32_t)&(SPIx.Instance->DR), Count);
__HAL_SPI_ENABLE(&SPIx);
- SET_BIT(SPIx.Instance->CR2, SPI_CR2_TXDMAEN); /* Enable Tx DMA Request */
+ SET_BIT(SPIx.Instance->CR2, SPI_CR2_TXDMAEN); // Enable Tx DMA Request
HAL_DMA_PollForTransfer(&DMAtx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY);
Abort();
diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.cpp b/Marlin/src/HAL/STM32/tft/xpt2046.cpp
index 04294e669c55..dffeb6aaf72f 100644
--- a/Marlin/src/HAL/STM32/tft/xpt2046.cpp
+++ b/Marlin/src/HAL/STM32/tft/xpt2046.cpp
@@ -23,7 +23,7 @@
#include "../../../inc/MarlinConfig.h"
-#if HAS_TFT_XPT2046 || HAS_TOUCH_BUTTONS
+#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS
#include "xpt2046.h"
#include "pinconfig.h"
diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.h b/Marlin/src/HAL/STM32/tft/xpt2046.h
index 5b8acf4b87af..2cff3e29d05b 100644
--- a/Marlin/src/HAL/STM32/tft/xpt2046.h
+++ b/Marlin/src/HAL/STM32/tft/xpt2046.h
@@ -56,7 +56,7 @@ enum XPTCoordinate : uint8_t {
XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE,
};
-#if !defined(XPT2046_Z1_THRESHOLD)
+#ifndef XPT2046_Z1_THRESHOLD
#define XPT2046_Z1_THRESHOLD 10
#endif
diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp
index e8e18a47d48b..03353c2ca30e 100644
--- a/Marlin/src/HAL/STM32/timers.cpp
+++ b/Marlin/src/HAL/STM32/timers.cpp
@@ -74,7 +74,7 @@
#elif defined(STM32F401xC) || defined(STM32F401xE)
#define MCU_STEP_TIMER 9
#define MCU_TEMP_TIMER 10
-#elif defined(STM32F4xx) || defined(STM32F7xx)
+#elif defined(STM32F4xx) || defined(STM32F7xx) || defined(STM32H7xx)
#define MCU_STEP_TIMER 6 // STM32F401 has no TIM6, TIM7, or TIM8
#define MCU_TEMP_TIMER 14 // TIM7 is consumed by Software Serial if used.
#endif
diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h
index 464982430358..7a35e432102d 100644
--- a/Marlin/src/HAL/STM32/timers.h
+++ b/Marlin/src/HAL/STM32/timers.h
@@ -21,15 +21,12 @@
*/
#pragma once
-#include
#include "../../inc/MarlinConfig.h"
// ------------------------
// Defines
// ------------------------
-#define FORCE_INLINE __attribute__((always_inline)) inline
-
// STM32 timers may be 16 or 32 bit. Limiting HAL_TIMER_TYPE_MAX to 16 bits
// avoids issues with STM32F0 MCUs, which seem to pause timers if UINT32_MAX
// is written to the register. STM32F4 timers do not manifest this issue,
diff --git a/Marlin/src/HAL/STM32/usb_host.cpp b/Marlin/src/HAL/STM32/usb_host.cpp
index ed743361e681..8fa49ccbcc16 100644
--- a/Marlin/src/HAL/STM32/usb_host.cpp
+++ b/Marlin/src/HAL/STM32/usb_host.cpp
@@ -110,7 +110,7 @@ uint8_t BulkStorage::Read(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t bl
}
uint8_t BulkStorage::Write(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t blocks, const uint8_t * buf) {
- return USBH_MSC_Write(&hUsbHost, lun, addr, const_cast (buf), blocks) != USBH_OK;
+ return USBH_MSC_Write(&hUsbHost, lun, addr, const_cast(buf), blocks) != USBH_OK;
}
#endif // USE_OTG_USB_HOST && USBHOST
diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp
index dfa99d83f4cf..dcfdc88555bb 100644
--- a/Marlin/src/HAL/STM32F1/HAL.cpp
+++ b/Marlin/src/HAL/STM32F1/HAL.cpp
@@ -84,6 +84,32 @@
#if defined(SERIAL_USB) && !HAS_SD_HOST_DRIVE
USBSerial SerialUSB;
+ DefaultSerial1 MSerial0(true, SerialUSB);
+
+ #if ENABLED(EMERGENCY_PARSER)
+ #include "../libmaple/usb/stm32f1/usb_reg_map.h"
+ #include "libmaple/usb_cdcacm.h"
+ // The original callback is not called (no way to retrieve address).
+ // That callback detects a special STM32 reset sequence: this functionality is not essential
+ // as M997 achieves the same.
+ void my_rx_callback(unsigned int, void*) {
+ // max length of 16 is enough to contain all emergency commands
+ uint8 buf[16];
+
+ //rx is usbSerialPart.endpoints[2]
+ uint16 len = usb_get_ep_rx_count(USB_CDCACM_RX_ENDP);
+ uint32 total = usb_cdcacm_data_available();
+
+ if (len == 0 || total == 0 || !WITHIN(total, len, COUNT(buf)))
+ return;
+
+ // cannot get character by character due to bug in composite_cdcacm_peek_ex
+ len = usb_cdcacm_peek(buf, total);
+
+ for (uint32 i = 0; i < len; i++)
+ emergency_parser.update(MSerial0.emergency_state, buf[i + total - len]);
+ }
+ #endif
#endif
uint16_t HAL_adc_result;
@@ -106,6 +132,9 @@ const uint8_t adc_pins[] = {
#if HAS_TEMP_CHAMBER
TEMP_CHAMBER_PIN,
#endif
+ #if HAS_TEMP_COOLER
+ TEMP_COOLER_PIN,
+ #endif
#if HAS_TEMP_ADC_1
TEMP_1_PIN,
#endif
@@ -163,6 +192,9 @@ enum TempPinIndex : char {
#if HAS_TEMP_CHAMBER
TEMP_CHAMBER,
#endif
+ #if HAS_TEMP_COOLER
+ TEMP_COOLER_PIN,
+ #endif
#if HAS_TEMP_ADC_1
TEMP_1,
#endif
@@ -246,6 +278,8 @@ static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) {
} }
#endif
+TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
+
void HAL_init() {
NVIC_SetPriorityGrouping(0x3);
#if PIN_EXISTS(LED)
@@ -253,12 +287,15 @@ void HAL_init() {
#endif
#if HAS_SD_HOST_DRIVE
MSC_SD_init();
+ #elif BOTH(SERIAL_USB, EMERGENCY_PARSER)
+ usb_cdcacm_set_hooks(USB_CDCACM_HOOK_RX, my_rx_callback);
#endif
#if PIN_EXISTS(USB_CONNECT)
OUT_WRITE(USB_CONNECT_PIN, !USB_CONNECT_INVERTING); // USB clear connection
delay(1000); // Give OS time to notice
- OUT_WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING);
+ WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING);
#endif
+ TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the minimal serial handler
}
// HAL idle task
@@ -354,6 +391,9 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) {
#if HAS_TEMP_CHAMBER
case TEMP_CHAMBER_PIN: pin_index = TEMP_CHAMBER; break;
#endif
+ #if HAS_TEMP_COOLER
+ case TEMP_COOLER_PIN: pin_index = TEMP_COOLER; break;
+ #endif
#if HAS_TEMP_ADC_1
case TEMP_1_PIN: pin_index = TEMP_1; break;
#endif
@@ -413,6 +453,8 @@ void analogWrite(pin_t pin, int pwm_val8) {
analogWrite(uint8_t(pin), pwm_val8);
}
-void flashFirmware(const int16_t) { nvic_sys_reset(); }
+void HAL_reboot() { nvic_sys_reset(); }
+
+void flashFirmware(const int16_t) { HAL_reboot(); }
#endif // __STM32F1__
diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h
index 7163db43a2fd..b3d8dc9d0b3e 100644
--- a/Marlin/src/HAL/STM32F1/HAL.h
+++ b/Marlin/src/HAL/STM32F1/HAL.h
@@ -36,7 +36,6 @@
#include "fastio.h"
#include "watchdog.h"
-
#include
#include
@@ -53,7 +52,7 @@
// ------------------------
#ifndef STM32_FLASH_SIZE
- #if EITHER(MCU_STM32F103RE, MCU_STM32F103VE)
+ #if ANY(MCU_STM32F103RE, MCU_STM32F103VE, MCU_STM32F103ZE)
#define STM32_FLASH_SIZE 512
#else
#define STM32_FLASH_SIZE 256
@@ -61,10 +60,12 @@
#endif
#ifdef SERIAL_USB
- #if !HAS_SD_HOST_DRIVE
- #define UsbSerial Serial
- #else
+ typedef ForwardSerial1Class< USBSerial > DefaultSerial1;
+ extern DefaultSerial1 MSerial0;
+ #if HAS_SD_HOST_DRIVE
#define UsbSerial MarlinCompositeSerial
+ #else
+ #define UsbSerial MSerial0
#endif
#endif
@@ -78,24 +79,44 @@
#endif
#if SERIAL_PORT == -1
- #define MYSERIAL0 UsbSerial
+ #define MYSERIAL1 UsbSerial
#elif WITHIN(SERIAL_PORT, 1, NUM_UARTS)
- #define MYSERIAL0 MSERIAL(SERIAL_PORT)
-#elif NUM_UARTS == 5
- #error "SERIAL_PORT must be -1 or from 1 to 5. Please update your configuration."
+ #define MYSERIAL1 MSERIAL(SERIAL_PORT)
#else
- #error "SERIAL_PORT must be -1 or from 1 to 3. Please update your configuration."
+ #define MYSERIAL1 MSERIAL(1) // dummy port
+ static_assert(false, "SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.")
#endif
#ifdef SERIAL_PORT_2
#if SERIAL_PORT_2 == -1
- #define MYSERIAL1 UsbSerial
+ #define MYSERIAL2 UsbSerial
#elif WITHIN(SERIAL_PORT_2, 1, NUM_UARTS)
- #define MYSERIAL1 MSERIAL(SERIAL_PORT_2)
- #elif NUM_UARTS == 5
- #error "SERIAL_PORT_2 must be -1 or from 1 to 5. Please update your configuration."
+ #define MYSERIAL2 MSERIAL(SERIAL_PORT_2)
+ #else
+ #define MYSERIAL2 MSERIAL(1) // dummy port
+ static_assert(false, "SERIAL_PORT_2 must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.")
+ #endif
+#endif
+
+#ifdef SERIAL_PORT_3
+ #if SERIAL_PORT_3 == -1
+ #define MYSERIAL3 UsbSerial
+ #elif WITHIN(SERIAL_PORT_3, 1, NUM_UARTS)
+ #define MYSERIAL3 MSERIAL(SERIAL_PORT_3)
+ #else
+ #define MYSERIAL3 MSERIAL(1) // dummy port
+ static_assert(false, "SERIAL_PORT_3 must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.")
+ #endif
+#endif
+
+#ifdef MMU2_SERIAL_PORT
+ #if MMU2_SERIAL_PORT == -1
+ #define MMU2_SERIAL UsbSerial
+ #elif WITHIN(MMU2_SERIAL_PORT, 1, NUM_UARTS)
+ #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT)
#else
- #error "SERIAL_PORT_2 must be -1 or from 1 to 3. Please update your configuration."
+ #define MMU2_SERIAL MSERIAL(1) // dummy port
+ static_assert(false, "MMU2_SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.")
#endif
#endif
@@ -104,13 +125,13 @@
#define LCD_SERIAL UsbSerial
#elif WITHIN(LCD_SERIAL_PORT, 1, NUM_UARTS)
#define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT)
- #elif NUM_UARTS == 5
- #error "LCD_SERIAL_PORT must be -1 or from 1 to 5. Please update your configuration."
#else
- #error "LCD_SERIAL_PORT must be -1 or from 1 to 3. Please update your configuration."
+ #define LCD_SERIAL MSERIAL(1) // dummy port
+ static_assert(false, "LCD_SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.")
+ #endif
+ #if HAS_DGUS_LCD
+ #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite()
#endif
-
- #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite()
#endif
// Set interrupt grouping for this MCU
@@ -139,14 +160,6 @@ void HAL_idletask();
// On AVR this is in math.h?
#define square(x) ((x)*(x))
-#ifndef strncpy_P
- #define strncpy_P(dest, src, num) strncpy((dest), (src), (num))
-#endif
-
-// Fix bug in pgm_read_ptr
-#undef pgm_read_ptr
-#define pgm_read_ptr(addr) (*(addr))
-
#define RST_POWER_ON 1
#define RST_EXTERNAL 2
#define RST_BROWN_OUT 4
@@ -187,7 +200,7 @@ void HAL_clear_reset_source();
// Reset reason
uint8_t HAL_get_reset_source();
-inline void HAL_reboot() {} // reboot the board or restart the bootloader
+void HAL_reboot();
void _delay_ms(const int delay);
diff --git a/Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp b/Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp
new file mode 100644
index 000000000000..0fc3d014d484
--- /dev/null
+++ b/Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp
@@ -0,0 +1,118 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ * Copyright (c) 2017 Victor Perez
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#ifdef __STM32F1__
+
+#include "../../inc/MarlinConfigPre.h"
+
+#if ENABLED(POSTMORTEM_DEBUGGING)
+
+#include "../shared/HAL_MinSerial.h"
+#include "watchdog.h"
+
+#include
+#include
+#include
+
+/* Instruction Synchronization Barrier */
+#define isb() __asm__ __volatile__ ("isb" : : : "memory")
+
+/* Data Synchronization Barrier */
+#define dsb() __asm__ __volatile__ ("dsb" : : : "memory")
+
+static void TXBegin() {
+ #if !WITHIN(SERIAL_PORT, 1, 6)
+ #warning "Using POSTMORTEM_DEBUGGING requires a physical U(S)ART hardware in case of severe error."
+ #warning "Disabling the severe error reporting feature currently because the used serial port is not a HW port."
+ #else
+ // We use MYSERIAL1 here, so we need to figure out how to get the linked register
+ struct usart_dev* dev = MYSERIAL1.c_dev();
+
+ // Or use this if removing libmaple
+ // int irq = dev->irq_num;
+ // int nvicUART[] = { NVIC_USART1 /* = 37 */, NVIC_USART2 /* = 38 */, NVIC_USART3 /* = 39 */, NVIC_UART4 /* = 52 */, NVIC_UART5 /* = 53 */ };
+ // Disabling irq means setting the bit in the NVIC ICER register located at
+ // Disable UART interrupt in NVIC
+ nvic_irq_disable(dev->irq_num);
+
+ // Use this if removing libmaple
+ //SBI(NVIC_BASE->ICER[1], irq - 32);
+
+ // We NEED memory barriers to ensure Interrupts are actually disabled!
+ // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
+ dsb();
+ isb();
+
+ rcc_clk_disable(dev->clk_id);
+ rcc_clk_enable(dev->clk_id);
+
+ usart_reg_map *regs = dev->regs;
+ regs->CR1 = 0; // Reset the USART
+ regs->CR2 = 0; // 1 stop bit
+
+ // If we don't touch the BRR (baudrate register), we don't need to recompute. Else we would need to call
+ usart_set_baud_rate(dev, 0, BAUDRATE);
+
+ regs->CR1 = (USART_CR1_TE | USART_CR1_UE); // 8 bits, no parity, 1 stop bit
+ #endif
+}
+
+// A SW memory barrier, to ensure GCC does not overoptimize loops
+#define sw_barrier() __asm__ volatile("": : :"memory");
+static void TX(char c) {
+ #if WITHIN(SERIAL_PORT, 1, 6)
+ struct usart_dev* dev = MYSERIAL1.c_dev();
+ while (!(dev->regs->SR & USART_SR_TXE)) {
+ TERN_(USE_WATCHDOG, HAL_watchdog_refresh());
+ sw_barrier();
+ }
+ dev->regs->DR = c;
+ #endif
+}
+
+void install_min_serial() {
+ HAL_min_serial_init = &TXBegin;
+ HAL_min_serial_out = &TX;
+}
+
+#if DISABLED(DYNAMIC_VECTORTABLE) && DISABLED(STM32F0xx) // Cortex M0 can't branch to a symbol that's too far, so we have a specific hack for them
+extern "C" {
+ __attribute__((naked)) void JumpHandler_ASM() {
+ __asm__ __volatile__ (
+ "b CommonHandler_ASM\n"
+ );
+ }
+ void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __exc_hardfault();
+ void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __exc_busfault();
+ void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __exc_usagefault();
+ void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __exc_memmanage();
+ void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __exc_nmi();
+ void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __stm32reservedexception7();
+ void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __stm32reservedexception8();
+ void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __stm32reservedexception9();
+ void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __stm32reservedexception10();
+ void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __stm32reservedexception13();
+}
+#endif
+
+#endif // POSTMORTEM_DEBUGGING
+#endif // __STM32F1__
diff --git a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp
index 7e876f765fb2..abb348d743c5 100644
--- a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp
+++ b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp
@@ -123,7 +123,7 @@ uint8_t spiRec() {
*
* @details Uses DMA
*/
-void spiRead(uint8_t* buf, uint16_t nbyte) {
+void spiRead(uint8_t *buf, uint16_t nbyte) {
SPI.dmaTransfer(0, const_cast(buf), nbyte);
}
@@ -146,7 +146,7 @@ void spiSend(uint8_t b) {
*
* @details Use DMA
*/
-void spiSendBlock(uint8_t token, const uint8_t* buf) {
+void spiSendBlock(uint8_t token, const uint8_t *buf) {
SPI.send(token);
SPI.dmaSend(const_cast(buf), 512);
}
@@ -160,7 +160,7 @@ uint8_t spiRec(uint32_t chan) { return SPI.transfer(0xFF); }
void spiSend(uint32_t chan, byte b) { SPI.send(b); }
// Write buffer to specified SPI channel
-void spiSend(uint32_t chan, const uint8_t* buf, size_t n) {
+void spiSend(uint32_t chan, const uint8_t *buf, size_t n) {
for (size_t p = 0; p < n; p++) spiSend(chan, buf[p]);
}
diff --git a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp
index 7c9625d64cd2..6dabcde51ead 100644
--- a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp
+++ b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp
@@ -28,7 +28,7 @@
// Copied from ~/.platformio/packages/framework-arduinoststm32-maple/STM32F1/system/libmaple/usart_private.h
// Changed to handle Emergency Parser
-static inline __always_inline void my_usart_irq(ring_buffer *rb, ring_buffer *wb, usart_reg_map *regs, MarlinSerial &serial) {
+static inline __always_inline void my_usart_irq(ring_buffer *rb, ring_buffer *wb, usart_reg_map *regs, MSerialT &serial) {
/* Handle RXNEIE and TXEIE interrupts.
* RXNE signifies availability of a byte in DR.
*
@@ -60,7 +60,7 @@ static inline __always_inline void my_usart_irq(ring_buffer *rb, ring_buffer *wb
}
else if (srflags & USART_SR_ORE) {
// overrun and empty data, just do a dummy read to clear ORE
- // and prevent a raise condition where a continous interrupt stream (due to ORE set) occurs
+ // and prevent a raise condition where a continuous interrupt stream (due to ORE set) occurs
// (see chapter "Overrun error" ) in STM32 reference manual
regs->DR;
}
@@ -90,20 +90,20 @@ constexpr bool serial_handles_emergency(int port) {
;
}
-#define DEFINE_HWSERIAL_MARLIN(name, n) \
- MarlinSerial name(USART##n, \
- BOARD_USART##n##_TX_PIN, \
- BOARD_USART##n##_RX_PIN, \
- serial_handles_emergency(n)); \
- extern "C" void __irq_usart##n(void) { \
+#define DEFINE_HWSERIAL_MARLIN(name, n) \
+ MSerialT name(serial_handles_emergency(n),\
+ USART##n, \
+ BOARD_USART##n##_TX_PIN, \
+ BOARD_USART##n##_RX_PIN); \
+ extern "C" void __irq_usart##n(void) { \
my_usart_irq(USART##n->rb, USART##n->wb, USART##n##_BASE, MSerial##n); \
}
#define DEFINE_HWSERIAL_UART_MARLIN(name, n) \
- MarlinSerial name(UART##n, \
+ MSerialT name(serial_handles_emergency(n), \
+ UART##n, \
BOARD_USART##n##_TX_PIN, \
- BOARD_USART##n##_RX_PIN, \
- serial_handles_emergency(n)); \
+ BOARD_USART##n##_RX_PIN); \
extern "C" void __irq_usart##n(void) { \
my_usart_irq(UART##n->rb, UART##n->wb, UART##n##_BASE, MSerial##n); \
}
@@ -134,12 +134,12 @@ constexpr bool IsSerialClassAllowed(const HardwareSerial&) { return false; }
// If you encounter this error, replace SerialX with MSerialX, for example MSerial3.
// Non-TMC ports were already validated in HAL.h, so do not require verbose error messages.
-#ifdef MYSERIAL0
- CHECK_CFG_SERIAL(MYSERIAL0);
-#endif
#ifdef MYSERIAL1
CHECK_CFG_SERIAL(MYSERIAL1);
#endif
+#ifdef MYSERIAL2
+ CHECK_CFG_SERIAL(MYSERIAL2);
+#endif
#ifdef LCD_SERIAL
CHECK_CFG_SERIAL(LCD_SERIAL);
#endif
@@ -167,6 +167,15 @@ constexpr bool IsSerialClassAllowed(const HardwareSerial&) { return false; }
#if AXIS_HAS_HW_SERIAL(Z4)
CHECK_AXIS_SERIAL(Z4);
#endif
+#if AXIS_HAS_HW_SERIAL(I)
+ CHECK_AXIS_SERIAL(I);
+#endif
+#if AXIS_HAS_HW_SERIAL(J)
+ CHECK_AXIS_SERIAL(J);
+#endif
+#if AXIS_HAS_HW_SERIAL(K)
+ CHECK_AXIS_SERIAL(K);
+#endif
#if AXIS_HAS_HW_SERIAL(E0)
CHECK_AXIS_SERIAL(E0);
#endif
diff --git a/Marlin/src/HAL/STM32F1/MarlinSerial.h b/Marlin/src/HAL/STM32F1/MarlinSerial.h
index 6aa94b64fff7..dda32fe7a2ef 100644
--- a/Marlin/src/HAL/STM32F1/MarlinSerial.h
+++ b/Marlin/src/HAL/STM32F1/MarlinSerial.h
@@ -26,28 +26,13 @@
#include
#include "../../inc/MarlinConfigPre.h"
-#if ENABLED(EMERGENCY_PARSER)
- #include "../../feature/e_parser.h"
-#endif
+#include "../../core/serial_hook.h"
// Increase priority of serial interrupts, to reduce overflow errors
#define UART_IRQ_PRIO 1
-class MarlinSerial : public HardwareSerial {
-public:
- #if ENABLED(EMERGENCY_PARSER)
- const bool ep_enabled;
- EmergencyParser::State emergency_state;
- inline bool emergency_parser_enabled() { return ep_enabled; }
- #endif
-
- MarlinSerial(struct usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin, bool TERN_(EMERGENCY_PARSER, ep_capable)) :
- HardwareSerial(usart_device, tx_pin, rx_pin)
- #if ENABLED(EMERGENCY_PARSER)
- , ep_enabled(ep_capable)
- , emergency_state(EmergencyParser::State::EP_RESET)
- #endif
- { }
+struct MarlinSerial : public HardwareSerial {
+ MarlinSerial(struct usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin) : HardwareSerial(usart_device, tx_pin, rx_pin) { }
#ifdef UART_IRQ_PRIO
// Shadow the parent methods to set IRQ priority after begin()
@@ -62,10 +47,12 @@ class MarlinSerial : public HardwareSerial {
#endif
};
-extern MarlinSerial MSerial1;
-extern MarlinSerial MSerial2;
-extern MarlinSerial MSerial3;
+typedef Serial1Class MSerialT;
+
+extern MSerialT MSerial1;
+extern MSerialT MSerial2;
+extern MSerialT MSerial3;
#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY)
- extern MarlinSerial MSerial4;
- extern MarlinSerial MSerial5;
+ extern MSerialT MSerial4;
+ extern MSerialT MSerial5;
#endif
diff --git a/Marlin/src/HAL/STM32F1/Servo.cpp b/Marlin/src/HAL/STM32F1/Servo.cpp
index e1ee83149374..36f7c6d51273 100644
--- a/Marlin/src/HAL/STM32F1/Servo.cpp
+++ b/Marlin/src/HAL/STM32F1/Servo.cpp
@@ -45,7 +45,7 @@ uint8_t ServoCount = 0;
*
* This uses the smallest prescaler that allows an overflow < 2^16.
*/
-#define MAX_OVERFLOW UINT16_MAX //((1 << 16) - 1)
+#define MAX_OVERFLOW UINT16_MAX // _BV(16) - 1
#define CYC_MSEC (1000 * CYCLES_PER_MICROSECOND)
#define TAU_MSEC 20
#define TAU_USEC (TAU_MSEC * 1000)
diff --git a/Marlin/src/HAL/STM32F1/build_flags.py b/Marlin/src/HAL/STM32F1/build_flags.py
index c51fd4fa58fd..d0848d1c6438 100755
--- a/Marlin/src/HAL/STM32F1/build_flags.py
+++ b/Marlin/src/HAL/STM32F1/build_flags.py
@@ -11,6 +11,7 @@
"-fsigned-char",
"-fno-move-loop-invariants",
"-fno-strict-aliasing",
+ "-fsingle-precision-constant",
"--specs=nano.specs",
"--specs=nosys.specs",
diff --git a/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp b/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp
index a6395698aae7..4e25bc69da4e 100644
--- a/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp
+++ b/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp
@@ -19,14 +19,13 @@
* along with this program. If not, see .
*
*/
+#ifdef __STM32F1__
/**
* PersistentStore for Arduino-style EEPROM interface
* with simple implementations supplied by Marlin.
*/
-#ifdef __STM32F1__
-
#include "../../inc/MarlinConfig.h"
#if ENABLED(IIC_BL24CXX_EEPROM)
@@ -48,13 +47,11 @@ 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) {
- size_t written = 0;
+ uint16_t written = 0;
while (size--) {
uint8_t v = *value;
uint8_t * const p = (uint8_t * const)pos;
- // EEPROM has only ~100,000 write cycles,
- // so only write bytes that have changed!
- if (v != eeprom_read_byte(p)) {
+ if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed!
eeprom_write_byte(p, v);
if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes
if (eeprom_read_byte(p) != v) {
diff --git a/Marlin/src/HAL/STM32F1/eeprom_flash.cpp b/Marlin/src/HAL/STM32F1/eeprom_flash.cpp
index dfcaaaf29ff3..e7d9dd29e2c5 100644
--- a/Marlin/src/HAL/STM32F1/eeprom_flash.cpp
+++ b/Marlin/src/HAL/STM32F1/eeprom_flash.cpp
@@ -48,8 +48,8 @@ static uint8_t ram_eeprom[MARLIN_EEPROM_SIZE] __attribute__((aligned(4))) = {0};
static bool eeprom_dirty = false;
bool PersistentStore::access_start() {
- const uint32_t* source = reinterpret_cast(EEPROM_PAGE0_BASE);
- uint32_t* destination = reinterpret_cast(ram_eeprom);
+ const uint32_t *source = reinterpret_cast(EEPROM_PAGE0_BASE);
+ uint32_t *destination = reinterpret_cast(ram_eeprom);
static_assert(0 == (MARLIN_EEPROM_SIZE) % 4, "MARLIN_EEPROM_SIZE is corrupted. (Must be a multiple of 4.)"); // Ensure copying as uint32_t is safe
constexpr size_t eeprom_size_u32 = (MARLIN_EEPROM_SIZE) / 4;
diff --git a/Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp b/Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp
index ccc3fc537f1a..78b7af0b0418 100644
--- a/Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp
+++ b/Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp
@@ -40,7 +40,7 @@ void eeprom_init() { BL24CXX::init(); }
// Public functions
// ------------------------
-void eeprom_write_byte(uint8_t *pos, unsigned char value) {
+void eeprom_write_byte(uint8_t *pos, uint8_t value) {
const unsigned eeprom_address = (unsigned)pos;
return BL24CXX::writeOneByte(eeprom_address, value);
}
diff --git a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp
index 6e992a22a32d..0ad69065cf9c 100644
--- a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp
+++ b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp
@@ -1,6 +1,5 @@
/**
* Marlin 3D Printer Firmware
- *
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* This program is free software: you can redistribute it and/or modify
@@ -53,13 +52,13 @@ bool PersistentStore::access_start() {
}
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ uint16_t written = 0;
while (size--) {
uint8_t * const p = (uint8_t * const)pos;
uint8_t v = *value;
- // EEPROM has only ~100,000 write cycles,
- // so only write bytes that have changed!
- if (v != eeprom_read_byte(p)) {
+ if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed!
eeprom_write_byte(p, v);
+ if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes
if (eeprom_read_byte(p) != v) {
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
return true;
diff --git a/Marlin/src/HAL/STM32F1/endstop_interrupts.h b/Marlin/src/HAL/STM32F1/endstop_interrupts.h
index bcb07d991d75..4d7edb9496c1 100644
--- a/Marlin/src/HAL/STM32F1/endstop_interrupts.h
+++ b/Marlin/src/HAL/STM32F1/endstop_interrupts.h
@@ -71,4 +71,10 @@ void setup_endstop_interrupts() {
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
+ TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
+ TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
+ TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
+ TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
+ TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
+ TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
}
diff --git a/Marlin/src/HAL/STM32F1/fastio.h b/Marlin/src/HAL/STM32F1/fastio.h
index a618fccc578e..e75254d6929e 100644
--- a/Marlin/src/HAL/STM32F1/fastio.h
+++ b/Marlin/src/HAL/STM32F1/fastio.h
@@ -29,9 +29,9 @@
#include
-#define READ(IO) (PIN_MAP[IO].gpio_device->regs->IDR & (1U << PIN_MAP[IO].gpio_bit) ? HIGH : LOW)
-#define WRITE(IO,V) (PIN_MAP[IO].gpio_device->regs->BSRR = (1U << PIN_MAP[IO].gpio_bit) << ((V) ? 0 : 16))
-#define TOGGLE(IO) (PIN_MAP[IO].gpio_device->regs->ODR = PIN_MAP[IO].gpio_device->regs->ODR ^ (1U << PIN_MAP[IO].gpio_bit))
+#define READ(IO) (PIN_MAP[IO].gpio_device->regs->IDR & _BV32(PIN_MAP[IO].gpio_bit) ? HIGH : LOW)
+#define WRITE(IO,V) (PIN_MAP[IO].gpio_device->regs->BSRR = _BV32(PIN_MAP[IO].gpio_bit) << ((V) ? 0 : 16))
+#define TOGGLE(IO) TBI32(PIN_MAP[IO].gpio_device->regs->ODR, PIN_MAP[IO].gpio_bit)
#define _GET_MODE(IO) gpio_get_mode(PIN_MAP[IO].gpio_device, PIN_MAP[IO].gpio_bit)
#define _SET_MODE(IO,M) gpio_set_mode(PIN_MAP[IO].gpio_device, PIN_MAP[IO].gpio_bit, M)
diff --git a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h
index 8d4c54ec0fd4..89ee66d6464b 100644
--- a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h
+++ b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h
@@ -34,9 +34,9 @@
#endif
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
- #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on this platform."
+ #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on the STM32F1 platform."
#elif ENABLED(SERIAL_STATS_DROPPED_RX)
- #error "SERIAL_STATS_DROPPED_RX is not supported on this platform."
+ #error "SERIAL_STATS_DROPPED_RX is not supported on the STM32F1 platform."
#endif
#if ENABLED(NEOPIXEL_LED)
diff --git a/Marlin/src/HAL/STM32F1/msc_sd.cpp b/Marlin/src/HAL/STM32F1/msc_sd.cpp
index ba722b8aebfe..7725b2c32400 100644
--- a/Marlin/src/HAL/STM32F1/msc_sd.cpp
+++ b/Marlin/src/HAL/STM32F1/msc_sd.cpp
@@ -19,11 +19,12 @@
#include "msc_sd.h"
#include "SPI.h"
+#include "usb_reg_map.h"
#define PRODUCT_ID 0x29
USBMassStorage MarlinMSC;
-MarlinUSBCompositeSerial MarlinCompositeSerial;
+Serial1Class MarlinCompositeSerial(true);
#include "../../inc/MarlinConfig.h"
@@ -41,14 +42,28 @@ MarlinUSBCompositeSerial MarlinCompositeSerial;
#endif
#if ENABLED(EMERGENCY_PARSER)
- void (*real_rx_callback)(void);
- void my_rx_callback(void) {
- real_rx_callback();
- int len = MarlinCompositeSerial.available();
- while (len-- > 0) // >0 because available() may return a negative value
- emergency_parser.update(MarlinCompositeSerial.emergency_state, MarlinCompositeSerial.peek());
+ // The original callback is not called (no way to retrieve address).
+ // That callback detects a special STM32 reset sequence: this functionality is not essential
+ // as M997 achieves the same.
+ void my_rx_callback(unsigned int, void*) {
+ // max length of 16 is enough to contain all emergency commands
+ uint8 buf[16];
+
+ //rx is usbSerialPart.endpoints[2]
+ uint16 len = usb_get_ep_rx_count(usbSerialPart.endpoints[2].address);
+ uint32 total = composite_cdcacm_data_available();
+
+ if (len == 0 || total == 0 || !WITHIN(total, len, COUNT(buf)))
+ return;
+
+ // cannot get character by character due to bug in composite_cdcacm_peek_ex
+ len = composite_cdcacm_peek(buf, total);
+
+ for (uint32 i = 0; i < len; i++)
+ emergency_parser.update(MarlinCompositeSerial.emergency_state, buf[i+total-len]);
}
+
#endif
void MSC_SD_init() {
@@ -73,9 +88,7 @@ void MSC_SD_init() {
MarlinCompositeSerial.registerComponent();
USBComposite.begin();
#if ENABLED(EMERGENCY_PARSER)
- //rx is usbSerialPart.endpoints[2]
- real_rx_callback = usbSerialPart.endpoints[2].callback;
- usbSerialPart.endpoints[2].callback = my_rx_callback;
+ composite_cdcacm_set_hooks(USBHID_CDCACM_HOOK_RX, my_rx_callback);
#endif
}
diff --git a/Marlin/src/HAL/STM32F1/msc_sd.h b/Marlin/src/HAL/STM32F1/msc_sd.h
index 1e4e4c44b1b5..f4636bdff702 100644
--- a/Marlin/src/HAL/STM32F1/msc_sd.h
+++ b/Marlin/src/HAL/STM32F1/msc_sd.h
@@ -18,25 +18,9 @@
#include
#include "../../inc/MarlinConfigPre.h"
-#if ENABLED(EMERGENCY_PARSER)
- #include "../../feature/e_parser.h"
-#endif
-
-class MarlinUSBCompositeSerial : public USBCompositeSerial {
-public:
- MarlinUSBCompositeSerial() : USBCompositeSerial()
- #if ENABLED(EMERGENCY_PARSER)
- , emergency_state(EmergencyParser::State::EP_RESET)
- #endif
- { }
-
- #if ENABLED(EMERGENCY_PARSER)
- EmergencyParser::State emergency_state;
- inline bool emergency_parser_enabled() { return true; }
- #endif
-};
+#include "../../core/serial_hook.h"
extern USBMassStorage MarlinMSC;
-extern MarlinUSBCompositeSerial MarlinCompositeSerial;
+extern Serial1Class MarlinCompositeSerial;
void MSC_SD_init();
diff --git a/Marlin/src/HAL/STM32F1/onboard_sd.h b/Marlin/src/HAL/STM32F1/onboard_sd.h
index 1dc7ec5b3bfa..1c0a1c5b845b 100644
--- a/Marlin/src/HAL/STM32F1/onboard_sd.h
+++ b/Marlin/src/HAL/STM32F1/onboard_sd.h
@@ -48,7 +48,7 @@ DRESULT disk_read(BYTE pdrv, BYTE* buff, DWORD sector, UINT count);
DRESULT disk_write(BYTE pdrv, const BYTE* buff, DWORD sector, UINT count);
#endif
#if _DISKIO_IOCTL
- DRESULT disk_ioctl(BYTE pdrv, BYTE cmd, void* buff);
+ DRESULT disk_ioctl(BYTE pdrv, BYTE cmd, void *buff);
#endif
/* Disk Status Bits (DSTATUS) */
diff --git a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp b/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp
index 1095389946ad..5edf96fe56be 100644
--- a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp
+++ b/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp
@@ -90,12 +90,20 @@ void TFT_SPI::DataTransferBegin(uint16_t DataSize) {
TFT_CS_L;
}
+#ifdef TFT_DEFAULT_DRIVER
+ #include "../../../lcd/tft_io/tft_ids.h"
+#endif
+
uint32_t TFT_SPI::GetID() {
uint32_t id;
id = ReadID(LCD_READ_ID);
-
- if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF)
+ if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) {
id = ReadID(LCD_READ_ID4);
+ #ifdef TFT_DEFAULT_DRIVER
+ if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF)
+ id = TFT_DEFAULT_DRIVER;
+ #endif
+ }
return id;
}
diff --git a/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp b/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp
index 98371c5ffb85..ac9ad072aa05 100644
--- a/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp
+++ b/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp
@@ -22,7 +22,7 @@
#include "../../../inc/MarlinConfig.h"
-#if HAS_TFT_XPT2046 || HAS_TOUCH_BUTTONS
+#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS
#include "xpt2046.h"
#include
diff --git a/Marlin/src/HAL/STM32F1/tft/xpt2046.h b/Marlin/src/HAL/STM32F1/tft/xpt2046.h
index 65602bda0f40..aba0799e445f 100644
--- a/Marlin/src/HAL/STM32F1/tft/xpt2046.h
+++ b/Marlin/src/HAL/STM32F1/tft/xpt2046.h
@@ -54,7 +54,7 @@ enum XPTCoordinate : uint8_t {
XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE,
};
-#if !defined(XPT2046_Z1_THRESHOLD)
+#ifndef XPT2046_Z1_THRESHOLD
#define XPT2046_Z1_THRESHOLD 10
#endif
diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h
index 3e2e7775f1e3..38a0fc7fa1e9 100644
--- a/Marlin/src/HAL/STM32F1/timers.h
+++ b/Marlin/src/HAL/STM32F1/timers.h
@@ -25,9 +25,10 @@
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
-#include
+#include "../../inc/MarlinConfig.h"
+#include "HAL.h"
+
#include
-#include "../../core/boards.h"
// ------------------------
// Defines
@@ -37,7 +38,6 @@
* TODO: Check and confirm what timer we will use for each Temps and stepper driving.
* We should probable drive temps with PWM.
*/
-#define FORCE_INLINE __attribute__((always_inline)) inline
typedef uint16_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFF
@@ -80,7 +80,7 @@ typedef uint16_t hal_timer_t;
//#define TEMP_TIMER_NUM 4 // 2->4, Timer 2 for Stepper Current PWM
#endif
-#if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_E3_DIP, BTT_SKR_MINI_E3_V1_2, MKS_ROBIN_LITE)
+#if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_E3_DIP, BTT_SKR_MINI_E3_V1_2, MKS_ROBIN_LITE, MKS_ROBIN_E3D, MKS_ROBIN_E3)
// SKR Mini E3 boards use PA8 as FAN_PIN, so TIMER 1 is used for Fan PWM.
#ifdef STM32_HIGH_DENSITY
#define SERVO0_TIMER_NUM 8 // tone.cpp uses Timer 4
diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.cpp b/Marlin/src/HAL/TEENSY31_32/HAL.cpp
index 8c3dd8337740..f08cf799e9e8 100644
--- a/Marlin/src/HAL/TEENSY31_32/HAL.cpp
+++ b/Marlin/src/HAL/TEENSY31_32/HAL.cpp
@@ -31,6 +31,15 @@
#include
+#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
+#define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X)
+#if WITHIN(SERIAL_PORT, 0, 3)
+ IMPLEMENT_SERIAL(SERIAL_PORT);
+#else
+ #error "SERIAL_PORT must be from 0 to 3."
+#endif
+USBSerialType USBSerial(false, SerialUSB);
+
uint16_t HAL_adc_result;
static const uint8_t pin2sc1a[] = {
@@ -69,6 +78,8 @@ uint8_t HAL_get_reset_source() {
return 0;
}
+void HAL_reboot() { _reboot_Teensyduino_(); }
+
extern "C" {
extern char __bss_end;
extern char __heap_start;
diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h
index 9156aadb4de0..8baa7936f5f8 100644
--- a/Marlin/src/HAL/TEENSY31_32/HAL.h
+++ b/Marlin/src/HAL/TEENSY31_32/HAL.h
@@ -34,7 +34,6 @@
#include "fastio.h"
#include "watchdog.h"
-
#include
#define ST7920_DELAY_1 DELAY_NS(600)
@@ -50,14 +49,27 @@
#define IS_TEENSY32 1
#endif
-#define _MSERIAL(X) Serial##X
-#define MSERIAL(X) _MSERIAL(X)
+#include "../../core/serial_hook.h"
+
#define Serial0 Serial
+#define _DECLARE_SERIAL(X) \
+ typedef ForwardSerial1Class DefaultSerial##X; \
+ extern DefaultSerial##X MSerial##X
+#define DECLARE_SERIAL(X) _DECLARE_SERIAL(X)
+
+typedef ForwardSerial1Class USBSerialType;
+extern USBSerialType USBSerial;
+
+#define _MSERIAL(X) MSerial##X
+#define MSERIAL(X) _MSERIAL(X)
#if SERIAL_PORT == -1
- #define MYSERIAL0 SerialUSB
+ #define MYSERIAL1 USBSerial
#elif WITHIN(SERIAL_PORT, 0, 3)
- #define MYSERIAL0 MSERIAL(SERIAL_PORT)
+ DECLARE_SERIAL(SERIAL_PORT);
+ #define MYSERIAL1 MSERIAL(SERIAL_PORT)
+#else
+ #error "The required SERIAL_PORT must be from 0 to 3, or -1 for Native USB."
#endif
#define HAL_SERVO_LIB libServo
@@ -74,17 +86,6 @@ typedef int8_t pin_t;
#define ENABLE_ISRS() __enable_irq()
#define DISABLE_ISRS() __disable_irq()
-#ifndef strncpy_P
- #define strncpy_P(dest, src, num) strncpy((dest), (src), (num))
-#endif
-
-// Fix bug in pgm_read_ptr
-#undef pgm_read_ptr
-#define pgm_read_ptr(addr) (*((void**)(addr)))
-// Add type-checking to pgm_read_word
-#undef pgm_read_word
-#define pgm_read_word(addr) (*((uint16_t*)(addr)))
-
inline void HAL_init() {}
// Clear the reset reason
@@ -93,7 +94,7 @@ void HAL_clear_reset_source();
// Get the reason for the reset
uint8_t HAL_get_reset_source();
-inline void HAL_reboot() {} // reboot the board or restart the bootloader
+void HAL_reboot();
FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
diff --git a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp
index dce236ef6bd0..b6f01e6c0ea0 100644
--- a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp
+++ b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp
@@ -21,11 +21,12 @@
*/
#ifdef __MK20DX256__
+#include "../../inc/MarlinConfig.h"
#include "HAL.h"
+
#include
#include
#include "spi_pins.h"
-#include "../../core/macros.h"
static SPISettings spiConfig;
@@ -82,7 +83,7 @@ uint8_t spiRec() {
}
// SPI read data
-void spiRead(uint8_t* buf, uint16_t nbyte) {
+void spiRead(uint8_t *buf, uint16_t nbyte) {
SPI.beginTransaction(spiConfig);
SPI.transfer(buf, nbyte);
SPI.endTransaction();
@@ -107,7 +108,7 @@ void spiSend(uint8_t b) {
}
// SPI send block
-void spiSendBlock(uint8_t token, const uint8_t* buf) {
+void spiSendBlock(uint8_t token, const uint8_t *buf) {
SPI.beginTransaction(spiConfig);
SPDR = token;
for (uint16_t i = 0; i < 512; i += 2) {
diff --git a/Marlin/src/HAL/TEENSY31_32/eeprom.cpp b/Marlin/src/HAL/TEENSY31_32/eeprom.cpp
index f2ae5dd534ec..85febebebc25 100644
--- a/Marlin/src/HAL/TEENSY31_32/eeprom.cpp
+++ b/Marlin/src/HAL/TEENSY31_32/eeprom.cpp
@@ -18,14 +18,14 @@
*/
#ifdef __MK20DX256__
-#include "../../inc/MarlinConfig.h"
-
-#if USE_WIRED_EEPROM
-
/**
* HAL PersistentStore for Teensy 3.2 (MK20DX256)
*/
+#include "../../inc/MarlinConfig.h"
+
+#if USE_WIRED_EEPROM
+
#include "../shared/eeprom_api.h"
#include
@@ -38,13 +38,13 @@ bool PersistentStore::access_start() { return true; }
bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ uint16_t written = 0;
while (size--) {
uint8_t * const p = (uint8_t * const)pos;
uint8_t v = *value;
- // EEPROM has only ~100,000 write cycles,
- // so only write bytes that have changed!
- if (v != eeprom_read_byte(p)) {
+ if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed!
eeprom_write_byte(p, v);
+ if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes
if (eeprom_read_byte(p) != v) {
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
return true;
diff --git a/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h b/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h
index 999ada512761..9c7e2104882e 100644
--- a/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h
+++ b/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h
@@ -64,4 +64,10 @@ void setup_endstop_interrupts() {
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
+ TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
+ TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
+ TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
+ TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
+ TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
+ TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
}
diff --git a/Marlin/src/HAL/TEENSY31_32/fastio.h b/Marlin/src/HAL/TEENSY31_32/fastio.h
index 9a299de9c763..622799ec8cac 100644
--- a/Marlin/src/HAL/TEENSY31_32/fastio.h
+++ b/Marlin/src/HAL/TEENSY31_32/fastio.h
@@ -28,7 +28,7 @@
*/
#ifndef MASK
- #define MASK(PIN) (1 << PIN)
+ #define MASK(PIN) _BV(PIN)
#endif
#define GPIO_BITBAND_ADDR(reg, bit) (((uint32_t)&(reg) - 0x40000000) * 32 + (bit) * 4 + 0x42000000)
diff --git a/Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h b/Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h
index 3932ee6a76c1..1efa76b1e9df 100644
--- a/Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h
+++ b/Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h
@@ -34,5 +34,9 @@
#endif
#if HAS_TMC_SW_SERIAL
- #error "TMC220x Software Serial is not supported on this platform."
+ #error "TMC220x Software Serial is not supported on Teensy 3.1/3.2."
+#endif
+
+#if ENABLED(POSTMORTEM_DEBUGGING)
+ #error "POSTMORTEM_DEBUGGING is not yet supported on Teensy 3.1/3.2."
#endif
diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.cpp b/Marlin/src/HAL/TEENSY35_36/HAL.cpp
index 92907353b833..046c00b56ed5 100644
--- a/Marlin/src/HAL/TEENSY35_36/HAL.cpp
+++ b/Marlin/src/HAL/TEENSY35_36/HAL.cpp
@@ -31,6 +31,14 @@
#include
+#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
+#define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X)
+#if WITHIN(SERIAL_PORT, 0, 3)
+ IMPLEMENT_SERIAL(SERIAL_PORT);
+#endif
+
+USBSerialType USBSerial(false, SerialUSB);
+
uint16_t HAL_adc_result, HAL_adc_select;
static const uint8_t pin2sc1a[] = {
@@ -78,6 +86,8 @@ uint8_t HAL_get_reset_source() {
return 0;
}
+void HAL_reboot() { _reboot_Teensyduino_(); }
+
extern "C" {
extern char __bss_end;
extern char __heap_start;
diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h
index 04151e837861..26c35223bd48 100644
--- a/Marlin/src/HAL/TEENSY35_36/HAL.h
+++ b/Marlin/src/HAL/TEENSY35_36/HAL.h
@@ -53,14 +53,27 @@
#define IS_TEENSY35 1
#endif
-#define _MSERIAL(X) Serial##X
-#define MSERIAL(X) _MSERIAL(X)
+#include "../../core/serial_hook.h"
+
#define Serial0 Serial
+#define _DECLARE_SERIAL(X) \
+ typedef ForwardSerial1Class DefaultSerial##X; \
+ extern DefaultSerial##X MSerial##X
+#define DECLARE_SERIAL(X) _DECLARE_SERIAL(X)
+
+typedef ForwardSerial1Class USBSerialType;
+extern USBSerialType USBSerial;
+
+#define _MSERIAL(X) MSerial##X
+#define MSERIAL(X) _MSERIAL(X)
#if SERIAL_PORT == -1
- #define MYSERIAL0 SerialUSB
+ #define MYSERIAL1 USBSerial
#elif WITHIN(SERIAL_PORT, 0, 3)
- #define MYSERIAL0 MSERIAL(SERIAL_PORT)
+ #define MYSERIAL1 MSERIAL(SERIAL_PORT)
+ DECLARE_SERIAL(SERIAL_PORT);
+#else
+ #error "SERIAL_PORT must be from 0 to 3, or -1 for Native USB."
#endif
#define HAL_SERVO_LIB libServo
@@ -80,17 +93,6 @@ typedef int8_t pin_t;
#undef sq
#define sq(x) ((x)*(x))
-#ifndef strncpy_P
- #define strncpy_P(dest, src, num) strncpy((dest), (src), (num))
-#endif
-
-// Fix bug in pgm_read_ptr
-#undef pgm_read_ptr
-#define pgm_read_ptr(addr) (*((void**)(addr)))
-// Add type-checking to pgm_read_word
-#undef pgm_read_word
-#define pgm_read_word(addr) (*((uint16_t*)(addr)))
-
inline void HAL_init() {}
// Clear reset reason
@@ -99,7 +101,7 @@ void HAL_clear_reset_source();
// Reset reason
uint8_t HAL_get_reset_source();
-inline void HAL_reboot() {} // reboot the board or restart the bootloader
+void HAL_reboot();
FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
diff --git a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp
index 84852cd3580d..28bca65af5da 100644
--- a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp
+++ b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp
@@ -26,11 +26,12 @@
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
+#include "../../inc/MarlinConfig.h"
#include "HAL.h"
+
#include
#include
#include "spi_pins.h"
-#include "../../core/macros.h"
static SPISettings spiConfig;
@@ -80,7 +81,7 @@ uint8_t spiRec() {
//return SPDR;
}
-void spiRead(uint8_t* buf, uint16_t nbyte) {
+void spiRead(uint8_t *buf, uint16_t nbyte) {
SPI.beginTransaction(spiConfig);
SPI.transfer(buf, nbyte);
SPI.endTransaction();
@@ -103,7 +104,7 @@ void spiSend(uint8_t b) {
//while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
}
-void spiSendBlock(uint8_t token, const uint8_t* buf) {
+void spiSendBlock(uint8_t token, const uint8_t *buf) {
SPI.beginTransaction(spiConfig);
SPDR = token;
for (uint16_t i = 0; i < 512; i += 2) {
diff --git a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp
index 8cd6b4ff41d7..b80e93b536a5 100644
--- a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp
+++ b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp
@@ -42,13 +42,13 @@ bool PersistentStore::access_start() { return true; }
bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ uint16_t written = 0;
while (size--) {
uint8_t * const p = (uint8_t * const)pos;
uint8_t v = *value;
- // EEPROM has only ~100,000 write cycles,
- // so only write bytes that have changed!
- if (v != eeprom_read_byte(p)) {
+ if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed!
eeprom_write_byte(p, v);
+ if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes
if (eeprom_read_byte(p) != v) {
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
return true;
diff --git a/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h b/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h
index 87e6a7507abc..a30024888535 100644
--- a/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h
+++ b/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h
@@ -63,4 +63,10 @@ void setup_endstop_interrupts() {
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
+ TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
+ TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
+ TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
+ TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
+ TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
+ TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
}
diff --git a/Marlin/src/HAL/TEENSY35_36/fastio.h b/Marlin/src/HAL/TEENSY35_36/fastio.h
index 9a299de9c763..622799ec8cac 100644
--- a/Marlin/src/HAL/TEENSY35_36/fastio.h
+++ b/Marlin/src/HAL/TEENSY35_36/fastio.h
@@ -28,7 +28,7 @@
*/
#ifndef MASK
- #define MASK(PIN) (1 << PIN)
+ #define MASK(PIN) _BV(PIN)
#endif
#define GPIO_BITBAND_ADDR(reg, bit) (((uint32_t)&(reg) - 0x40000000) * 32 + (bit) * 4 + 0x42000000)
diff --git a/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h b/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h
index ee80e42696fa..eef2850550eb 100644
--- a/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h
+++ b/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h
@@ -34,5 +34,9 @@
#endif
#if HAS_TMC_SW_SERIAL
- #error "TMC220x Software Serial is not supported on this platform."
+ #error "TMC220x Software Serial is not supported on Teensy 3.5/3.6."
+#endif
+
+#if ENABLED(POSTMORTEM_DEBUGGING)
+ #error "POSTMORTEM_DEBUGGING is not yet supported on Teensy 3.5/3.6."
#endif
diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.cpp b/Marlin/src/HAL/TEENSY40_41/HAL.cpp
index 5b1b4272f5ee..ccc8c2659c65 100644
--- a/Marlin/src/HAL/TEENSY40_41/HAL.cpp
+++ b/Marlin/src/HAL/TEENSY40_41/HAL.cpp
@@ -26,12 +26,20 @@
#ifdef __IMXRT1062__
+#include "../../inc/MarlinConfig.h"
#include "HAL.h"
+
#include "../shared/Delay.h"
#include "timers.h"
-
#include
+#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
+#define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X)
+#if WITHIN(SERIAL_PORT, 0, 3)
+ IMPLEMENT_SERIAL(SERIAL_PORT);
+#endif
+USBSerialType USBSerial(false, SerialUSB);
+
uint16_t HAL_adc_result, HAL_adc_select;
static const uint8_t pin2sc1a[] = {
@@ -113,6 +121,8 @@ uint8_t HAL_get_reset_source() {
return 0;
}
+void HAL_reboot() { _reboot_Teensyduino_(); }
+
#define __bss_end _ebss
extern "C" {
diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h
index 28f511631eea..1d00447fe894 100644
--- a/Marlin/src/HAL/TEENSY40_41/HAL.h
+++ b/Marlin/src/HAL/TEENSY40_41/HAL.h
@@ -37,6 +37,10 @@
#include
#include
+#if HAS_ETHERNET
+ #include "../../feature/ethernet.h"
+#endif
+
//#define ST7920_DELAY_1 DELAY_NS(600)
//#define ST7920_DELAY_2 DELAY_NS(750)
//#define ST7920_DELAY_3 DELAY_NS(750)
@@ -51,27 +55,37 @@
#define IS_TEENSY41 1
#endif
-#define _MSERIAL(X) Serial##X
-#define MSERIAL(X) _MSERIAL(X)
+#include "../../core/serial_hook.h"
#define Serial0 Serial
+#define _DECLARE_SERIAL(X) \
+ typedef ForwardSerial1Class DefaultSerial##X; \
+ extern DefaultSerial##X MSerial##X
+#define DECLARE_SERIAL(X) _DECLARE_SERIAL(X)
+
+typedef ForwardSerial1Class USBSerialType;
+extern USBSerialType USBSerial;
+
+#define _MSERIAL(X) MSerial##X
+#define MSERIAL(X) _MSERIAL(X)
#if SERIAL_PORT == -1
- #define MYSERIAL0 SerialUSB
+ #define MYSERIAL1 SerialUSB
#elif WITHIN(SERIAL_PORT, 0, 8)
- #define MYSERIAL0 MSERIAL(SERIAL_PORT)
+ DECLARE_SERIAL(SERIAL_PORT);
+ #define MYSERIAL1 MSERIAL(SERIAL_PORT)
#else
- #error "The required SERIAL_PORT must be from -1 to 8. Please update your configuration."
+ #error "The required SERIAL_PORT must be from 0 to 8, or -1 for Native USB."
#endif
#ifdef SERIAL_PORT_2
#if SERIAL_PORT_2 == -1
- #define MYSERIAL1 usbSerial
+ #define MYSERIAL2 usbSerial
#elif SERIAL_PORT_2 == -2
- #define MYSERIAL1 ethernet.telnetClient
+ #define MYSERIAL2 ethernet.telnetClient
#elif WITHIN(SERIAL_PORT_2, 0, 8)
- #define MYSERIAL1 MSERIAL(SERIAL_PORT_2)
+ #define MYSERIAL2 MSERIAL(SERIAL_PORT_2)
#else
- #error "SERIAL_PORT_2 must be from -2 to 8. Please update your configuration."
+ #error "SERIAL_PORT_2 must be from 0 to 8, or -1 for Native USB, or -2 for Ethernet."
#endif
#endif
@@ -92,21 +106,10 @@ typedef int8_t pin_t;
#undef sq
#define sq(x) ((x)*(x))
-#ifndef strncpy_P
- #define strncpy_P(dest, src, num) strncpy((dest), (src), (num))
-#endif
-
// Don't place string constants in PROGMEM
#undef PSTR
#define PSTR(str) ({static const char *data = (str); &data[0];})
-// Fix bug in pgm_read_ptr
-#undef pgm_read_ptr
-#define pgm_read_ptr(addr) (*((void**)(addr)))
-// Add type-checking to pgm_read_word
-#undef pgm_read_word
-#define pgm_read_word(addr) (*((uint16_t*)(addr)))
-
// Enable hooks into idle and setup for HAL
#define HAL_IDLETASK 1
FORCE_INLINE void HAL_idletask() {}
@@ -118,6 +121,8 @@ void HAL_clear_reset_source();
// Reset reason
uint8_t HAL_get_reset_source();
+void HAL_reboot();
+
FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
#if GCC_VERSION <= 50000
diff --git a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp
index 8c93049027ab..7e202d724edc 100644
--- a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp
+++ b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp
@@ -26,11 +26,12 @@
#ifdef __IMXRT1062__
+#include "../../inc/MarlinConfig.h"
#include "HAL.h"
+
#include
#include
#include "spi_pins.h"
-#include "../../core/macros.h"
static SPISettings spiConfig;
@@ -97,7 +98,7 @@ uint8_t spiRec() {
//return SPDR;
}
-void spiRead(uint8_t* buf, uint16_t nbyte) {
+void spiRead(uint8_t *buf, uint16_t nbyte) {
SPI.beginTransaction(spiConfig);
SPI.transfer(buf, nbyte);
SPI.endTransaction();
@@ -120,7 +121,7 @@ void spiSend(uint8_t b) {
//while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
}
-void spiSendBlock(uint8_t token, const uint8_t* buf) {
+void spiSendBlock(uint8_t token, const uint8_t *buf) {
SPI.beginTransaction(spiConfig);
SPDR = token;
for (uint16_t i = 0; i < 512; i += 2) {
diff --git a/Marlin/src/HAL/TEENSY40_41/eeprom.cpp b/Marlin/src/HAL/TEENSY40_41/eeprom.cpp
index fe2de388a7a0..3cd376edce62 100644
--- a/Marlin/src/HAL/TEENSY40_41/eeprom.cpp
+++ b/Marlin/src/HAL/TEENSY40_41/eeprom.cpp
@@ -22,14 +22,14 @@
*/
#ifdef __IMXRT1062__
-#include "../../inc/MarlinConfig.h"
-
-#if USE_WIRED_EEPROM
-
/**
* HAL PersistentStore for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
*/
+#include "../../inc/MarlinConfig.h"
+
+#if USE_WIRED_EEPROM
+
#include "../shared/eeprom_api.h"
#include
@@ -42,13 +42,13 @@ bool PersistentStore::access_start() { return true; }
bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ uint16_t written = 0;
while (size--) {
uint8_t * const p = (uint8_t * const)pos;
uint8_t v = *value;
- // EEPROM has only ~100,000 write cycles,
- // so only write bytes that have changed!
- if (v != eeprom_read_byte(p)) {
+ if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed!
eeprom_write_byte(p, v);
+ if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes
if (eeprom_read_byte(p) != v) {
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
return true;
diff --git a/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h b/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h
index a05e911668a7..4c3ddec9f1f1 100644
--- a/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h
+++ b/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h
@@ -63,4 +63,10 @@ void setup_endstop_interrupts() {
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
+ TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
+ TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
+ TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
+ TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
+ TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
+ TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
}
diff --git a/Marlin/src/HAL/TEENSY40_41/inc/SanityCheck.h b/Marlin/src/HAL/TEENSY40_41/inc/SanityCheck.h
index fbfe7b0fc3d4..3d2668d749bc 100644
--- a/Marlin/src/HAL/TEENSY40_41/inc/SanityCheck.h
+++ b/Marlin/src/HAL/TEENSY40_41/inc/SanityCheck.h
@@ -34,5 +34,9 @@
#endif
#if HAS_TMC_SW_SERIAL
- #error "TMC220x Software Serial is not supported on this platform."
+ #error "TMC220x Software Serial is not supported on Teensy 4.0/4.1."
+#endif
+
+#if ENABLED(POSTMORTEM_DEBUGGING)
+ #error "POSTMORTEM_DEBUGGING is not yet supported on Teensy 4.0/4.1."
#endif
diff --git a/Marlin/src/HAL/shared/Delay.cpp b/Marlin/src/HAL/shared/Delay.cpp
new file mode 100644
index 000000000000..129698fd306d
--- /dev/null
+++ b/Marlin/src/HAL/shared/Delay.cpp
@@ -0,0 +1,175 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#include "Delay.h"
+
+#include "../../inc/MarlinConfig.h"
+
+#if defined(__arm__) || defined(__thumb__)
+
+ static uint32_t ASM_CYCLES_PER_ITERATION = 4; // Initial bet which will be adjusted in calibrate_delay_loop
+
+ // Simple assembler loop counting down
+ void delay_asm(uint32_t cy) {
+ cy = _MAX(cy / ASM_CYCLES_PER_ITERATION, 1U); // Zero is forbidden here
+ __asm__ __volatile__(
+ A(".syntax unified") // is to prevent CM0,CM1 non-unified syntax
+ L("1")
+ A("subs %[cnt],#1")
+ A("bne 1b")
+ : [cnt]"+r"(cy) // output: +r means input+output
+ : // input:
+ : "cc" // clobbers:
+ );
+ }
+
+ // We can't use CMSIS since it's not available on all platform, so fallback to hardcoded register values
+ #define HW_REG(X) *(volatile uint32_t *)(X)
+ #define _DWT_CTRL 0xE0001000
+ #define _DWT_CYCCNT 0xE0001004 // CYCCNT is 32bits, takes 37s or so to wrap.
+ #define _DEM_CR 0xE000EDFC
+ #define _LAR 0xE0001FB0
+
+ // Use hardware cycle counter instead, it's much safer
+ void delay_dwt(uint32_t count) {
+ // Reuse the ASM_CYCLES_PER_ITERATION variable to avoid wasting another useless variable
+ uint32_t start = HW_REG(_DWT_CYCCNT) - ASM_CYCLES_PER_ITERATION, elapsed;
+ do {
+ elapsed = HW_REG(_DWT_CYCCNT) - start;
+ } while (elapsed < count);
+ }
+
+ // Pointer to asm function, calling the functions has a ~20 cycles overhead
+ DelayImpl DelayCycleFnc = delay_asm;
+
+ void calibrate_delay_loop() {
+ // Check if we have a working DWT implementation in the CPU (see https://developer.arm.com/documentation/ddi0439/b/Data-Watchpoint-and-Trace-Unit/DWT-Programmers-Model)
+ if (!HW_REG(_DWT_CTRL)) {
+ // No DWT present, so fallback to plain old ASM nop counting
+ // Unfortunately, we don't exactly know how many iteration it'll take to decrement a counter in a loop
+ // It depends on the CPU architecture, the code current position (flash vs SRAM)
+ // So, instead of wild guessing and making mistake, instead
+ // compute it once for all
+ ASM_CYCLES_PER_ITERATION = 1;
+ // We need to fetch some reference clock before waiting
+ cli();
+ uint32_t start = micros();
+ delay_asm(1000); // On a typical CPU running in MHz, waiting 1000 "unknown cycles" means it'll take between 1ms to 6ms, that's perfectly acceptable
+ uint32_t end = micros();
+ sei();
+ uint32_t expectedCycles = (end - start) * ((F_CPU) / 1000000UL); // Convert microseconds to cycles
+ // Finally compute the right scale
+ ASM_CYCLES_PER_ITERATION = (uint32_t)(expectedCycles / 1000);
+
+ // No DWT present, likely a Cortex M0 so NOP counting is our best bet here
+ DelayCycleFnc = delay_asm;
+ }
+ else {
+ // Enable DWT counter
+ // From https://stackoverflow.com/a/41188674/1469714
+ HW_REG(_DEM_CR) = HW_REG(_DEM_CR) | 0x01000000; // Enable trace
+ #if __CORTEX_M == 7
+ HW_REG(_LAR) = 0xC5ACCE55; // Unlock access to DWT registers, see https://developer.arm.com/documentation/ihi0029/e/ section B2.3.10
+ #endif
+ HW_REG(_DWT_CYCCNT) = 0; // Clear DWT cycle counter
+ HW_REG(_DWT_CTRL) = HW_REG(_DWT_CTRL) | 1; // Enable DWT cycle counter
+
+ // Then calibrate the constant offset from the counter
+ ASM_CYCLES_PER_ITERATION = 0;
+ uint32_t s = HW_REG(_DWT_CYCCNT);
+ uint32_t e = HW_REG(_DWT_CYCCNT); // (e - s) contains the number of cycle required to read the cycle counter
+ delay_dwt(0);
+ uint32_t f = HW_REG(_DWT_CYCCNT); // (f - e) contains the delay to call the delay function + the time to read the cycle counter
+ ASM_CYCLES_PER_ITERATION = (f - e) - (e - s);
+
+ // Use safer DWT function
+ DelayCycleFnc = delay_dwt;
+ }
+ }
+
+ #if ENABLED(MARLIN_DEV_MODE)
+ void dump_delay_accuracy_check() {
+ auto report_call_time = [](PGM_P const name, PGM_P const unit, const uint32_t cycles, const uint32_t total, const bool do_flush=true) {
+ SERIAL_ECHOPGM("Calling ");
+ SERIAL_ECHOPGM_P(name);
+ SERIAL_ECHOLNPAIR(" for ", cycles);
+ SERIAL_ECHOPGM_P(unit);
+ SERIAL_ECHOLNPAIR(" took: ", total);
+ SERIAL_ECHOPGM_P(unit);
+ if (do_flush) SERIAL_FLUSHTX();
+ };
+
+ uint32_t s, e;
+
+ SERIAL_ECHOLNPAIR("Computed delay calibration value: ", ASM_CYCLES_PER_ITERATION);
+ SERIAL_FLUSH();
+ // Display the results of the calibration above
+ constexpr uint32_t testValues[] = { 1, 5, 10, 20, 50, 100, 150, 200, 350, 500, 750, 1000 };
+ for (auto i : testValues) {
+ s = micros(); DELAY_US(i); e = micros();
+ report_call_time(PSTR("delay"), PSTR("us"), i, e - s);
+ }
+
+ if (HW_REG(_DWT_CTRL)) {
+ for (auto i : testValues) {
+ s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(i); e = HW_REG(_DWT_CYCCNT);
+ report_call_time(PSTR("runtime delay"), PSTR("cycles"), i, e - s);
+ }
+
+ // Measure the delay to call a real function compared to a function pointer
+ s = HW_REG(_DWT_CYCCNT); delay_dwt(1); e = HW_REG(_DWT_CYCCNT);
+ report_call_time(PSTR("delay_dwt"), PSTR("cycles"), 1, e - s);
+
+ static PGMSTR(dcd, "DELAY_CYCLES directly ");
+
+ s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES( 1); e = HW_REG(_DWT_CYCCNT);
+ report_call_time(dcd, PSTR("cycles"), 1, e - s, false);
+
+ s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES( 5); e = HW_REG(_DWT_CYCCNT);
+ report_call_time(dcd, PSTR("cycles"), 5, e - s, false);
+
+ s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(10); e = HW_REG(_DWT_CYCCNT);
+ report_call_time(dcd, PSTR("cycles"), 10, e - s, false);
+
+ s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(20); e = HW_REG(_DWT_CYCCNT);
+ report_call_time(dcd, PSTR("cycles"), 20, e - s, false);
+
+ s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(50); e = HW_REG(_DWT_CYCCNT);
+ report_call_time(dcd, PSTR("cycles"), 50, e - s, false);
+
+ s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(100); e = HW_REG(_DWT_CYCCNT);
+ report_call_time(dcd, PSTR("cycles"), 100, e - s, false);
+
+ s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(200); e = HW_REG(_DWT_CYCCNT);
+ report_call_time(dcd, PSTR("cycles"), 200, e - s, false);
+ }
+ }
+ #endif // MARLIN_DEV_MODE
+
+
+#else
+
+ void calibrate_delay_loop() {}
+ #if ENABLED(MARLIN_DEV_MODE)
+ void dump_delay_accuracy_check() { SERIAL_ECHOPGM_P(PSTR("N/A on this platform")); }
+ #endif
+
+#endif
diff --git a/Marlin/src/HAL/shared/Delay.h b/Marlin/src/HAL/shared/Delay.h
index a48f3f79cfd0..f7e01ad25cf8 100644
--- a/Marlin/src/HAL/shared/Delay.h
+++ b/Marlin/src/HAL/shared/Delay.h
@@ -21,6 +21,8 @@
*/
#pragma once
+#include "../../inc/MarlinConfigPre.h"
+
/**
* Busy wait delay cycles routines:
*
@@ -31,79 +33,68 @@
#include "../../core/macros.h"
-#if defined(__arm__) || defined(__thumb__)
-
- #if __CORTEX_M == 7
+void calibrate_delay_loop();
- // Cortex-M3 through M7 can use the cycle counter of the DWT unit
- // https://www.anthonyvh.com/2017/05/18/cortex_m-cycle_counter/
+#if defined(__arm__) || defined(__thumb__)
- FORCE_INLINE static void enableCycleCounter() {
- CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
+ // We want to have delay_cycle function with the lowest possible overhead, so we adjust at the function at runtime based on the current CPU best feature
+ typedef void (*DelayImpl)(uint32_t);
+ extern DelayImpl DelayCycleFnc;
- #if __CORTEX_M == 7
- DWT->LAR = 0xC5ACCE55; // Unlock DWT on the M7
- #endif
+ // I've measured 36 cycles on my system to call the cycle waiting method, but it shouldn't change much to have a bit more margin, it only consume a bit more flash
+ #define TRIP_POINT_FOR_CALLING_FUNCTION 40
- DWT->CYCCNT = 0;
- DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk;
+ // A simple recursive template class that output exactly one 'nop' of code per recursion
+ template struct NopWriter {
+ FORCE_INLINE static void build() {
+ __asm__ __volatile__("nop");
+ NopWriter::build();
}
+ };
+ // End the loop
+ template <> struct NopWriter<0> { FORCE_INLINE static void build() {} };
+
+ namespace Private {
+ // Split recursing template in 2 different class so we don't reach the maximum template instantiation depth limit
+ template struct Helper {
+ FORCE_INLINE static void build() {
+ DelayCycleFnc(N - 2); // Approximative cost of calling the function (might be off by one or 2 cycles)
+ }
+ };
- FORCE_INLINE volatile uint32_t getCycleCount() { return DWT->CYCCNT; }
+ template struct Helper {
+ FORCE_INLINE static void build() {
+ NopWriter::build();
+ }
+ };
- FORCE_INLINE static void DELAY_CYCLES(const uint32_t x) {
- const uint32_t endCycles = getCycleCount() + x;
- while (PENDING(getCycleCount(), endCycles)) {}
- }
+ template <> struct Helper {
+ FORCE_INLINE static void build() {}
+ };
- #else
-
- // https://blueprints.launchpad.net/gcc-arm-embedded/+spec/delay-cycles
-
- #define nop() __asm__ __volatile__("nop;\n\t":::)
-
- FORCE_INLINE static void __delay_4cycles(uint32_t cy) { // +1 cycle
- #if ARCH_PIPELINE_RELOAD_CYCLES < 2
- #define EXTRA_NOP_CYCLES A("nop")
- #else
- #define EXTRA_NOP_CYCLES ""
- #endif
-
- __asm__ __volatile__(
- A(".syntax unified") // is to prevent CM0,CM1 non-unified syntax
- L("1")
- A("subs %[cnt],#1")
- EXTRA_NOP_CYCLES
- A("bne 1b")
- : [cnt]"+r"(cy) // output: +r means input+output
- : // input:
- : "cc" // clobbers:
- );
+ }
+ // Select a behavior based on the constexpr'ness of the parameter
+ // If called with a compile-time parameter, then write as many NOP as required to reach the asked cycle count
+ // (there is some tripping point here to start looping when it's more profitable than gruntly executing NOPs)
+ // If not called from a compile-time parameter, fallback to a runtime loop counting version instead
+ template
+ struct SmartDelay {
+ FORCE_INLINE SmartDelay(int) {
+ if (Cycles == 0) return;
+ Private::Helper::build();
}
+ };
+ // Runtime version below. There is no way this would run under less than ~TRIP_POINT_FOR_CALLING_FUNCTION cycles
+ template
+ struct SmartDelay {
+ FORCE_INLINE SmartDelay(int v) { DelayCycleFnc(v); }
+ };
- // Delay in cycles
- FORCE_INLINE static void DELAY_CYCLES(uint32_t x) {
-
- if (__builtin_constant_p(x)) {
- #define MAXNOPS 4
-
- if (x <= (MAXNOPS)) {
- switch (x) { case 4: nop(); case 3: nop(); case 2: nop(); case 1: nop(); }
- }
- else { // because of +1 cycle inside delay_4cycles
- const uint32_t rem = (x - 1) % (MAXNOPS);
- switch (rem) { case 3: nop(); case 2: nop(); case 1: nop(); }
- if ((x = (x - 1) / (MAXNOPS)))
- __delay_4cycles(x); // if need more then 4 nop loop is more optimal
- }
- #undef MAXNOPS
- }
- else if ((x >>= 2))
- __delay_4cycles(x);
- }
- #undef nop
+ #define DELAY_CYCLES(X) do { SmartDelay _smrtdly_X(X); } while(0)
- #endif
+ // For delay in microseconds, no smart delay selection is required, directly call the delay function
+ // Teensy compiler is too old and does not accept smart delay compile-time / run-time selection correctly
+ #define DELAY_US(x) DelayCycleFnc((x) * ((F_CPU) / 1000000UL))
#elif defined(__AVR__)
@@ -144,18 +135,52 @@
}
#undef nop
+ // Delay in microseconds
+ #define DELAY_US(x) DELAY_CYCLES((x) * ((F_CPU) / 1000000UL))
+
#elif defined(__PLAT_LINUX__) || defined(ESP32)
- // specified inside platform
+ // DELAY_CYCLES specified inside platform
+ // Delay in microseconds
+ #define DELAY_US(x) DELAY_CYCLES((x) * ((F_CPU) / 1000000UL))
#else
#error "Unsupported MCU architecture"
#endif
-// Delay in nanoseconds
-#define DELAY_NS(x) DELAY_CYCLES((x) * ((F_CPU) / 1000000UL) / 1000UL)
+/**************************************************************
+ * Delay in nanoseconds. Requires the F_CPU macro.
+ * These macros follow avr-libc delay conventions.
+ *
+ * For AVR there are three possible operation modes, due to its
+ * slower clock speeds and thus coarser delay resolution. For
+ * example, when F_CPU = 16000000 the resolution is 62.5ns.
+ *
+ * Round up (default)
+ * Round up the delay according to the CPU clock resolution.
+ * e.g., 100 will give a delay of 2 cycles (125ns).
+ *
+ * Round down (DELAY_NS_ROUND_DOWN)
+ * Round down the delay according to the CPU clock resolution.
+ * e.g., 100 will be rounded down to 1 cycle (62.5ns).
+ *
+ * Nearest (DELAY_NS_ROUND_CLOSEST)
+ * Round the delay to the nearest number of clock cycles.
+ * e.g., 165 will be rounded up to 3 cycles (187.5ns) because
+ * it's closer to the requested delay than 2 cycle (125ns).
+ */
+
+#ifndef __AVR__
+ #undef DELAY_NS_ROUND_DOWN
+ #undef DELAY_NS_ROUND_CLOSEST
+#endif
-// Delay in microseconds
-#define DELAY_US(x) DELAY_CYCLES((x) * ((F_CPU) / 1000000UL))
+#if ENABLED(DELAY_NS_ROUND_DOWN)
+ #define DELAY_NS(x) DELAY_CYCLES((x) * ((F_CPU) / 1000000UL) / 1000UL) // floor
+#elif ENABLED(DELAY_NS_ROUND_CLOSEST)
+ #define DELAY_NS(x) DELAY_CYCLES(((x) * ((F_CPU) / 1000000UL) + 500) / 1000UL) // round
+#else
+ #define DELAY_NS(x) DELAY_CYCLES(((x) * ((F_CPU) / 1000000UL) + 999) / 1000UL) // "ceil"
+#endif
diff --git a/Marlin/src/HAL/shared/HAL_MinSerial.cpp b/Marlin/src/HAL/shared/HAL_MinSerial.cpp
new file mode 100644
index 000000000000..9dda5fdf8c67
--- /dev/null
+++ b/Marlin/src/HAL/shared/HAL_MinSerial.cpp
@@ -0,0 +1,33 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#include "HAL_MinSerial.h"
+
+#if ENABLED(POSTMORTEM_DEBUGGING)
+
+void HAL_min_serial_init_default() {}
+void HAL_min_serial_out_default(char ch) { SERIAL_CHAR(ch); }
+void (*HAL_min_serial_init)() = &HAL_min_serial_init_default;
+void (*HAL_min_serial_out)(char) = &HAL_min_serial_out_default;
+
+bool MinSerial::force_using_default_output = false;
+
+#endif
diff --git a/Marlin/src/HAL/shared/HAL_MinSerial.h b/Marlin/src/HAL/shared/HAL_MinSerial.h
new file mode 100644
index 000000000000..3089b8aa0618
--- /dev/null
+++ b/Marlin/src/HAL/shared/HAL_MinSerial.h
@@ -0,0 +1,79 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#pragma once
+
+#include "../../core/serial.h"
+#include
+
+// Serial stuff here
+// Inside an exception handler, the CPU state is not safe, we can't expect the handler to resume
+// and the software to continue. UART communication can't rely on later callback/interrupt as it might never happen.
+// So, you need to provide some method to send one byte to the usual UART with the interrupts disabled
+// By default, the method uses SERIAL_CHAR but it's 100% guaranteed to break (couldn't be worse than nothing...)7
+extern void (*HAL_min_serial_init)();
+extern void (*HAL_min_serial_out)(char ch);
+
+struct MinSerial {
+ static bool force_using_default_output;
+ // Serial output
+ static void TX(char ch) {
+ if (force_using_default_output)
+ SERIAL_CHAR(ch);
+ else
+ HAL_min_serial_out(ch);
+ }
+ // Send String through UART
+ static void TX(const char *s) { while (*s) TX(*s++); }
+ // Send a digit through UART
+ static void TXDigit(uint32_t d) {
+ if (d < 10) TX((char)(d+'0'));
+ else if (d < 16) TX((char)(d+'A'-10));
+ else TX('?');
+ }
+
+ // Send Hex number through UART
+ static void TXHex(uint32_t v) {
+ TX("0x");
+ for (uint8_t i = 0; i < 8; i++, v <<= 4)
+ TXDigit((v >> 28) & 0xF);
+ }
+
+ // Send Decimal number through UART
+ static void TXDec(uint32_t v) {
+ if (!v) {
+ TX('0');
+ return;
+ }
+
+ char nbrs[14];
+ char *p = &nbrs[0];
+ while (v != 0) {
+ *p++ = '0' + (v % 10);
+ v /= 10;
+ }
+ do {
+ p--;
+ TX(*p);
+ } while (p != &nbrs[0]);
+ }
+ static void init() { if (!force_using_default_output) HAL_min_serial_init(); }
+};
diff --git a/Marlin/src/HAL/shared/HAL_SPI.h b/Marlin/src/HAL/shared/HAL_SPI.h
index 59af5548064c..6611f9ec4e0f 100644
--- a/Marlin/src/HAL/shared/HAL_SPI.h
+++ b/Marlin/src/HAL/shared/HAL_SPI.h
@@ -71,10 +71,10 @@ void spiSend(uint8_t b);
uint8_t spiRec();
// Read from SPI into buffer
-void spiRead(uint8_t* buf, uint16_t nbyte);
+void spiRead(uint8_t *buf, uint16_t nbyte);
// Write token and then write from 512 byte buffer to SPI (for SD card)
-void spiSendBlock(uint8_t token, const uint8_t* buf);
+void spiSendBlock(uint8_t token, const uint8_t *buf);
// Begin SPI transaction, set clock, bit order, data mode
void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode);
@@ -87,7 +87,7 @@ void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode);
void spiSend(uint32_t chan, byte b);
// Write buffer to specified SPI channel
-void spiSend(uint32_t chan, const uint8_t* buf, size_t n);
+void spiSend(uint32_t chan, const uint8_t *buf, size_t n);
// Read single byte from specified SPI channel
uint8_t spiRec(uint32_t chan);
diff --git a/Marlin/src/HAL/shared/Marduino.h b/Marlin/src/HAL/shared/Marduino.h
index 3003f3cc2891..56be8d72118f 100644
--- a/Marlin/src/HAL/shared/Marduino.h
+++ b/Marlin/src/HAL/shared/Marduino.h
@@ -28,9 +28,9 @@
#undef DISABLED // Redefined by ESP32
#undef M_PI // Redefined by all
#undef _BV // Redefined by some
-#undef sq // Redefined by teensy3/wiring.h
#undef SBI // Redefined by arduino/const_functions.h
#undef CBI // Redefined by arduino/const_functions.h
+#undef sq // Redefined by teensy3/wiring.h
#undef UNUSED // Redefined by stm32f4xx_hal_def.h
#include // NOTE: If included earlier then this line is a NOOP
@@ -40,18 +40,16 @@
#undef _BV
#define _BV(b) (1UL << (b))
-
-#undef sq
-#define sq(x) ((x)*(x))
-
#ifndef SBI
- #define SBI(A,B) (A |= (1 << (B)))
+ #define SBI(A,B) (A |= _BV(B))
#endif
-
#ifndef CBI
- #define CBI(A,B) (A &= ~(1 << (B)))
+ #define CBI(A,B) (A &= ~_BV(B))
#endif
+#undef sq
+#define sq(x) ((x)*(x))
+
#ifndef __AVR__
#ifndef strchr_P // Some platforms define a macro (DUE, teensy35)
inline const char* strchr_P(const char *s, int c) { return strchr(s,c); }
@@ -83,3 +81,9 @@
#ifndef UNUSED
#define UNUSED(x) ((void)(x))
#endif
+
+#ifndef FORCE_INLINE
+ #define FORCE_INLINE inline __attribute__((always_inline))
+#endif
+
+#include "progmem.h"
diff --git a/Marlin/src/HAL/shared/backtrace/backtrace.cpp b/Marlin/src/HAL/shared/backtrace/backtrace.cpp
index 6cf5e055e151..ad88de8385ac 100644
--- a/Marlin/src/HAL/shared/backtrace/backtrace.cpp
+++ b/Marlin/src/HAL/shared/backtrace/backtrace.cpp
@@ -25,30 +25,32 @@
#include "unwinder.h"
#include "unwmemaccess.h"
-#include "../../../core/serial.h"
+#include "../HAL_MinSerial.h"
#include
// Dump a backtrace entry
-static bool UnwReportOut(void* ctx, const UnwReport* bte) {
+static bool UnwReportOut(void *ctx, const UnwReport *bte) {
int *p = (int*)ctx;
(*p)++;
- SERIAL_CHAR('#'); SERIAL_PRINT(*p, DEC); SERIAL_ECHOPGM(" : ");
- SERIAL_ECHOPGM(bte->name ? bte->name : "unknown"); SERIAL_ECHOPGM("@0x"); SERIAL_PRINT(bte->function, HEX);
- SERIAL_CHAR('+'); SERIAL_PRINT(bte->address - bte->function,DEC);
- SERIAL_ECHOPGM(" PC:"); SERIAL_PRINT(bte->address,HEX); SERIAL_CHAR('\n');
+ const uint32_t a = bte->address, f = bte->function;
+ MinSerial::TX('#'); MinSerial::TXDec(*p); MinSerial::TX(" : ");
+ MinSerial::TX(bte->name?:"unknown"); MinSerial::TX('@'); MinSerial::TXHex(f);
+ MinSerial::TX('+'); MinSerial::TXDec(a - f);
+ MinSerial::TX(" PC:"); MinSerial::TXHex(a);
+ MinSerial::TX('\n');
return true;
}
#ifdef UNW_DEBUG
- void UnwPrintf(const char* format, ...) {
+ void UnwPrintf(const char *format, ...) {
char dest[256];
va_list argptr;
va_start(argptr, format);
vsprintf(dest, format, argptr);
va_end(argptr);
- TX(&dest[0]);
+ MinSerial::TX(&dest[0]);
}
#endif
@@ -63,10 +65,10 @@ static const UnwindCallbacks UnwCallbacks = {
#endif
};
+// Perform a backtrace to the serial port
void backtrace() {
- UnwindFrame btf;
- uint32_t sp = 0, lr = 0, pc = 0;
+ unsigned long sp = 0, lr = 0, pc = 0;
// Capture the values of the registers to perform the traceback
__asm__ __volatile__ (
@@ -79,6 +81,12 @@ void backtrace() {
::
);
+ backtrace_ex(sp, lr, pc);
+}
+
+void backtrace_ex(unsigned long sp, unsigned long lr, unsigned long pc) {
+ UnwindFrame btf;
+
// Fill the traceback structure
btf.sp = sp;
btf.fp = btf.sp;
@@ -86,7 +94,7 @@ void backtrace() {
btf.pc = pc | 1; // Force Thumb, as CORTEX only support it
// Perform a backtrace
- SERIAL_ERROR_MSG("Backtrace:");
+ MinSerial::TX("Backtrace:");
int ctr = 0;
UnwindStart(&btf, &UnwCallbacks, &ctr);
}
@@ -95,4 +103,4 @@ void backtrace() {
void backtrace() {}
-#endif
+#endif // __arm__ || __thumb__
diff --git a/Marlin/src/HAL/shared/backtrace/backtrace.h b/Marlin/src/HAL/shared/backtrace/backtrace.h
index fccadedaa543..5d2ba601a071 100644
--- a/Marlin/src/HAL/shared/backtrace/backtrace.h
+++ b/Marlin/src/HAL/shared/backtrace/backtrace.h
@@ -23,3 +23,6 @@
// Perform a backtrace to the serial port
void backtrace();
+
+// Perform a backtrace to the serial port
+void backtrace_ex(unsigned long sp, unsigned long lr, unsigned long pc);
diff --git a/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp b/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp
index bfc062af2090..f1ee81ed4acb 100644
--- a/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp
+++ b/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp
@@ -128,11 +128,8 @@ static UnwResult UnwTabStateInit(const UnwindCallbacks *cb, UnwTabState *ucb, ui
* Execute unwinding instructions
*/
static UnwResult UnwTabExecuteInstructions(const UnwindCallbacks *cb, UnwTabState *ucb) {
-
int instruction;
- uint32_t mask;
- uint32_t reg;
- uint32_t vsp;
+ uint32_t mask, reg, vsp;
/* Consume all instruction byte */
while ((instruction = UnwTabGetNextInstruction(cb, ucb)) != -1) {
@@ -140,12 +137,12 @@ static UnwResult UnwTabExecuteInstructions(const UnwindCallbacks *cb, UnwTabStat
if ((instruction & 0xC0) == 0x00) { // ARM_EXIDX_CMD_DATA_POP
/* vsp = vsp + (xxxxxx << 2) + 4 */
ucb->vrs[13] += ((instruction & 0x3F) << 2) + 4;
- } else
- if ((instruction & 0xC0) == 0x40) { // ARM_EXIDX_CMD_DATA_PUSH
+ }
+ else if ((instruction & 0xC0) == 0x40) { // ARM_EXIDX_CMD_DATA_PUSH
/* vsp = vsp - (xxxxxx << 2) - 4 */
ucb->vrs[13] -= ((instruction & 0x3F) << 2) - 4;
- } else
- if ((instruction & 0xF0) == 0x80) {
+ }
+ else if ((instruction & 0xF0) == 0x80) {
/* pop under mask {r15-r12},{r11-r4} or refuse to unwind */
instruction = instruction << 8 | UnwTabGetNextInstruction(cb, ucb);
@@ -171,17 +168,17 @@ static UnwResult UnwTabExecuteInstructions(const UnwindCallbacks *cb, UnwTabStat
}
/* Patch up the vrs sp if it was in the mask */
- if ((instruction & (1 << (13 - 4))) != 0)
+ if (instruction & (1 << (13 - 4)))
ucb->vrs[13] = vsp;
-
- } else
- if ((instruction & 0xF0) == 0x90 && // ARM_EXIDX_CMD_REG_TO_SP
- instruction != 0x9D &&
- instruction != 0x9F) {
+ }
+ else if ((instruction & 0xF0) == 0x90 // ARM_EXIDX_CMD_REG_TO_SP
+ && instruction != 0x9D
+ && instruction != 0x9F
+ ) {
/* vsp = r[nnnn] */
ucb->vrs[13] = ucb->vrs[instruction & 0x0F];
- } else
- if ((instruction & 0xF0) == 0xA0) { // ARM_EXIDX_CMD_REG_POP
+ }
+ else if ((instruction & 0xF0) == 0xA0) { // ARM_EXIDX_CMD_REG_POP
/* pop r4-r[4+nnn] or pop r4-r[4+nnn], r14*/
vsp = ucb->vrs[13];
@@ -204,8 +201,8 @@ static UnwResult UnwTabExecuteInstructions(const UnwindCallbacks *cb, UnwTabStat
ucb->vrs[13] = vsp;
- } else
- if (instruction == 0xB0) { // ARM_EXIDX_CMD_FINISH
+ }
+ else if (instruction == 0xB0) { // ARM_EXIDX_CMD_FINISH
/* finished */
if (ucb->vrs[15] == 0)
ucb->vrs[15] = ucb->vrs[14];
@@ -213,8 +210,8 @@ static UnwResult UnwTabExecuteInstructions(const UnwindCallbacks *cb, UnwTabStat
/* All done unwinding */
return UNWIND_SUCCESS;
- } else
- if (instruction == 0xB1) { // ARM_EXIDX_CMD_REG_POP
+ }
+ else if (instruction == 0xB1) { // ARM_EXIDX_CMD_REG_POP
/* pop register under mask {r3,r2,r1,r0} */
vsp = ucb->vrs[13];
mask = UnwTabGetNextInstruction(cb, ucb);
@@ -234,16 +231,15 @@ static UnwResult UnwTabExecuteInstructions(const UnwindCallbacks *cb, UnwTabStat
}
ucb->vrs[13] = (uint32_t)vsp;
- } else
- if (instruction == 0xB2) { // ARM_EXIDX_CMD_DATA_POP
+ }
+ else if (instruction == 0xB2) { // ARM_EXIDX_CMD_DATA_POP
/* vps = vsp + 0x204 + (uleb128 << 2) */
ucb->vrs[13] += 0x204 + (UnwTabGetNextInstruction(cb, ucb) << 2);
-
- } else
- if (instruction == 0xB3 || // ARM_EXIDX_CMD_VFP_POP
- instruction == 0xC8 ||
- instruction == 0xC9) {
-
+ }
+ else if (instruction == 0xB3 // ARM_EXIDX_CMD_VFP_POP
+ || instruction == 0xC8
+ || instruction == 0xC9
+ ) {
/* pop VFP double-precision registers */
vsp = ucb->vrs[13];
@@ -266,27 +262,20 @@ static UnwResult UnwTabExecuteInstructions(const UnwindCallbacks *cb, UnwTabStat
}
ucb->vrs[13] = vsp;
-
- } else
- if ((instruction & 0xF8) == 0xB8 ||
- (instruction & 0xF8) == 0xD0) {
-
+ }
+ else if ((instruction & 0xF8) == 0xB8 || (instruction & 0xF8) == 0xD0) {
/* Pop VFP double precision registers D[8]-D[8+nnn] */
ucb->vrs[14] = 0x80 | (instruction & 0x07);
-
- if ((instruction & 0xF8) == 0xD0) {
+ if ((instruction & 0xF8) == 0xD0)
ucb->vrs[14] = 1 << 17;
- }
-
- } else
+ }
+ else
return UNWIND_UNSUPPORTED_DWARF_INSTR;
}
-
return UNWIND_SUCCESS;
}
static inline __attribute__((always_inline)) uint32_t read_psp() {
-
/* Read the current PSP and return its value as a pointer */
uint32_t psp;
diff --git a/Marlin/src/HAL/shared/backtrace/unwinder.h b/Marlin/src/HAL/shared/backtrace/unwinder.h
index 157808d540da..8692c7a1aa50 100644
--- a/Marlin/src/HAL/shared/backtrace/unwinder.h
+++ b/Marlin/src/HAL/shared/backtrace/unwinder.h
@@ -114,7 +114,7 @@ typedef struct {
* report function maybe called again in future. If false is returned,
* unwinding will stop with UnwindStart() returning UNWIND_TRUNCATED.
*/
-typedef bool (*UnwindReportFunc)(void* data, const UnwReport* bte);
+typedef bool (*UnwindReportFunc)(void *data, const UnwReport *bte);
/** Structure that holds memory callback function pointers.
*/
diff --git a/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp b/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp
index 5ca46f98865b..2bde1e208d95 100644
--- a/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp
+++ b/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp
@@ -41,27 +41,16 @@
#define START_FLASH_ADDR 0x00000000
#define END_FLASH_ADDR 0x00080000
-#elif 0
-
- // For STM32F103CBT6
- // SRAM (0x20000000 - 0x20005000) (20kb)
- // FLASH (0x00000000 - 0x00020000) (128kb)
- //
- #define START_SRAM_ADDR 0x20000000
- #define END_SRAM_ADDR 0x20005000
- #define START_FLASH_ADDR 0x00000000
- #define END_FLASH_ADDR 0x00020000
-
#elif defined(__STM32F1__) || defined(STM32F1xx) || defined(STM32F0xx)
// For STM32F103ZET6/STM32F103VET6/STM32F0xx
// SRAM (0x20000000 - 0x20010000) (64kb)
- // FLASH (0x00000000 - 0x00080000) (512kb)
+ // FLASH (0x08000000 - 0x08080000) (512kb)
//
#define START_SRAM_ADDR 0x20000000
#define END_SRAM_ADDR 0x20010000
- #define START_FLASH_ADDR 0x00000000
- #define END_FLASH_ADDR 0x00080000
+ #define START_FLASH_ADDR 0x08000000
+ #define END_FLASH_ADDR 0x08080000
#elif defined(STM32F4) || defined(STM32F4xx)
@@ -142,20 +131,57 @@
#define START_FLASH_ADDR 0x00000000
#define END_FLASH_ADDR 0x00100000
+#else
+ // Generic ARM code, that's testing if an access to the given address would cause a fault or not
+ // It can't guarantee an address is in RAM or Flash only, but we usually don't care
+
+ #define NVIC_FAULT_STAT 0xE000ED28 // Configurable Fault Status Reg.
+ #define NVIC_CFG_CTRL 0xE000ED14 // Configuration Control Register
+ #define NVIC_FAULT_STAT_BFARV 0x00008000 // BFAR is valid
+ #define NVIC_CFG_CTRL_BFHFNMIGN 0x00000100 // Ignore bus fault in NMI/fault
+ #define HW_REG(X) (*((volatile unsigned long *)(X)))
+
+ static bool validate_addr(uint32_t read_address) {
+ bool works = true;
+ uint32_t intDisabled = 0;
+ // Read current interrupt state
+ __asm__ __volatile__ ("MRS %[result], PRIMASK\n\t" : [result]"=r"(intDisabled) :: ); // 0 is int enabled, 1 for disabled
+
+ // Clear bus fault indicator first (write 1 to clear)
+ HW_REG(NVIC_FAULT_STAT) |= NVIC_FAULT_STAT_BFARV;
+ // Ignore bus fault interrupt
+ HW_REG(NVIC_CFG_CTRL) |= NVIC_CFG_CTRL_BFHFNMIGN;
+ // Disable interrupts if not disabled previously
+ if (!intDisabled) __asm__ __volatile__ ("CPSID f");
+ // Probe address
+ *(volatile uint32_t*)read_address;
+ // Check if a fault happened
+ if ((HW_REG(NVIC_FAULT_STAT) & NVIC_FAULT_STAT_BFARV) != 0)
+ works = false;
+ // Enable interrupts again if previously disabled
+ if (!intDisabled) __asm__ __volatile__ ("CPSIE f");
+ // Enable fault interrupt flag
+ HW_REG(NVIC_CFG_CTRL) &= ~NVIC_CFG_CTRL_BFHFNMIGN;
+
+ return works;
+ }
+
#endif
-static bool validate_addr(uint32_t addr) {
+#ifdef START_SRAM_ADDR
+ static bool validate_addr(uint32_t addr) {
- // Address must be in SRAM range
- if (addr >= START_SRAM_ADDR && addr < END_SRAM_ADDR)
- return true;
+ // Address must be in SRAM range
+ if (addr >= START_SRAM_ADDR && addr < END_SRAM_ADDR)
+ return true;
- // Or in FLASH range
- if (addr >= START_FLASH_ADDR && addr < END_FLASH_ADDR)
- return true;
+ // Or in FLASH range
+ if (addr >= START_FLASH_ADDR && addr < END_FLASH_ADDR)
+ return true;
- return false;
-}
+ return false;
+ }
+#endif
bool UnwReadW(const uint32_t a, uint32_t *v) {
if (!validate_addr(a))
diff --git a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp
new file mode 100644
index 000000000000..124f0b7c43c6
--- /dev/null
+++ b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp
@@ -0,0 +1,379 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ * Copyright (c) 2020 Cyril Russo
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+
+/***************************************************************************
+ * ARM CPU Exception handler
+ ***************************************************************************/
+
+#if defined(__arm__) || defined(__thumb__)
+
+
+/*
+ On ARM CPUs exception handling is quite powerful.
+
+ By default, upon a crash, the CPU enters the handlers that have a higher priority than any other interrupts,
+ so, in effect, no (real) interrupt can "interrupt" the handler (it's acting like if interrupts were disabled).
+
+ If the handler is not called as re-entrant (that is, if the crash is not happening inside an interrupt or an handler),
+ then it'll patch the return address to a dumping function (resume_from_fault) and save the crash state.
+ The CPU will exit the handler and, as such, re-allow the other interrupts, and jump to the dumping function.
+ In this function, the usual serial port (USB / HW) will be used to dump the crash (no special configuration required).
+
+ The only case where it requires hardware UART is when it's crashing in an interrupt or a crash handler.
+ In that case, instead of returning to the resume_from_fault function (and thus, re-enabling interrupts),
+ it jumps to this function directly (so with interrupts disabled), after changing the behavior of the serial output
+ wrapper to use the HW uart (and in effect, calling MinSerial::init which triggers a warning if you are using
+ a USB serial port).
+
+ In the case you have a USB serial port, this part will be disabled, and only that part (so that's the reason for
+ the warning).
+ This means that you can't have a crash report if the crash happens in an interrupt or an handler if you are using
+ a USB serial port since it's physically impossible.
+ You will get a crash report in all other cases.
+*/
+
+#include "exception_hook.h"
+#include "../backtrace/backtrace.h"
+#include "../HAL_MinSerial.h"
+
+#define HW_REG(X) (*((volatile unsigned long *)(X)))
+
+// Default function use the CPU VTOR register to get the vector table.
+// Accessing the CPU VTOR register is done in assembly since it's the only way that's common to all current tool
+unsigned long get_vtor() { return HW_REG(0xE000ED08); } // Even if it looks like an error, it is not an error
+void * hook_get_hardfault_vector_address(unsigned vtor) { return (void*)(vtor + 0x03); }
+void * hook_get_memfault_vector_address(unsigned vtor) { return (void*)(vtor + 0x04); }
+void * hook_get_busfault_vector_address(unsigned vtor) { return (void*)(vtor + 0x05); }
+void * hook_get_usagefault_vector_address(unsigned vtor) { return (void*)(vtor + 0x06); }
+void * hook_get_reserved_vector_address(unsigned vtor) { return (void*)(vtor + 0x07); }
+
+// Common exception frame for ARM, should work for all ARM CPU
+// Described here (modified for convenience): https://interrupt.memfault.com/blog/cortex-m-fault-debug
+struct __attribute__((packed)) ContextStateFrame {
+ uint32_t r0;
+ uint32_t r1;
+ uint32_t r2;
+ uint32_t r3;
+ uint32_t r12;
+ uint32_t lr;
+ uint32_t pc;
+ uint32_t xpsr;
+};
+
+struct __attribute__((packed)) ContextSavedFrame {
+ uint32_t R0;
+ uint32_t R1;
+ uint32_t R2;
+ uint32_t R3;
+ uint32_t R12;
+ uint32_t LR;
+ uint32_t PC;
+ uint32_t XPSR;
+
+ uint32_t CFSR;
+ uint32_t HFSR;
+ uint32_t DFSR;
+ uint32_t AFSR;
+ uint32_t MMAR;
+ uint32_t BFAR;
+
+ uint32_t ESP;
+ uint32_t ELR;
+};
+
+#if DISABLED(STM32F0xx)
+ extern "C"
+ __attribute__((naked)) void CommonHandler_ASM() {
+ __asm__ __volatile__ (
+ // Bit 2 of LR tells which stack pointer to use (either main or process, only main should be used anyway)
+ "tst lr, #4\n"
+ "ite eq\n"
+ "mrseq r0, msp\n"
+ "mrsne r0, psp\n"
+ // Save the LR in use when being interrupted
+ "mov r1, lr\n"
+ // Get the exception number from the ICSR register
+ "ldr r2, =0xE000ED00\n"
+ "ldr r2, [r2, #4]\n"
+ "b CommonHandler_C\n"
+ );
+ }
+#else // Cortex M0 does not support conditional mov and testing with a constant, so let's have a specific handler for it
+ extern "C"
+ __attribute__((naked)) void CommonHandler_ASM() {
+ __asm__ __volatile__ (
+ ".syntax unified\n"
+ // Save the LR in use when being interrupted
+ "mov r1, lr\n"
+ // Get the exception number from the ICSR register
+ "ldr r2, =0xE000ED00\n"
+ "ldr r2, [r2, #4]\n"
+ "movs r0, #4\n"
+ "tst r1, r0\n"
+ "beq _MSP\n"
+ "mrs r0, psp\n"
+ "b CommonHandler_C\n"
+ "_MSP:\n"
+ "mrs r0, msp\n"
+ "b CommonHandler_C\n"
+ );
+ }
+
+ #if DISABLED(DYNAMIC_VECTORTABLE) // Cortex M0 requires the handler's address to be within 32kB to the actual function to be able to branch to it
+ extern "C" {
+ void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __exc_hardfault();
+ void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __exc_busfault();
+ void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __exc_usagefault();
+ void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __exc_memmanage();
+ void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __exc_nmi();
+ void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __stm32reservedexception7();
+ void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __stm32reservedexception8();
+ void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __stm32reservedexception9();
+ void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __stm32reservedexception10();
+ void __attribute__((naked, alias("CommonHandler_ASM"), nothrow)) __stm32reservedexception13();
+ }
+ //TODO When going off from libmaple, you'll need to replace those by the one from STM32/HAL_MinSerial.cpp
+ #endif
+#endif
+
+// Must be a macro to avoid creating a function frame
+#define HALT_IF_DEBUGGING() \
+ do { \
+ if (HW_REG(0xE000EDF0) & _BV(0)) { \
+ __asm("bkpt 1"); \
+ } \
+} while (0)
+
+// Resume from a fault (if possible) so we can still use interrupt based code for serial output
+// In that case, we will not jump back to the faulty code, but instead to a dumping code and then a
+// basic loop with watchdog calling or manual resetting
+static ContextSavedFrame savedFrame;
+static uint8_t lastCause;
+bool resume_from_fault() {
+ static const char* causestr[] = { "Thread", "Rsvd", "NMI", "Hard", "Mem", "Bus", "Usage", "7", "8", "9", "10", "SVC", "Dbg", "13", "PendSV", "SysTk", "IRQ" };
+ // Reinit the serial link (might only work if implemented in each of your boards)
+ MinSerial::init();
+
+ MinSerial::TX("\n\n## Software Fault detected ##\n");
+ MinSerial::TX("Cause: "); MinSerial::TX(causestr[min(lastCause, (uint8_t)16)]); MinSerial::TX('\n');
+
+ MinSerial::TX("R0 : "); MinSerial::TXHex(savedFrame.R0); MinSerial::TX('\n');
+ MinSerial::TX("R1 : "); MinSerial::TXHex(savedFrame.R1); MinSerial::TX('\n');
+ MinSerial::TX("R2 : "); MinSerial::TXHex(savedFrame.R2); MinSerial::TX('\n');
+ MinSerial::TX("R3 : "); MinSerial::TXHex(savedFrame.R3); MinSerial::TX('\n');
+ MinSerial::TX("R12 : "); MinSerial::TXHex(savedFrame.R12); MinSerial::TX('\n');
+ MinSerial::TX("LR : "); MinSerial::TXHex(savedFrame.LR); MinSerial::TX('\n');
+ MinSerial::TX("PC : "); MinSerial::TXHex(savedFrame.PC); MinSerial::TX('\n');
+ MinSerial::TX("PSR : "); MinSerial::TXHex(savedFrame.XPSR); MinSerial::TX('\n');
+
+ // Configurable Fault Status Register
+ // Consists of MMSR, BFSR and UFSR
+ MinSerial::TX("CFSR : "); MinSerial::TXHex(savedFrame.CFSR); MinSerial::TX('\n');
+
+ // Hard Fault Status Register
+ MinSerial::TX("HFSR : "); MinSerial::TXHex(savedFrame.HFSR); MinSerial::TX('\n');
+
+ // Debug Fault Status Register
+ MinSerial::TX("DFSR : "); MinSerial::TXHex(savedFrame.DFSR); MinSerial::TX('\n');
+
+ // Auxiliary Fault Status Register
+ MinSerial::TX("AFSR : "); MinSerial::TXHex(savedFrame.AFSR); MinSerial::TX('\n');
+
+ // Read the Fault Address Registers. These may not contain valid values.
+ // Check BFARVALID/MMARVALID to see if they are valid values
+ // MemManage Fault Address Register
+ MinSerial::TX("MMAR : "); MinSerial::TXHex(savedFrame.MMAR); MinSerial::TX('\n');
+
+ // Bus Fault Address Register
+ MinSerial::TX("BFAR : "); MinSerial::TXHex(savedFrame.BFAR); MinSerial::TX('\n');
+
+ MinSerial::TX("ExcLR: "); MinSerial::TXHex(savedFrame.ELR); MinSerial::TX('\n');
+ MinSerial::TX("ExcSP: "); MinSerial::TXHex(savedFrame.ESP); MinSerial::TX('\n');
+
+ // The stack pointer is pushed by 8 words upon entering an exception, so we need to revert this
+ backtrace_ex(savedFrame.ESP + 8*4, savedFrame.LR, savedFrame.PC);
+
+ // Call the last resort function here
+ hook_last_resort_func();
+
+ const uint32_t start = millis(), end = start + 100; // 100ms should be enough
+ // We need to wait for the serial buffers to be output but we don't know for how long
+ // So we'll just need to refresh the watchdog for a while and then stop for the system to reboot
+ uint32_t last = start;
+ while (PENDING(last, end)) {
+ watchdog_refresh();
+ while (millis() == last) { /* nada */ }
+ last = millis();
+ MinSerial::TX('.');
+ }
+
+ // Reset now by reinstantiating the bootloader's vector table
+ HW_REG(0xE000ED08) = 0;
+ // Restart watchdog
+ #if DISABLED(USE_WATCHDOG)
+ // No watchdog, let's perform ARMv7 reset instead by writing to AIRCR register with VECTKEY set to SYSRESETREQ
+ HW_REG(0xE000ED0C) = (HW_REG(0xE000ED0C) & 0x0000FFFF) | 0x05FA0004;
+ #endif
+
+ while(1) {} // Bad luck, nothing worked
+}
+
+// Make sure the compiler does not optimize the frame argument away
+extern "C"
+__attribute__((optimize("O0")))
+void CommonHandler_C(ContextStateFrame * frame, unsigned long lr, unsigned long cause) {
+
+ // If you are using it'll stop here
+ HALT_IF_DEBUGGING();
+
+ // Save the state to backtrace later on (don't call memcpy here since the stack can be corrupted)
+ savedFrame.R0 = frame->r0;
+ savedFrame.R1 = frame->r1;
+ savedFrame.R2 = frame->r2;
+ savedFrame.R3 = frame->r3;
+ savedFrame.R12 = frame->r12;
+ savedFrame.LR = frame->lr;
+ savedFrame.PC = frame->pc;
+ savedFrame.XPSR= frame->xpsr;
+ lastCause = cause & 0x1FF;
+
+ volatile uint32_t &CFSR = HW_REG(0xE000ED28);
+ savedFrame.CFSR = CFSR;
+ savedFrame.HFSR = HW_REG(0xE000ED2C);
+ savedFrame.DFSR = HW_REG(0xE000ED30);
+ savedFrame.AFSR = HW_REG(0xE000ED3C);
+ savedFrame.MMAR = HW_REG(0xE000ED34);
+ savedFrame.BFAR = HW_REG(0xE000ED38);
+ savedFrame.ESP = (unsigned long)frame; // Even on return, this should not be overwritten by the CPU
+ savedFrame.ELR = lr;
+
+ // First check if we can resume from this exception to our own handler safely
+ // If we can, then we don't need to disable interrupts and the usual serial code
+ // can be used
+
+ //const uint32_t non_usage_fault_mask = 0x0000FFFF;
+ //const bool non_usage_fault_occurred = (CFSR & non_usage_fault_mask) != 0;
+ // the bottom 8 bits of the xpsr hold the exception number of the
+ // executing exception or 0 if the processor is in Thread mode
+ const bool faulted_from_exception = ((frame->xpsr & 0xFF) != 0);
+ if (!faulted_from_exception) { // Not sure about the non_usage_fault, we want to try anyway, don't we ? && !non_usage_fault_occurred)
+ // Try to resume to our handler here
+ CFSR |= CFSR; // The ARM programmer manual says you must write to 1 all fault bits to clear them so this instruction is correct
+ // The frame will not be valid when returning anymore, let's clean it
+ savedFrame.CFSR = 0;
+
+ frame->pc = (uint32_t)resume_from_fault; // Patch where to return to
+ frame->lr = 0xDEADBEEF; // If our handler returns (it shouldn't), let's make it trigger an exception immediately
+ frame->xpsr = _BV(24); // Need to clean the PSR register to thumb II only
+ MinSerial::force_using_default_output = true;
+ return; // The CPU will resume in our handler hopefully, and we'll try to use default serial output
+ }
+
+ // Sorry, we need to emergency code here since the fault is too dangerous to recover from
+ MinSerial::force_using_default_output = false;
+ resume_from_fault();
+}
+
+void hook_cpu_exceptions() {
+ #if ENABLED(DYNAMIC_VECTORTABLE)
+ // On ARM 32bits CPU, the vector table is like this:
+ // 0x0C => Hardfault
+ // 0x10 => MemFault
+ // 0x14 => BusFault
+ // 0x18 => UsageFault
+
+ // Unfortunately, it's usually run from flash, and we can't write to flash here directly to hook our instruction
+ // We could set an hardware breakpoint, and hook on the fly when it's being called, but this
+ // is hard to get right and would probably break debugger when attached
+
+ // So instead, we'll allocate a new vector table filled with the previous value except
+ // for the fault we are interested in.
+ // Now, comes the issue to figure out what is the current vector table size
+ // There is nothing telling us what is the vector table as it's per-cpu vendor specific.
+ // BUT: we are being called at the end of the setup, so we assume the setup is done
+ // Thus, we can read the current vector table until we find an address that's not in flash, and it would mark the
+ // end of the vector table (skipping the fist entry obviously)
+ // The position of the program in flash is expected to be at 0x08xxx xxxx on all known platform for ARM and the
+ // flash size is available via register 0x1FFFF7E0 on STM32 family, but it's not the case for all ARM boards
+ // (accessing this register might trigger a fault if it's not implemented).
+
+ // So we'll simply mask the top 8 bits of the first handler as an hint of being in the flash or not -that's poor and will
+ // probably break if the flash happens to be more than 128MB, but in this case, we are not magician, we need help from outside.
+
+ unsigned long *vecAddr = (unsigned long*)get_vtor();
+ SERIAL_ECHOPGM("Vector table addr: ");
+ SERIAL_PRINTLN(get_vtor(), HEX);
+
+ #ifdef VECTOR_TABLE_SIZE
+ uint32_t vec_size = VECTOR_TABLE_SIZE;
+ alignas(128) static unsigned long vectable[VECTOR_TABLE_SIZE] ;
+ #else
+ #ifndef IS_IN_FLASH
+ #define IS_IN_FLASH(X) (((unsigned long)X & 0xFF000000) == 0x08000000)
+ #endif
+
+ // When searching for the end of the vector table, this acts as a limit not to overcome
+ #ifndef VECTOR_TABLE_SENTINEL
+ #define VECTOR_TABLE_SENTINEL 80
+ #endif
+
+ // Find the vector table size
+ uint32_t vec_size = 1;
+ while (IS_IN_FLASH(vecAddr[vec_size]) && vec_size < VECTOR_TABLE_SENTINEL)
+ vec_size++;
+
+ // We failed to find a valid vector table size, let's abort hooking up
+ if (vec_size == VECTOR_TABLE_SENTINEL) return;
+ // Poor method that's wasting RAM here, but allocating with malloc and alignment would be worst
+ // 128 bytes alignement is required for writing the VTOR register
+ alignas(128) static unsigned long vectable[VECTOR_TABLE_SENTINEL];
+
+ SERIAL_ECHOPGM("Detected vector table size: ");
+ SERIAL_PRINTLN(vec_size, HEX);
+ #endif
+
+ uint32_t defaultFaultHandler = vecAddr[(unsigned)7];
+ // Copy the current vector table into the new table
+ for (uint32_t i = 0; i < vec_size; i++) {
+ vectable[i] = vecAddr[i];
+ // Replace all default handler by our own handler
+ if (vectable[i] == defaultFaultHandler)
+ vectable[i] = (unsigned long)&CommonHandler_ASM;
+ }
+
+ // Let's hook now with our functions
+ vectable[(unsigned long)hook_get_hardfault_vector_address(0)] = (unsigned long)&CommonHandler_ASM;
+ vectable[(unsigned long)hook_get_memfault_vector_address(0)] = (unsigned long)&CommonHandler_ASM;
+ vectable[(unsigned long)hook_get_busfault_vector_address(0)] = (unsigned long)&CommonHandler_ASM;
+ vectable[(unsigned long)hook_get_usagefault_vector_address(0)] = (unsigned long)&CommonHandler_ASM;
+
+ // Finally swap with our own vector table
+ // This is supposed to be atomic, but let's do that with interrupt disabled
+
+ HW_REG(0xE000ED08) = (unsigned long)vectable | _BV32(29); // 29th bit is for telling the CPU the table is now in SRAM (should be present already)
+
+ SERIAL_ECHOLNPGM("Installed fault handlers");
+ #endif
+}
+
+#endif // __arm__ || __thumb__
diff --git a/Marlin/src/HAL/shared/cpu_exception/exception_hook.cpp b/Marlin/src/HAL/shared/cpu_exception/exception_hook.cpp
new file mode 100644
index 000000000000..93e80f3e8524
--- /dev/null
+++ b/Marlin/src/HAL/shared/cpu_exception/exception_hook.cpp
@@ -0,0 +1,28 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#include "exception_hook.h"
+
+void * __attribute__((weak)) hook_get_hardfault_vector_address(unsigned) { return 0; }
+void * __attribute__((weak)) hook_get_memfault_vector_address(unsigned) { return 0; }
+void * __attribute__((weak)) hook_get_busfault_vector_address(unsigned) { return 0; }
+void * __attribute__((weak)) hook_get_usagefault_vector_address(unsigned) { return 0; }
+void __attribute__((weak)) hook_last_resort_func() {}
diff --git a/Marlin/src/HAL/shared/cpu_exception/exception_hook.h b/Marlin/src/HAL/shared/cpu_exception/exception_hook.h
new file mode 100644
index 000000000000..70d943470457
--- /dev/null
+++ b/Marlin/src/HAL/shared/cpu_exception/exception_hook.h
@@ -0,0 +1,54 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#pragma once
+
+/* Here is the expected behavior of a system producing a CPU exception with this hook installed:
+ 1. Before the system is crashed
+ 1.1 Upon validation (not done yet in this code, but we could be using DEBUG flags here to allow/disallow hooking)
+ 1.2 Install the hook by overwriting the vector table exception handler with the hooked function
+ 2. Upon system crash (for example, by a dereference of a NULL pointer or anything else)
+ 2.1 The CPU triggers its exception and jump into the vector table for the exception type
+ 2.2 Instead of finding the default handler, it finds the updated pointer to our hook
+ 2.3 The CPU jumps into our hook function (likely a naked function to keep all information about crash point intact)
+ 2.4 The hook (naked) function saves the important registers (stack pointer, program counter, current mode) and jumps to a common exception handler (in C)
+ 2.5 The common exception handler dumps the registers on the serial link and perform a backtrace around the crashing point
+ 2.6 Once the backtrace is performed the last resort function is called (platform specific).
+ On some platform with a LCD screen, this might display the crash information as a QR code or as text for the
+ user to capture by taking a picture
+ 2.7 The CPU is reset and/or halted by triggering a debug breakpoint if a debugger is attached */
+
+// Hook into CPU exception interrupt table to call the backtracing code upon an exception
+// Most platform will simply do nothing here, but those who can will install/overwrite the default exception handler
+// with a more performant exception handler
+void hook_cpu_exceptions();
+
+// Some platform might deal without a hard fault handler, in that case, return 0 in your platform here or skip implementing it
+void * __attribute__((weak)) hook_get_hardfault_vector_address(unsigned base_address);
+// Some platform might deal without a memory management fault handler, in that case, return 0 in your platform here or skip implementing it
+void * __attribute__((weak)) hook_get_memfault_vector_address(unsigned base_address);
+// Some platform might deal without a bus fault handler, in that case, return 0 in your platform here or skip implementing it
+void * __attribute__((weak)) hook_get_busfault_vector_address(unsigned base_address);
+// Some platform might deal without a usage fault handler, in that case, return 0 in your platform here or skip implementing it
+void * __attribute__((weak)) hook_get_usagefault_vector_address(unsigned base_address);
+
+// Last resort function that can be called after the exception handler was called.
+void __attribute__((weak)) hook_last_resort_func();
diff --git a/Marlin/src/HAL/shared/eeprom_api.h b/Marlin/src/HAL/shared/eeprom_api.h
index 6445f7a4aae4..1f38639930dc 100644
--- a/Marlin/src/HAL/shared/eeprom_api.h
+++ b/Marlin/src/HAL/shared/eeprom_api.h
@@ -45,11 +45,11 @@ class PersistentStore {
// Read one or more bytes of data and update the CRC
// Return 'true' on read error
- static bool read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing=true);
+ static bool read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing=true);
// Write one or more bytes of data
// Return 'true' on write error
- static inline bool write_data(const int pos, const uint8_t* value, const size_t size=sizeof(uint8_t)) {
+ static inline bool write_data(const int pos, const uint8_t *value, const size_t size=sizeof(uint8_t)) {
int data_pos = pos;
uint16_t crc = 0;
return write_data(data_pos, value, size, &crc);
@@ -61,7 +61,7 @@ class PersistentStore {
// Read one or more bytes of data
// Return 'true' on read error
- static inline bool read_data(const int pos, uint8_t* value, const size_t size=1) {
+ static inline bool read_data(const int pos, uint8_t *value, const size_t size=1) {
int data_pos = pos;
uint16_t crc = 0;
return read_data(data_pos, value, size, &crc);
diff --git a/Marlin/src/HAL/shared/eeprom_if.h b/Marlin/src/HAL/shared/eeprom_if.h
index e44da801dfbf..e496de2a03c6 100644
--- a/Marlin/src/HAL/shared/eeprom_if.h
+++ b/Marlin/src/HAL/shared/eeprom_if.h
@@ -25,5 +25,5 @@
// EEPROM
//
void eeprom_init();
-void eeprom_write_byte(uint8_t *pos, unsigned char value);
+void eeprom_write_byte(uint8_t *pos, uint8_t value);
uint8_t eeprom_read_byte(uint8_t *pos);
diff --git a/Marlin/src/HAL/shared/eeprom_if_i2c.cpp b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp
index cc22bf7d986f..6b559e234b4c 100644
--- a/Marlin/src/HAL/shared/eeprom_if_i2c.cpp
+++ b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp
@@ -30,9 +30,21 @@
#if ENABLED(I2C_EEPROM)
#include "eeprom_if.h"
-#include
-void eeprom_init() { Wire.begin(); }
+#if ENABLED(SOFT_I2C_EEPROM)
+ #include
+ SlowSoftWire Wire = SlowSoftWire(I2C_SDA_PIN, I2C_SCL_PIN, true);
+#else
+ #include
+#endif
+
+void eeprom_init() {
+ Wire.begin(
+ #if PINS_EXIST(I2C_SCL, I2C_SDA) && DISABLED(SOFT_I2C_EEPROM)
+ uint8_t(I2C_SDA_PIN), uint8_t(I2C_SCL_PIN)
+ #endif
+ );
+}
#if ENABLED(USE_SHARED_EEPROM)
@@ -49,12 +61,28 @@ static constexpr uint8_t eeprom_device_address = I2C_ADDRESS(EEPROM_DEVICE_ADDRE
// Public functions
// ------------------------
-void eeprom_write_byte(uint8_t *pos, unsigned char value) {
+#define SMALL_EEPROM (MARLIN_EEPROM_SIZE <= 2048)
+
+// Combine Address high bits into the device address on <=16Kbit (2K) and >512Kbit (64K) EEPROMs.
+// Note: MARLIN_EEPROM_SIZE is specified in bytes, whereas EEPROM model numbers refer to bits.
+// e.g., The "16" in BL24C16 indicates a 16Kbit (2KB) size.
+static uint8_t _eeprom_calc_device_address(uint8_t * const pos) {
+ const unsigned eeprom_address = (unsigned)pos;
+ return (SMALL_EEPROM || MARLIN_EEPROM_SIZE > 65536)
+ ? uint8_t(eeprom_device_address | ((eeprom_address >> (SMALL_EEPROM ? 8 : 16)) & 0x07))
+ : eeprom_device_address;
+}
+
+static void _eeprom_begin(uint8_t * const pos) {
const unsigned eeprom_address = (unsigned)pos;
+ Wire.beginTransmission(_eeprom_calc_device_address(pos));
+ if (!SMALL_EEPROM)
+ Wire.write(uint8_t((eeprom_address >> 8) & 0xFF)); // Address High, if needed
+ Wire.write(uint8_t(eeprom_address & 0xFF)); // Address Low
+}
- Wire.beginTransmission(eeprom_device_address);
- Wire.write(int(eeprom_address >> 8)); // MSB
- Wire.write(int(eeprom_address & 0xFF)); // LSB
+void eeprom_write_byte(uint8_t *pos, uint8_t value) {
+ _eeprom_begin(pos);
Wire.write(value);
Wire.endTransmission();
@@ -64,13 +92,9 @@ void eeprom_write_byte(uint8_t *pos, unsigned char value) {
}
uint8_t eeprom_read_byte(uint8_t *pos) {
- const unsigned eeprom_address = (unsigned)pos;
-
- Wire.beginTransmission(eeprom_device_address);
- Wire.write(int(eeprom_address >> 8)); // MSB
- Wire.write(int(eeprom_address & 0xFF)); // LSB
+ _eeprom_begin(pos);
Wire.endTransmission();
- Wire.requestFrom(eeprom_device_address, (byte)1);
+ Wire.requestFrom(_eeprom_calc_device_address(pos), (byte)1);
return Wire.available() ? Wire.read() : 0xFF;
}
diff --git a/Marlin/src/HAL/shared/eeprom_if_spi.cpp b/Marlin/src/HAL/shared/eeprom_if_spi.cpp
index a341fef9de97..6aa6e0909623 100644
--- a/Marlin/src/HAL/shared/eeprom_if_spi.cpp
+++ b/Marlin/src/HAL/shared/eeprom_if_spi.cpp
@@ -43,44 +43,41 @@ void eeprom_init() {}
#define EEPROM_WRITE_DELAY 7
#endif
-uint8_t eeprom_read_byte(uint8_t* pos) {
- uint8_t v;
- uint8_t eeprom_temp[3];
-
- // set read location
- // begin transmission from device
- eeprom_temp[0] = CMD_READ;
- eeprom_temp[1] = ((unsigned)pos>>8) & 0xFF; // addr High
- eeprom_temp[2] = (unsigned)pos& 0xFF; // addr Low
- WRITE(SPI_EEPROM1_CS, HIGH);
- WRITE(SPI_EEPROM1_CS, LOW);
+static void _eeprom_begin(uint8_t * const pos, const uint8_t cmd) {
+ const uint8_t eeprom_temp[3] = {
+ cmd,
+ (unsigned(pos) >> 8) & 0xFF, // Address High
+ unsigned(pos) & 0xFF // Address Low
+ };
+ WRITE(SPI_EEPROM1_CS, HIGH); // Usually free already
+ WRITE(SPI_EEPROM1_CS, LOW); // Activate the Bus
spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 3);
+ // Leave the Bus in-use
+}
+
+uint8_t eeprom_read_byte(uint8_t *pos) {
+ _eeprom_begin(pos, CMD_READ); // Set read location and begin transmission
+
+ const uint8_t v = spiRec(SPI_CHAN_EEPROM1); // After READ a value sits on the Bus
+
+ WRITE(SPI_EEPROM1_CS, HIGH); // Done with device
- v = spiRec(SPI_CHAN_EEPROM1);
- WRITE(SPI_EEPROM1_CS, HIGH);
return v;
}
-void eeprom_write_byte(uint8_t* pos, uint8_t value) {
- uint8_t eeprom_temp[3];
-
- /*write enable*/
- eeprom_temp[0] = CMD_WREN;
- WRITE(SPI_EEPROM1_CS, LOW);
- spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 1);
- WRITE(SPI_EEPROM1_CS, HIGH);
- delay(1);
-
- /*write addr*/
- eeprom_temp[0] = CMD_WRITE;
- eeprom_temp[1] = ((unsigned)pos>>8) & 0xFF; //addr High
- eeprom_temp[2] = (unsigned)pos & 0xFF; //addr Low
+void eeprom_write_byte(uint8_t *pos, uint8_t value) {
+ const uint8_t eeprom_temp = CMD_WREN;
WRITE(SPI_EEPROM1_CS, LOW);
- spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 3);
+ spiSend(SPI_CHAN_EEPROM1, &eeprom_temp, 1); // Write Enable
+
+ WRITE(SPI_EEPROM1_CS, HIGH); // Done with the Bus
+ delay(1); // For a small amount of time
+
+ _eeprom_begin(pos, CMD_WRITE); // Set write address and begin transmission
- spiSend(SPI_CHAN_EEPROM1, value);
- WRITE(SPI_EEPROM1_CS, HIGH);
- delay(EEPROM_WRITE_DELAY); // wait for page write to complete
+ spiSend(SPI_CHAN_EEPROM1, value); // Send the value to be written
+ WRITE(SPI_EEPROM1_CS, HIGH); // Done with the Bus
+ delay(EEPROM_WRITE_DELAY); // Give page write time to complete
}
#endif // USE_SHARED_EEPROM
diff --git a/Marlin/src/HAL/shared/progmem.h b/Marlin/src/HAL/shared/progmem.h
new file mode 100644
index 000000000000..539d02705e97
--- /dev/null
+++ b/Marlin/src/HAL/shared/progmem.h
@@ -0,0 +1,189 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see .
+ *
+ */
+#pragma once
+
+#ifndef __AVR__
+#ifndef __PGMSPACE_H_
+// This define should prevent reading the system pgmspace.h if included elsewhere
+// This is not normally needed.
+#define __PGMSPACE_H_ 1
+#endif
+
+#ifndef PROGMEM
+#define PROGMEM
+#endif
+#ifndef PGM_P
+#define PGM_P const char *
+#endif
+#ifndef PSTR
+#define PSTR(str) (str)
+#endif
+#ifndef F
+#define F(str) (str)
+#endif
+#ifndef _SFR_BYTE
+#define _SFR_BYTE(n) (n)
+#endif
+#ifndef memchr_P
+#define memchr_P(str, c, len) memchr((str), (c), (len))
+#endif
+#ifndef memcmp_P
+#define memcmp_P(a, b, n) memcmp((a), (b), (n))
+#endif
+#ifndef memcpy_P
+#define memcpy_P(dest, src, num) memcpy((dest), (src), (num))
+#endif
+#ifndef memmem_P
+#define memmem_P(a, alen, b, blen) memmem((a), (alen), (b), (blen))
+#endif
+#ifndef memrchr_P
+#define memrchr_P(str, val, len) memrchr((str), (val), (len))
+#endif
+#ifndef strcat_P
+#define strcat_P(dest, src) strcat((dest), (src))
+#endif
+#ifndef strchr_P
+#define strchr_P(str, c) strchr((str), (c))
+#endif
+#ifndef strchrnul_P
+#define strchrnul_P(str, c) strchrnul((str), (c))
+#endif
+#ifndef strcmp_P
+#define strcmp_P(a, b) strcmp((a), (b))
+#endif
+#ifndef strcpy_P
+#define strcpy_P(dest, src) strcpy((dest), (src))
+#endif
+#ifndef strcasecmp_P
+#define strcasecmp_P(a, b) strcasecmp((a), (b))
+#endif
+#ifndef strcasestr_P
+#define strcasestr_P(a, b) strcasestr((a), (b))
+#endif
+#ifndef strlcat_P
+#define strlcat_P(dest, src, len) strlcat((dest), (src), (len))
+#endif
+#ifndef strlcpy_P
+#define strlcpy_P(dest, src, len) strlcpy((dest), (src), (len))
+#endif
+#ifndef strlen_P
+#define strlen_P(s) strlen((const char *)(s))
+#endif
+#ifndef strnlen_P
+#define strnlen_P(str, len) strnlen((str), (len))
+#endif
+#ifndef strncmp_P
+#define strncmp_P(a, b, n) strncmp((a), (b), (n))
+#endif
+#ifndef strncasecmp_P
+#define strncasecmp_P(a, b, n) strncasecmp((a), (b), (n))
+#endif
+#ifndef strncat_P
+#define strncat_P(a, b, n) strncat((a), (b), (n))
+#endif
+#ifndef strncpy_P
+#define strncpy_P(a, b, n) strncpy((a), (b), (n))
+#endif
+#ifndef strpbrk_P
+#define strpbrk_P(str, chrs) strpbrk((str), (chrs))
+#endif
+#ifndef strrchr_P
+#define strrchr_P(str, c) strrchr((str), (c))
+#endif
+#ifndef strsep_P
+#define strsep_P(strp, delim) strsep((strp), (delim))
+#endif
+#ifndef strspn_P
+#define strspn_P(str, chrs) strspn((str), (chrs))
+#endif
+#ifndef strstr_P
+#define strstr_P(a, b) strstr((a), (b))
+#endif
+#ifndef sprintf_P
+#define sprintf_P(s, ...) sprintf((s), __VA_ARGS__)
+#endif
+#ifndef vfprintf_P
+#define vfprintf_P(s, ...) vfprintf((s), __VA_ARGS__)
+#endif
+#ifndef printf_P
+#define printf_P(...) printf(__VA_ARGS__)
+#endif
+#ifndef snprintf_P
+#define snprintf_P(s, n, ...) snprintf((s), (n), __VA_ARGS__)
+#endif
+#ifndef vsprintf_P
+#define vsprintf_P(s, ...) vsprintf((s),__VA_ARGS__)
+#endif
+#ifndef vsnprintf_P
+#define vsnprintf_P(s, n, ...) vsnprintf((s), (n),__VA_ARGS__)
+#endif
+#ifndef fprintf_P
+#define fprintf_P(s, ...) fprintf((s), __VA_ARGS__)
+#endif
+
+#ifndef pgm_read_byte
+#define pgm_read_byte(addr) (*(const unsigned char *)(addr))
+#endif
+#ifndef pgm_read_word
+#define pgm_read_word(addr) (*(const unsigned short *)(addr))
+#endif
+#ifndef pgm_read_dword
+#define pgm_read_dword(addr) (*(const unsigned long *)(addr))
+#endif
+#ifndef pgm_read_float
+#define pgm_read_float(addr) (*(const float *)(addr))
+#endif
+
+#ifndef pgm_read_byte_near
+#define pgm_read_byte_near(addr) pgm_read_byte(addr)
+#endif
+#ifndef pgm_read_word_near
+#define pgm_read_word_near(addr) pgm_read_word(addr)
+#endif
+#ifndef pgm_read_dword_near
+#define pgm_read_dword_near(addr) pgm_read_dword(addr)
+#endif
+#ifndef pgm_read_float_near
+#define pgm_read_float_near(addr) pgm_read_float(addr)
+#endif
+#ifndef pgm_read_byte_far
+#define pgm_read_byte_far(addr) pgm_read_byte(addr)
+#endif
+#ifndef pgm_read_word_far
+#define pgm_read_word_far(addr) pgm_read_word(addr)
+#endif
+#ifndef pgm_read_dword_far
+#define pgm_read_dword_far(addr) pgm_read_dword(addr)
+#endif
+#ifndef pgm_read_float_far
+#define pgm_read_float_far(addr) pgm_read_float(addr)
+#endif
+
+#ifndef pgm_read_pointer
+#define pgm_read_pointer
+#endif
+
+// Fix bug in pgm_read_ptr
+#undef pgm_read_ptr
+#define pgm_read_ptr(addr) (*((void**)(addr)))
+
+#endif // __AVR__
diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp
index 343700e9f7ae..404f36c79fb2 100644
--- a/Marlin/src/MarlinCore.cpp
+++ b/Marlin/src/MarlinCore.cpp
@@ -36,6 +36,7 @@
#include "HAL/shared/Delay.h"
#include "HAL/shared/esp_wifi.h"
+#include "HAL/shared/cpu_exception/exception_hook.h"
#ifdef ARDUINO
#include
@@ -43,6 +44,7 @@
#include
#include "core/utility.h"
+
#include "module/motion.h"
#include "module/planner.h"
#include "module/endstops.h"
@@ -57,6 +59,7 @@
#include "gcode/parser.h"
#include "gcode/queue.h"
+#include "feature/pause.h"
#include "sd/cardreader.h"
#include "lcd/marlinui.h"
@@ -65,15 +68,14 @@
#endif
#if HAS_TFT_LVGL_UI
- #include "lcd/extui/lib/mks_ui/tft_lvgl_configuration.h"
- #include "lcd/extui/lib/mks_ui/draw_ui.h"
- #include "lcd/extui/lib/mks_ui/mks_hardware_test.h"
+ #include "lcd/extui/mks_ui/tft_lvgl_configuration.h"
+ #include "lcd/extui/mks_ui/draw_ui.h"
+ #include "lcd/extui/mks_ui/mks_hardware_test.h"
#include
#endif
#if ENABLED(DWIN_CREALITY_LCD)
#include "lcd/dwin/e3v2/dwin.h"
- #include "lcd/dwin/dwin_lcd.h"
#include "lcd/dwin/e3v2/rotary_encoder.h"
#endif
@@ -139,7 +141,6 @@
#if ENABLED(EXPERIMENTAL_I2CBUS)
#include "feature/twibus.h"
- TWIBus i2c;
#endif
#if ENABLED(I2C_POSITION_ENCODERS)
@@ -173,10 +174,6 @@
#include "feature/bedlevel/bedlevel.h"
#endif
-#if BOTH(ADVANCED_PAUSE_FEATURE, PAUSE_PARK_NO_STEPPER_TIMEOUT)
- #include "feature/pause.h"
-#endif
-
#if ENABLED(GCODE_REPEAT_MARKERS)
#include "feature/repeat.h"
#endif
@@ -213,9 +210,7 @@
#include "feature/fanmux.h"
#endif
-#if DO_SWITCH_EXTRUDER || ANY(SWITCHING_NOZZLE, PARKING_EXTRUDER, MAGNETIC_PARKING_EXTRUDER, ELECTROMAGNETIC_SWITCHING_TOOLHEAD, SWITCHING_TOOLHEAD)
- #include "module/tool_change.h"
-#endif
+#include "module/tool_change.h"
#if ENABLED(USE_CONTROLLER_FAN)
#include "feature/controllerfan.h"
@@ -233,18 +228,15 @@
#include "feature/password/password.h"
#endif
-PGMSTR(NUL_STR, "");
+#if ENABLED(DGUS_LCD_UI_MKS)
+ #include "lcd/extui/dgus/DGUSScreenHandler.h"
+#endif
+
+#if HAS_DRIVER_SAFE_POWER_PROTECT
+ #include "feature/stepper_driver_safety.h"
+#endif
+
PGMSTR(M112_KILL_STR, "M112 Shutdown");
-PGMSTR(G28_STR, "G28");
-PGMSTR(M21_STR, "M21");
-PGMSTR(M23_STR, "M23 %s");
-PGMSTR(M24_STR, "M24");
-PGMSTR(SP_P_STR, " P"); PGMSTR(SP_T_STR, " T");
-PGMSTR(X_STR, "X"); PGMSTR(Y_STR, "Y"); PGMSTR(Z_STR, "Z"); PGMSTR(E_STR, "E");
-PGMSTR(X_LBL, "X:"); PGMSTR(Y_LBL, "Y:"); PGMSTR(Z_LBL, "Z:"); PGMSTR(E_LBL, "E:");
-PGMSTR(SP_A_STR, " A"); PGMSTR(SP_B_STR, " B"); PGMSTR(SP_C_STR, " C");
-PGMSTR(SP_X_STR, " X"); PGMSTR(SP_Y_STR, " Y"); PGMSTR(SP_Z_STR, " Z"); PGMSTR(SP_E_STR, " E");
-PGMSTR(SP_X_LBL, " X:"); PGMSTR(SP_Y_LBL, " Y:"); PGMSTR(SP_Z_LBL, " Z:"); PGMSTR(SP_E_LBL, " E:");
MarlinState marlin_state = MF_INITIALIZING;
@@ -267,40 +259,12 @@ bool wait_for_heatup = true;
#endif
-#if PIN_EXISTS(CHDK)
- extern millis_t chdk_timeout;
-#endif
-
-#if ENABLED(I2C_POSITION_ENCODERS)
- I2CPositionEncodersMgr I2CPEM;
-#endif
-
/**
* ***************************************************************************
* ******************************** FUNCTIONS ********************************
* ***************************************************************************
*/
-void setup_killpin() {
- #if HAS_KILL
- #if KILL_PIN_STATE
- SET_INPUT_PULLDOWN(KILL_PIN);
- #else
- SET_INPUT_PULLUP(KILL_PIN);
- #endif
- #endif
-}
-
-void setup_powerhold() {
- #if HAS_SUICIDE
- OUT_WRITE(SUICIDE_PIN, !SUICIDE_PIN_INVERTING);
- #endif
- #if ENABLED(PSU_CONTROL)
- powersupply_on = ENABLED(PSU_DEFAULT_OFF);
- if (ENABLED(PSU_DEFAULT_OFF)) PSU_OFF(); else PSU_ON();
- #endif
-}
-
/**
* Stepper Reset (RigidBoard, et.al.)
*/
@@ -309,18 +273,6 @@ void setup_powerhold() {
void enableStepperDrivers() { SET_INPUT(STEPPER_RESET_PIN); } // Set to input, allowing pullups to pull the pin high
#endif
-#if ENABLED(EXPERIMENTAL_I2CBUS) && I2C_SLAVE_ADDRESS > 0
-
- void i2c_on_receive(int bytes) { // just echo all bytes received to serial
- i2c.receive(bytes);
- }
-
- void i2c_on_request() { // just send dummy data for now
- i2c.reply("Hello World!\n");
- }
-
-#endif
-
/**
* Sensitive pin test for M42, M226
*/
@@ -330,8 +282,15 @@ void setup_powerhold() {
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wnarrowing"
+#ifdef RUNTIME_ONLY_ANALOG_TO_DIGITAL
+ static const pin_t sensitive_pins[] PROGMEM = { SENSITIVE_PINS };
+#else
+ template
+ constexpr pin_t OnlyPins<-2, D...>::table[sizeof...(D)];
+ #define sensitive_pins OnlyPins