From dc11874abe4f683d3a436693c0ec5900c2c2afbc Mon Sep 17 00:00:00 2001
From: X-Ryl669 <boite.pour.spam@gmail.com>
Date: Sun, 21 Feb 2021 03:22:20 +0100
Subject: [PATCH] Postmortem Debugging to serial port (#20492)

---
 Marlin/Configuration_adv.h                    |   7 +
 Marlin/src/HAL/AVR/inc/SanityCheck.h          |   7 +
 Marlin/src/HAL/DUE/DebugMonitor.cpp           | 342 ----------------
 Marlin/src/HAL/DUE/HAL.cpp                    |   3 +
 Marlin/src/HAL/DUE/HAL_MinSerial.cpp          |  91 +++++
 Marlin/src/HAL/DUE/inc/SanityCheck.h          |   2 +-
 Marlin/src/HAL/ESP32/inc/SanityCheck.h        |   6 +-
 Marlin/src/HAL/LINUX/inc/SanityCheck.h        |   6 +-
 Marlin/src/HAL/LPC1768/DebugMonitor.cpp       | 322 ---------------
 Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp      |  50 +++
 Marlin/src/HAL/LPC1768/inc/SanityCheck.h      |   4 +-
 Marlin/src/HAL/LPC1768/main.cpp               |   8 +-
 Marlin/src/HAL/STM32/HAL.cpp                  |   4 +
 Marlin/src/HAL/STM32/HAL_MinSerial.cpp        | 152 +++++++
 Marlin/src/HAL/STM32/inc/SanityCheck.h        |   4 +-
 Marlin/src/HAL/STM32F1/HAL.cpp                |   3 +
 Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp      | 118 ++++++
 Marlin/src/HAL/STM32F1/inc/SanityCheck.h      |   4 +-
 Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h  |   6 +-
 Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h  |   6 +-
 Marlin/src/HAL/TEENSY40_41/inc/SanityCheck.h  |   6 +-
 Marlin/src/HAL/shared/HAL_MinSerial.cpp       |  33 ++
 Marlin/src/HAL/shared/HAL_MinSerial.h         |  79 ++++
 Marlin/src/HAL/shared/backtrace/backtrace.cpp |  28 +-
 Marlin/src/HAL/shared/backtrace/backtrace.h   |   3 +
 .../src/HAL/shared/backtrace/unwmemaccess.cpp |  72 ++--
 .../shared/cpu_exception/exception_arm.cpp    | 379 ++++++++++++++++++
 .../shared/cpu_exception/exception_hook.cpp   |  28 ++
 .../HAL/shared/cpu_exception/exception_hook.h |  54 +++
 Marlin/src/MarlinCore.cpp                     |   3 +
 Marlin/src/gcode/gcode_d.cpp                  |  21 +-
 buildroot/share/PlatformIO/scripts/exc.S      | 104 +++++
 .../scripts/fix_framework_weakness.py         |  29 ++
 platformio.ini                                |  42 +-
 34 files changed, 1286 insertions(+), 740 deletions(-)
 delete mode 100644 Marlin/src/HAL/DUE/DebugMonitor.cpp
 create mode 100644 Marlin/src/HAL/DUE/HAL_MinSerial.cpp
 delete mode 100644 Marlin/src/HAL/LPC1768/DebugMonitor.cpp
 create mode 100644 Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp
 create mode 100644 Marlin/src/HAL/STM32/HAL_MinSerial.cpp
 create mode 100644 Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp
 create mode 100644 Marlin/src/HAL/shared/HAL_MinSerial.cpp
 create mode 100644 Marlin/src/HAL/shared/HAL_MinSerial.h
 create mode 100644 Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp
 create mode 100644 Marlin/src/HAL/shared/cpu_exception/exception_hook.cpp
 create mode 100644 Marlin/src/HAL/shared/cpu_exception/exception_hook.h
 create mode 100644 buildroot/share/PlatformIO/scripts/exc.S
 create mode 100644 buildroot/share/PlatformIO/scripts/fix_framework_weakness.py

diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h
index f615a546713..987ac293b2d 100644
--- a/Marlin/Configuration_adv.h
+++ b/Marlin/Configuration_adv.h
@@ -3732,3 +3732,10 @@
 
 // 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
diff --git a/Marlin/src/HAL/AVR/inc/SanityCheck.h b/Marlin/src/HAL/AVR/inc/SanityCheck.h
index 731cf928658..51ba247953b 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/DUE/DebugMonitor.cpp b/Marlin/src/HAL/DUE/DebugMonitor.cpp
deleted file mode 100644
index 79759151d89..00000000000
--- 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 <https://www.gnu.org/licenses/>.
- *
- */
-#ifdef ARDUINO_ARCH_SAM
-
-#include "../../core/macros.h"
-#include "../../core/serial.h"
-
-#include "../shared/backtrace/unwinder.h"
-#include "../shared/backtrace/unwmemaccess.h"
-
-#include <stdarg.h>
-
-// 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 c15adee0c77..034b86ccb07 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
diff --git a/Marlin/src/HAL/DUE/HAL_MinSerial.cpp b/Marlin/src/HAL/DUE/HAL_MinSerial.cpp
new file mode 100644
index 00000000000..93c4ed67d63
--- /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 <https://www.gnu.org/licenses/>.
+ *
+ */
+#ifdef ARDUINO_ARCH_SAM
+
+#include "../../inc/MarlinConfigPre.h"
+
+#if ENABLED(POSTMORTEM_DEBUGGING)
+
+#include "../shared/HAL_MinSerial.h"
+
+#include <stdarg.h>
+
+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/inc/SanityCheck.h b/Marlin/src/HAL/DUE/inc/SanityCheck.h
index 26fb44f3980..87b09cf2925 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/ESP32/inc/SanityCheck.h b/Marlin/src/HAL/ESP32/inc/SanityCheck.h
index f57a6c59102..8bbc68d8715 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/LINUX/inc/SanityCheck.h b/Marlin/src/HAL/LINUX/inc/SanityCheck.h
index 84167c97a14..45bb2662ace 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/LPC1768/DebugMonitor.cpp b/Marlin/src/HAL/LPC1768/DebugMonitor.cpp
deleted file mode 100644
index 783b10cfac1..00000000000
--- 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 <https://www.gnu.org/licenses/>.
- *
- */
-#ifdef TARGET_LPC1768
-
-#include "../../core/macros.h"
-#include "../../core/serial.h"
-#include <stdarg.h>
-
-#include "../shared/backtrace/unwinder.h"
-#include "../shared/backtrace/unwmemaccess.h"
-#include "watchdog.h"
-#include <debug_frmwrk.h>
-
-
-// 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_MinSerial.cpp b/Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp
new file mode 100644
index 00000000000..ab9af1fe002
--- /dev/null
+++ b/Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp
@@ -0,0 +1,50 @@
+/**
+ * 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 <https://www.gnu.org/licenses/>.
+ *
+ */
+#ifdef TARGET_LPC1768
+
+#include "HAL.h"
+
+#if ENABLED(POSTMORTEM_DEBUGGING)
+
+#include "../shared/HAL_MinSerial.h"
+#include <debug_frmwrk.h>
+
+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/inc/SanityCheck.h b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h
index 10d67377147..dda1c640fa7 100644
--- a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h
+++ b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h
@@ -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 1fbeddd9ea6..08fb1a1ed5d 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
@@ -123,9 +125,7 @@ void HAL_init() {
   delay(1000);                              // Give OS time to notice
   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/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp
index e694a16a820..5c7bc3a00b4 100644
--- a/Marlin/src/HAL/STM32/HAL.cpp
+++ b/Marlin/src/HAL/STM32/HAL.cpp
@@ -57,6 +57,8 @@ uint16_t HAL_adc_result;
 // Public functions
 // ------------------------
 
+TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
+
 // HAL initialization task
 void HAL_init() {
   FastIO_init();
@@ -83,6 +85,8 @@ void HAL_init() {
     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
diff --git a/Marlin/src/HAL/STM32/HAL_MinSerial.cpp b/Marlin/src/HAL/STM32/HAL_MinSerial.cpp
new file mode 100644
index 00000000000..823bb6e8f5e
--- /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 <https://www.gnu.org/licenses/>.
+ *
+ */
+#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;
+    nvicBase->ICER[nvicIndex / 32] |= _BV32(nvicIndex % 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();
+
+    // 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/inc/SanityCheck.h b/Marlin/src/HAL/STM32/inc/SanityCheck.h
index 4df75a05055..7ee606af7f3 100644
--- a/Marlin/src/HAL/STM32/inc/SanityCheck.h
+++ b/Marlin/src/HAL/STM32/inc/SanityCheck.h
@@ -47,9 +47,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 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)
diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp
index 2f29b9b0e36..020c623b77a 100644
--- a/Marlin/src/HAL/STM32F1/HAL.cpp
+++ b/Marlin/src/HAL/STM32F1/HAL.cpp
@@ -272,6 +272,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)
@@ -287,6 +289,7 @@ void HAL_init() {
     delay(1000);                                         // Give OS time to notice
     OUT_WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING);
   #endif
+  TERN_(POSTMORTEM_DEBUGGING, install_min_serial());    // Install the minimal serial handler
 }
 
 // HAL idle task
diff --git a/Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp b/Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp
new file mode 100644
index 00000000000..e6b89f1105c
--- /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 <https://www.gnu.org/licenses/>.
+ *
+ */
+#ifdef __STM32F1__
+
+#include "../../inc/MarlinConfigPre.h"
+
+#if ENABLED(POSTMORTEM_DEBUGGING)
+
+#include "../shared/HAL_MinSerial.h"
+#include "watchdog.h"
+
+#include <libmaple/usart.h>
+#include <libmaple/rcc.h>
+#include <libmaple/nvic.h>
+
+/* 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 MYSERIAL0 here, so we need to figure out how to get the linked register
+    struct usart_dev* dev = MYSERIAL0.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
+    //NVIC_BASE->ICER[1] |= _BV(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 = MYSERIAL0.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/inc/SanityCheck.h b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h
index 8d4c54ec0fd..89ee66d6464 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/TEENSY31_32/inc/SanityCheck.h b/Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h
index 3932ee6a76c..1efa76b1e9d 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/inc/SanityCheck.h b/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h
index ee80e42696f..eef2850550e 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/inc/SanityCheck.h b/Marlin/src/HAL/TEENSY40_41/inc/SanityCheck.h
index fbfe7b0fc3d..3d2668d749b 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/HAL_MinSerial.cpp b/Marlin/src/HAL/shared/HAL_MinSerial.cpp
new file mode 100644
index 00000000000..9dda5fdf8c6
--- /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 <https://www.gnu.org/licenses/>.
+ *
+ */
+#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 00000000000..04643c1ab36
--- /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 <https://www.gnu.org/licenses/>.
+ *
+ */
+#pragma once
+
+#include "../../core/serial.h"
+#include <stdint.h>
+
+// 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/backtrace/backtrace.cpp b/Marlin/src/HAL/shared/backtrace/backtrace.cpp
index 4a8990c00b8..8320f475096 100644
--- a/Marlin/src/HAL/shared/backtrace/backtrace.cpp
+++ b/Marlin/src/HAL/shared/backtrace/backtrace.cpp
@@ -25,7 +25,7 @@
 #include "unwinder.h"
 #include "unwmemaccess.h"
 
-#include "../../../core/serial.h"
+#include "../HAL_MinSerial.h"
 #include <stdarg.h>
 
 // Dump a backtrace entry
@@ -34,10 +34,12 @@ static bool UnwReportOut(void* ctx, const UnwReport* bte) {
 
   (*p)++;
 
-  SERIAL_CHAR('#'); SERIAL_ECHO(*p); SERIAL_ECHOPGM(" : ");
-  SERIAL_ECHOPGM(bte->name ? bte->name : "unknown"); SERIAL_ECHOPGM("@0x"); SERIAL_PRINT(bte->function, PrintBase::Hex);
-  SERIAL_CHAR('+'); SERIAL_ECHO(bte->address - bte->function);
-  SERIAL_ECHOPGM(" PC:"); SERIAL_PRINT(bte->address, PrintBase::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;
 }
 
@@ -48,7 +50,7 @@ static bool UnwReportOut(void* ctx, const UnwReport* bte) {
     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 fccadedaa54..5d2ba601a07 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/unwmemaccess.cpp b/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp
index 5ca46f98865..2bde1e208d9 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 00000000000..090148683fa
--- /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 <https://www.gnu.org/licenses/>.
+ *
+ */
+
+/***************************************************************************
+ * 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_ECHO("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_ECHO("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_ECHOLN("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 00000000000..93e80f3e852
--- /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 <https://www.gnu.org/licenses/>.
+ *
+ */
+#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 00000000000..70d94347045
--- /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 <https://www.gnu.org/licenses/>.
+ *
+ */
+#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/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp
index b085e6145a5..8aa6cdd6c89 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 <pins_arduino.h>
@@ -935,6 +936,8 @@ void setup() {
     while (/*!WIFISERIAL && */PENDING(millis(), serial_connect_timeout)) { /*nada*/ }
   #endif
 
+  TERN_(DYNAMIC_VECTORTABLE, hook_cpu_exceptions()); // If supported, install Marlin exception handlers at runtime
+
   SETUP_RUN(HAL_init());
 
   // Init and disable SPI thermocouples; this is still needed
diff --git a/Marlin/src/gcode/gcode_d.cpp b/Marlin/src/gcode/gcode_d.cpp
index 653ae6a553f..805dcd52cec 100644
--- a/Marlin/src/gcode/gcode_d.cpp
+++ b/Marlin/src/gcode/gcode_d.cpp
@@ -152,8 +152,7 @@
         NOMORE(len, FLASH_SIZE - addr);
         if (parser.seenval('X')) {
           // TODO: Write the hex bytes after the X
-          //while (len--) {
-          //}
+          //while (len--) {}
         }
         else {
           // while (len--) {
@@ -180,7 +179,25 @@
         for (int i = 10000; i--;) DELAY_US(1000UL);
         ENABLE_ISRS();
         SERIAL_ECHOLNPGM("FAILURE: Watchdog did not trigger board reset.");
+      } break;
+
+      #if ENABLED(POSTMORTEM_DEBUGGING)
+      case 451: { // Trigger all kind of faults to test exception catcher
+        SERIAL_ECHOLNPGM("Disabling heaters");
+        thermalManager.disable_all_heaters();
+        delay(1000); // Allow time to print
+        volatile uint8_t type[5] = { parser.byteval('T', 1) };
+
+        // The code below is obviously wrong and it's full of quirks to fool the compiler from optimizing away the code
+        switch (type[0]) {
+          case 1: default: *(int*)0 = 451; break; // Write at bad address
+          case 2: { volatile int a = 0; volatile int b = 452 / a; *(int*)&a = b; } break; // Divide by zero (some CPUs accept this, like ARM)
+          case 3: { *(uint32_t*)&type[1] = 453; volatile int a = *(int*)&type[1]; type[0] = a / 255; } break; // Unaligned access (some CPUs accept this)
+          case 4: { volatile void (*func)() = (volatile void (*)()) 0xE0000000; func(); } break; // Invalid instruction
+        }
+        break;
       }
+      #endif
     }
   }
 
diff --git a/buildroot/share/PlatformIO/scripts/exc.S b/buildroot/share/PlatformIO/scripts/exc.S
new file mode 100644
index 00000000000..1db462bb237
--- /dev/null
+++ b/buildroot/share/PlatformIO/scripts/exc.S
@@ -0,0 +1,104 @@
+/* *****************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2010 Perry Hung.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ * ****************************************************************************/
+
+# On an exception, push a fake stack thread mode stack frame and redirect
+# thread execution to a thread mode error handler
+
+# From RM008:
+# The SP is decremented by eight words by the completion of the stack push.
+# Figure 5-1 shows the contents of the stack after an exception pre-empts the
+# current program flow.
+#
+# Old SP--> <previous>
+#           xPSR
+#           PC
+#           LR
+#           r12
+#           r3
+#           r2
+#           r1
+#    SP-->  r0
+
+.text
+.globl __exc_nmi
+.weak  __exc_nmi
+.globl __exc_hardfault
+.weak  __exc_hardfault
+.globl __exc_memmanage
+.weak  __exc_memmanage
+.globl __exc_busfault
+.weak  __exc_busfault
+.globl __exc_usagefault
+.weak  __exc_usagefault
+
+.code 16
+.thumb_func
+__exc_nmi:
+    mov r0, #1
+    b __default_exc
+
+.thumb_func
+__exc_hardfault:
+    mov r0, #2
+    b __default_exc
+
+.thumb_func
+__exc_memmanage:
+    mov r0, #3
+    b __default_exc
+
+.thumb_func
+__exc_busfault:
+    mov r0, #4
+    b __default_exc
+
+.thumb_func
+__exc_usagefault:
+    mov r0, #5
+    b __default_exc
+
+.thumb_func
+__default_exc:
+    ldr r2, NVIC_CCR            @ Enable returning to thread mode even if there are
+    mov r1 ,#1                  @ pending exceptions. See flag NONEBASETHRDENA.
+    str r1, [r2]
+    cpsid i                     @ Disable global interrupts
+    ldr r2, SYSTICK_CSR         @ Disable systick handler
+    mov r1, #0
+    str r1, [r2]
+    ldr r1, CPSR_MASK           @ Set default CPSR
+    push {r1}
+    ldr r1, TARGET_PC           @ Set target pc
+    push {r1}
+    sub sp, sp, #24             @ Don't care
+    ldr r1, EXC_RETURN          @ Return to thread mode
+    mov lr, r1
+    bx lr                       @ Exception exit
+
+.align 4
+CPSR_MASK:     .word 0x61000000
+EXC_RETURN:    .word 0xFFFFFFF9
+TARGET_PC:     .word __error
+NVIC_CCR:      .word 0xE000ED14    @ NVIC configuration control register
+SYSTICK_CSR:   .word 0xE000E010    @ Systick control register
diff --git a/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py b/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py
new file mode 100644
index 00000000000..94076cfbab5
--- /dev/null
+++ b/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py
@@ -0,0 +1,29 @@
+from os.path import join, isfile
+import shutil
+from pprint import pprint
+
+Import("env")
+
+if env.MarlinFeatureIsEnabled("POSTMORTEM_DEBUGGING"):
+    FRAMEWORK_DIR = env.PioPlatform().get_package_dir("framework-arduinoststm32-maple")
+    patchflag_path = join(FRAMEWORK_DIR, ".exc-patching-done")
+
+    # patch file only if we didn't do it before
+    if not isfile(patchflag_path):
+        print("Patching libmaple exception handlers")
+        original_file = join(FRAMEWORK_DIR, "STM32F1", "cores", "maple", "libmaple", "exc.S")
+        backup_file = join(FRAMEWORK_DIR, "STM32F1", "cores", "maple", "libmaple", "exc.S.bak")
+        src_file = join("buildroot", "share", "PlatformIO", "scripts", "exc.S")
+
+        assert isfile(original_file) and isfile(src_file)
+        shutil.copyfile(original_file, backup_file)
+        shutil.copyfile(src_file, original_file);
+
+        def _touch(path):
+            with open(path, "w") as fp:
+                fp.write("")
+
+        env.Execute(lambda *args, **kwargs: _touch(patchflag_path))
+        print("Done patching exception handler")
+
+    print("Libmaple modified and ready for post mortem debugging")
diff --git a/platformio.ini b/platformio.ini
index 15fbf220d4e..dd8a3968492 100644
--- a/platformio.ini
+++ b/platformio.ini
@@ -64,6 +64,7 @@ default_src_filter = +<src/*> -<src/config> -<src/HAL> +<src/HAL/shared>
   -<src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp>
   -<src/sd/cardreader.cpp> -<src/sd/Sd2Card.cpp> -<src/sd/SdBaseFile.cpp> -<src/sd/SdFatUtil.cpp> -<src/sd/SdFile.cpp> -<src/sd/SdVolume.cpp> -<src/gcode/sd>
   -<src/HAL/shared/backtrace>
+  -<src/HAL/shared/cpu_exception>
   -<src/HAL/shared/eeprom_if_i2c.cpp>
   -<src/HAL/shared/eeprom_if_spi.cpp>
   -<src/feature/babystep.cpp>
@@ -223,6 +224,8 @@ YHCB2004                = red-scorp/LiquidCrystal_AIP31068@^1.0.4, red-scorp/Sof
 HAS_TFT_LVGL_UI         = lvgl=https://github.com/makerbase-mks/LVGL-6.1.1-MKS/archive/master.zip
                           src_filter=+<src/lcd/extui/lib/mks_ui>
                           extra_scripts=download_mks_assets.py
+POSTMORTEM_DEBUGGING    = src_filter=+<src/HAL/shared/cpu_exception> +<src/HAL/shared/backtrace>
+                          build_flags=-funwind-tables
 MKS_WIFI_MODULE         = QRCode=https://github.com/makerbase-mks/QRCode/archive/master.zip
 HAS_TRINAMIC_CONFIG     = TMCStepper@~0.7.1
                           src_filter=+<src/feature/tmc_util.cpp> +<src/module/stepper/trinamic.cpp> +<src/gcode/feature/trinamic/M122.cpp> +<src/gcode/feature/trinamic/M906.cpp> +<src/gcode/feature/trinamic/M911-M914.cpp>
@@ -637,14 +640,6 @@ platform = atmelsam
 extends  = env:DUE
 board    = dueUSB
 
-[env:DUE_debug]
-# Used when WATCHDOG_RESET_MANUAL is enabled
-platform    = atmelsam
-extends     = env:DUE
-build_flags = ${common.build_flags}
-  -funwind-tables
-  -mpoke-function-name
-
 #
 # Archim SAM
 #
@@ -662,12 +657,6 @@ extra_scripts            = ${common.extra_scripts}
 platform = ${common_DUE_archim.platform}
 extends  = common_DUE_archim
 
-# Used when WATCHDOG_RESET_MANUAL is enabled
-[env:DUE_archim_debug]
-platform    = ${common_DUE_archim.platform}
-extends     = common_DUE_archim
-build_flags = ${common_DUE_archim.build_flags} -funwind-tables -mpoke-function-name
-
 #################################
 #                               #
 #      SAMD51 Architecture      #
@@ -763,6 +752,8 @@ lib_ignore        = SPI, FreeRTOS701, FreeRTOS821
 lib_deps          = ${common.lib_deps}
   SoftwareSerialM
 platform_packages = tool-stm32duino
+extra_scripts     = ${common.extra_scripts}
+  buildroot/share/PlatformIO/scripts/fix_framework_weakness.py
 
 #
 # STM32F103RC
@@ -788,7 +779,7 @@ build_flags       = ${common_stm32f1.build_flags}
                     -DUSE_USB_COMPOSITE
                     -DVECT_TAB_OFFSET=0x2000
                     -DGENERIC_BOOTLOADER
-extra_scripts     = ${common.extra_scripts}
+extra_scripts     = ${common_stm32f1.extra_scripts}
   pre:buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py
   buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py
 lib_deps          = ${common.lib_deps}
@@ -934,7 +925,7 @@ upload_protocol   = serial
 platform      = ${common_stm32f1.platform}
 extends       = common_stm32f1
 board         = genericSTM32F103VE
-extra_scripts = ${common.extra_scripts}
+extra_scripts = ${common_stm32f1.extra_scripts}
   buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py
 build_flags   = ${common_stm32f1.build_flags}
   -DMCU_STM32F103VE -DSTM32F1xx -USERIAL_USB -DU20 -DTS_V12
@@ -948,7 +939,7 @@ build_unflags = ${common_stm32f1.build_unflags}
 platform      = ${common_stm32f1.platform}
 extends       = common_stm32f1
 board         = genericSTM32F103VE
-extra_scripts = ${common.extra_scripts}
+extra_scripts = ${common_stm32f1.extra_scripts}
   buildroot/share/PlatformIO/scripts/mks_robin_mini.py
 build_flags   = ${common_stm32f1.build_flags}
   -DMCU_STM32F103VE
@@ -974,7 +965,7 @@ upload_protocol = jlink
 platform      = ${common_stm32f1.platform}
 extends       = common_stm32f1
 board         = genericSTM32F103ZE
-extra_scripts = ${common.extra_scripts}
+extra_scripts = ${common_stm32f1.extra_scripts}
   buildroot/share/PlatformIO/scripts/mks_robin.py
 build_flags   = ${common_stm32f1.build_flags}
   -DSS_TIMER=4 -DSTM32_XL_DENSITY
@@ -1008,7 +999,7 @@ lib_deps             =
 [env:mks_robin_pro]
 platform      = ${common_stm32f1.platform}
 extends       = env:mks_robin
-extra_scripts = ${common.extra_scripts}
+extra_scripts = ${common_stm32f1.extra_scripts}
   buildroot/share/PlatformIO/scripts/mks_robin_pro.py
 
 #
@@ -1017,7 +1008,7 @@ extra_scripts = ${common.extra_scripts}
 [env:trigorilla_pro]
 platform      = ${common_stm32f1.platform}
 extends       = env:mks_robin
-extra_scripts = ${common.extra_scripts}
+extra_scripts = ${common_stm32f1.extra_scripts}
 
 #
 # MKS Robin E3D (STM32F103RCT6) and
@@ -1041,7 +1032,7 @@ build_flags   = ${common_stm32f1.build_flags}
 platform        = ${common_stm32f1.platform}
 extends         = common_stm32f1
 board           = genericSTM32F103VE
-extra_scripts   = ${common.extra_scripts}
+extra_scripts   = ${common_stm32f1.extra_scripts}
   buildroot/share/PlatformIO/scripts/mks_robin_e3p.py
 build_flags     = ${common_stm32f1.build_flags}
   -DMCU_STM32F103VE -DSS_TIMER=4
@@ -1055,7 +1046,7 @@ upload_protocol = jlink
 platform      = ${common_stm32f1.platform}
 extends       = common_stm32f1
 board         = genericSTM32F103RC
-extra_scripts = ${common.extra_scripts}
+extra_scripts = ${common_stm32f1.extra_scripts}
   buildroot/share/PlatformIO/scripts/mks_robin_lite.py
 
 #
@@ -1065,7 +1056,7 @@ extra_scripts = ${common.extra_scripts}
 platform      = ${common_stm32f1.platform}
 extends       = common_stm32f1
 board         = genericSTM32F103RC
-extra_scripts = ${common.extra_scripts}
+extra_scripts = ${common_stm32f1.extra_scripts}
   buildroot/share/PlatformIO/scripts/mks_robin_lite3.py
 
 #
@@ -1075,7 +1066,7 @@ extra_scripts = ${common.extra_scripts}
 platform      = ${common_stm32f1.platform}
 extends       = common_stm32f1
 board         = genericSTM32F103ZE
-extra_scripts = ${common.extra_scripts}
+extra_scripts = ${common_stm32f1.extra_scripts}
   buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py
 build_flags   = ${common_stm32f1.build_flags}
   -DSTM32F1xx -DSTM32_XL_DENSITY
@@ -1230,7 +1221,7 @@ extra_scripts     = ${common.extra_scripts}
 platform          = ${common_stm32f1.platform}
 extends           = common_stm32f1
 board             = genericSTM32F103RC
-extra_scripts     = ${common.extra_scripts}
+extra_scripts     = ${common_stm32f1.extra_scripts}
  buildroot/share/PlatformIO/scripts/fly_mini.py
 build_flags       = ${common_stm32f1.build_flags}
  -DDEBUG_LEVEL=0 -DSS_TIMER=4
@@ -1557,7 +1548,6 @@ build_flags          = ${common_stm32.build_flags} -DENABLE_HWSERIAL3 -DTIMER_SE
 build_unflags        = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC
 extra_scripts        = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py
 
-
 #################################
 #                               #
 #      Other Architectures      #