diff --git a/Marlin/src/HAL/AVR/HAL.cpp b/Marlin/src/HAL/AVR/HAL.cpp
index 2b6d2bdbcf..d7bf2a6f6f 100644
--- a/Marlin/src/HAL/AVR/HAL.cpp
+++ b/Marlin/src/HAL/AVR/HAL.cpp
@@ -36,7 +36,7 @@
 // ------------------------
 
 // Don't initialize/override variable (which would happen in .init4)
-uint8_t MarlinHAL::reset_reason __attribute__((section(".noinit")));
+uint8_t reset_reason __attribute__((section(".noinit")));
 
 // ------------------------
 // Public functions
@@ -45,22 +45,22 @@ uint8_t MarlinHAL::reset_reason __attribute__((section(".noinit")));
 __attribute__((naked))             // Don't output function pro- and epilogue
 __attribute__((used))              // Output the function, even if "not used"
 __attribute__((section(".init3"))) // Put in an early user definable section
-void save_reset_reason() {
+void HAL_save_reset_reason() {
   #if ENABLED(OPTIBOOT_RESET_REASON)
     __asm__ __volatile__(
       A("STS %0, r2")
-      : "=m"(hal.reset_reason)
+      : "=m"(reset_reason)
     );
   #else
-    hal.reset_reason = MCUSR;
+    reset_reason = MCUSR;
   #endif
 
   // Clear within 16ms since WDRF bit enables a 16ms watchdog timer -> Boot loop
-  hal.clear_reset_source();
+  MCUSR = 0;
   wdt_disable();
 }
 
-void MarlinHAL::init() {
+void HAL_init() {
   // Init Servo Pins
   #define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW)
   #if HAS_SERVO_0
@@ -77,7 +77,7 @@ void MarlinHAL::init() {
   #endif
 }
 
-void MarlinHAL::reboot() {
+void HAL_reboot() {
   #if ENABLED(USE_WATCHDOG)
     while (1) { /* run out the watchdog */ }
   #else
diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h
index 3dade7fa15..2217f239d6 100644
--- a/Marlin/src/HAL/AVR/HAL.h
+++ b/Marlin/src/HAL/AVR/HAL.h
@@ -74,8 +74,9 @@
   #define CRITICAL_SECTION_START()  unsigned char _sreg = SREG; cli()
   #define CRITICAL_SECTION_END()    SREG = _sreg
 #endif
-
-#define HAL_CAN_SET_PWM_FREQ   // This HAL supports PWM Frequency adjustment
+#define ISRS_ENABLED() TEST(SREG, SREG_I)
+#define ENABLE_ISRS()  sei()
+#define DISABLE_ISRS() cli()
 
 // ------------------------
 // Types
@@ -83,16 +84,16 @@
 
 typedef int8_t pin_t;
 
-// Use shared/servos.cpp
 #define SHARED_SERVOS HAS_SERVOS
-
-class Servo;
-typedef Servo hal_servo_t;
+#define HAL_SERVO_LIB Servo
 
 // ------------------------
+// Public Variables
+// ------------------------
+
+extern uint8_t reset_reason;
+
 // Serial ports
-// ------------------------
-
 #ifdef USBCON
   #include "../../core/serial_hook.h"
   typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1;
@@ -141,15 +142,57 @@ typedef Servo hal_servo_t;
   #endif
 #endif
 
-//
+// ------------------------
+// Public functions
+// ------------------------
+
+void HAL_init();
+
+//void cli();
+
+//void _delay_ms(const int delay);
+
+inline void HAL_clear_reset_source() { }
+inline uint8_t HAL_get_reset_source() { return reset_reason; }
+
+void HAL_reboot();
+
+#pragma GCC diagnostic push
+#if GCC_VERSION <= 50000
+  #pragma GCC diagnostic ignored "-Wunused-function"
+#endif
+
+extern "C" int freeMemory();
+
+#pragma GCC diagnostic pop
+
 // ADC
-//
+#ifdef DIDR2
+  #define HAL_ANALOG_SELECT(ind) do{ if (ind < 8) SBI(DIDR0, ind); else SBI(DIDR2, ind & 0x07); }while(0)
+#else
+  #define HAL_ANALOG_SELECT(ind) SBI(DIDR0, ind);
+#endif
+
+inline void HAL_adc_init() {
+  ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07;
+  DIDR0 = 0;
+  #ifdef DIDR2
+    DIDR2 = 0;
+  #endif
+}
+
+#define SET_ADMUX_ADCSRA(ch) ADMUX = _BV(REFS0) | (ch & 0x07); SBI(ADCSRA, ADSC)
+#ifdef MUX5
+  #define HAL_START_ADC(ch) if (ch > 7) ADCSRB = _BV(MUX5); else ADCSRB = 0; SET_ADMUX_ADCSRA(ch)
+#else
+  #define HAL_START_ADC(ch) ADCSRB = 0; SET_ADMUX_ADCSRA(ch)
+#endif
+
 #define HAL_ADC_VREF        5.0
 #define HAL_ADC_RESOLUTION 10
+#define HAL_READ_ADC()  ADC
+#define HAL_ADC_READY() !TEST(ADCSRA, ADSC)
 
-//
-// Pin Mapping for M42, M43, M226
-//
 #define GET_PIN_MAP_PIN(index) index
 #define GET_PIN_MAP_INDEX(pin) pin
 #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
@@ -163,104 +206,23 @@ typedef Servo hal_servo_t;
 // AVR compatibility
 #define strtof strtod
 
-// ------------------------
-// Class Utilities
-// ------------------------
+#define HAL_CAN_SET_PWM_FREQ   // This HAL supports PWM Frequency adjustment
 
-#pragma GCC diagnostic push
-#if GCC_VERSION <= 50000
-  #pragma GCC diagnostic ignored "-Wunused-function"
-#endif
+/**
+ *  set_pwm_frequency
+ *  Sets the frequency of the timer corresponding to the provided pin
+ *  as close as possible to the provided desired frequency. Internally
+ *  calculates the required waveform generation mode, prescaler and
+ *  resolution values required and sets the timer registers accordingly.
+ *  NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B)
+ *  NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST FAN PWM Settings)
+ */
+void set_pwm_frequency(const pin_t pin, int f_desired);
 
-extern "C" int freeMemory();
-
-#pragma GCC diagnostic pop
-
-// ------------------------
-// MarlinHAL Class
-// ------------------------
-
-class MarlinHAL {
-public:
-
-  // Earliest possible init, before setup()
-  MarlinHAL() {}
-
-  static void init();                 // Called early in setup()
-  static inline void init_board() {}  // Called less early in setup()
-  static void reboot();               // Restart the firmware from 0x0
-
-  static inline bool isr_state() { return TEST(SREG, SREG_I); }
-  static inline void isr_on()  { sei(); }
-  static inline void isr_off() { cli(); }
-
-  static inline void delay_ms(const int ms) { _delay_ms(ms); }
-
-  // Tasks, called from idle()
-  static inline void idletask() {}
-
-  // Reset
-  static uint8_t reset_reason;
-  static inline uint8_t get_reset_source() { return reset_reason; }
-  static inline void clear_reset_source() { MCUSR = 0; }
-
-  // Free SRAM
-  static inline int freeMemory() { return ::freeMemory(); }
-
-  //
-  // ADC Methods
-  //
-
-  // Called by Temperature::init once at startup
-  static inline void adc_init() {
-    ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07;
-    DIDR0 = 0;
-    #ifdef DIDR2
-      DIDR2 = 0;
-    #endif
-  }
-
-  // Called by Temperature::init for each sensor at startup
-  static inline void adc_enable(const uint8_t ch) {
-    #ifdef DIDR2
-      if (ch > 7) { SBI(DIDR2, ch & 0x07); return; }
-    #endif
-    SBI(DIDR0, ch);
-  }
-
-  // Begin ADC sampling on the given channel
-  static inline void adc_start(const uint8_t ch) {
-    #ifdef MUX5
-      ADCSRB = ch > 7 ? _BV(MUX5) : 0;
-    #else
-      ADCSRB = 0;
-    #endif
-    ADMUX = _BV(REFS0) | (ch & 0x07);
-    SBI(ADCSRA, ADSC);
-  }
-
-  // Is the ADC ready for reading?
-  static inline bool adc_ready() { return !TEST(ADCSRA, ADSC); }
-
-  // The current value of the ADC register
-  static inline __typeof__(ADC) adc_value() { return ADC; }
-
-  /**
-   * Set the PWM duty cycle for the pin to the given value.
-   * Optionally invert the duty cycle [default = false]
-   * Optionally change the scale of the provided value to enable finer PWM duty control [default = 255]
-   */
-  static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
-
-  /**
-   * Set the frequency of the timer for the given pin as close as
-   * possible to the provided desired frequency. Internally calculate
-   * the required waveform generation mode, prescaler, and resolution
-   * values and set timer registers accordingly.
-   * NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B)
-   * NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST FAN PWM Settings)
-   */
-  static void set_pwm_frequency(const pin_t pin, int f_desired);
-};
-
-extern MarlinHAL hal;
+/**
+ * set_pwm_duty
+ *  Set the PWM duty cycle of the provided pin to the provided value
+ *  Optionally allows inverting the duty cycle [default = false]
+ *  Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255]
+ */
+void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
diff --git a/Marlin/src/HAL/AVR/MarlinSerial.cpp b/Marlin/src/HAL/AVR/MarlinSerial.cpp
index 986462437c..cd8bf5e690 100644
--- a/Marlin/src/HAL/AVR/MarlinSerial.cpp
+++ b/Marlin/src/HAL/AVR/MarlinSerial.cpp
@@ -486,7 +486,7 @@ void MarlinSerial<Cfg>::write(const uint8_t c) {
     const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1);
 
     // If global interrupts are disabled (as the result of being called from an ISR)...
-    if (!hal.isr_state()) {
+    if (!ISRS_ENABLED()) {
 
       // Make room by polling if it is possible to transmit, and do so!
       while (i == tx_buffer.tail) {
@@ -534,7 +534,7 @@ void MarlinSerial<Cfg>::flushTX() {
     if (!_written) return;
 
     // If global interrupts are disabled (as the result of being called from an ISR)...
-    if (!hal.isr_state()) {
+    if (!ISRS_ENABLED()) {
 
       // Wait until everything was transmitted - We must do polling, as interrupts are disabled
       while (tx_buffer.head != tx_buffer.tail || !B_TXC) {
diff --git a/Marlin/src/HAL/AVR/fast_pwm.cpp b/Marlin/src/HAL/AVR/fast_pwm.cpp
index 0053b44c3c..804e5fad30 100644
--- a/Marlin/src/HAL/AVR/fast_pwm.cpp
+++ b/Marlin/src/HAL/AVR/fast_pwm.cpp
@@ -35,9 +35,10 @@ struct Timer {
 };
 
 /**
- * Get the timer information and register for a pin.
- * Return a Timer struct containing this information.
- * Used by set_pwm_frequency, set_pwm_duty
+ * get_pwm_timer
+ *  Get the timer information and register of the provided pin.
+ *  Return a Timer struct containing this information.
+ *  Used by set_pwm_frequency, set_pwm_duty
  */
 Timer get_pwm_timer(const pin_t pin) {
   uint8_t q = 0;
@@ -149,7 +150,7 @@ Timer get_pwm_timer(const pin_t pin) {
   return timer;
 }
 
-void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) {
+void set_pwm_frequency(const pin_t pin, int f_desired) {
   Timer timer = get_pwm_timer(pin);
   if (timer.n == 0) return; // Don't proceed if protected timer or not recognized
   uint16_t size;
@@ -229,7 +230,7 @@ void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) {
 
 #endif // NEEDS_HARDWARE_PWM
 
-void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
+void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
   #if NEEDS_HARDWARE_PWM
 
     // If v is 0 or v_size (max), digitalWrite to LOW or HIGH.
diff --git a/Marlin/src/HAL/AVR/timers.h b/Marlin/src/HAL/AVR/timers.h
index e1fcbf52d6..36b04eae0d 100644
--- a/Marlin/src/HAL/AVR/timers.h
+++ b/Marlin/src/HAL/AVR/timers.h
@@ -109,8 +109,8 @@ FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t) {
  * (otherwise, characters will be lost due to UART overflow).
  * Then: Stepper, Endstops, Temperature, and -finally- all others.
  */
-#define HAL_timer_isr_prologue(T) NOOP
-#define HAL_timer_isr_epilogue(T) NOOP
+#define HAL_timer_isr_prologue(T)
+#define HAL_timer_isr_epilogue(T)
 
 /* 18 cycles maximum latency */
 #ifndef HAL_STEP_TIMER_ISR
diff --git a/Marlin/src/HAL/DUE/HAL.cpp b/Marlin/src/HAL/DUE/HAL.cpp
index 20b711b1b0..a3985652e7 100644
--- a/Marlin/src/HAL/DUE/HAL.cpp
+++ b/Marlin/src/HAL/DUE/HAL.cpp
@@ -34,7 +34,7 @@
 // Public Variables
 // ------------------------
 
-uint16_t MarlinHAL::adc_result;
+uint16_t HAL_adc_result;
 
 // ------------------------
 // Public functions
@@ -42,7 +42,8 @@ uint16_t MarlinHAL::adc_result;
 
 TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
 
-void MarlinHAL::init() {
+// HAL initialization task
+void HAL_init() {
   // Initialize the USB stack
   #if ENABLED(SDSUPPORT)
     OUT_WRITE(SDSS, HIGH);  // Try to set SDSS inactive before any other SPI users start up
@@ -51,17 +52,21 @@ void MarlinHAL::init() {
   TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler
 }
 
-void MarlinHAL::init_board() {
-  #ifdef BOARD_INIT
-    BOARD_INIT();
-  #endif
+// HAL idle task
+void HAL_idletask() {
+  // Perform USB stack housekeeping
+  usb_task_idle();
 }
 
-void MarlinHAL::idletask() {
-  usb_task_idle();    // Perform USB stack housekeeping
-}
+// Disable interrupts
+void cli() { noInterrupts(); }
 
-uint8_t MarlinHAL::get_reset_source() {
+// Enable interrupts
+void sei() { interrupts(); }
+
+void HAL_clear_reset_source() { }
+
+uint8_t HAL_get_reset_source() {
   switch ((RSTC->RSTC_SR >> 8) & 0x07) {
     case 0: return RST_POWER_ON;
     case 1: return RST_BACKUP;
@@ -72,7 +77,12 @@ uint8_t MarlinHAL::get_reset_source() {
   }
 }
 
-void MarlinHAL::reboot() { rstc_start_software_reset(RSTC); }
+void HAL_reboot() { rstc_start_software_reset(RSTC); }
+
+void _delay_ms(const int delay_ms) {
+  // Todo: port for Due?
+  delay(delay_ms);
+}
 
 extern "C" {
   extern unsigned int _ebss; // end of bss section
@@ -84,6 +94,19 @@ int freeMemory() {
   return (int)&free_memory - (heap_end ?: (int)&_ebss);
 }
 
+// ------------------------
+// ADC
+// ------------------------
+
+void HAL_adc_start_conversion(const uint8_t ch) {
+  HAL_adc_result = analogRead(ch);
+}
+
+uint16_t HAL_adc_get_result() {
+  // nop
+  return HAL_adc_result;
+}
+
 // Forward the default serial ports
 #if USING_HW_SERIAL0
   DefaultSerial1 MSerial0(false, Serial);
diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h
index 96a59fcf3c..96ab5d9808 100644
--- a/Marlin/src/HAL/DUE/HAL.h
+++ b/Marlin/src/HAL/DUE/HAL.h
@@ -38,10 +38,6 @@
 
 #include "../../core/serial_hook.h"
 
-// ------------------------
-// Serial ports
-// ------------------------
-
 typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1;
 typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2;
 typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3;
@@ -101,38 +97,60 @@ extern DefaultSerial4 MSerial3;
 #include "MarlinSerial.h"
 #include "MarlinSerialUSB.h"
 
-// ------------------------
-// Types
-// ------------------------
+// On AVR this is in math.h?
+#define square(x) ((x)*(x))
 
 typedef int8_t pin_t;
 
-// Use shared/servos.cpp
 #define SHARED_SERVOS HAS_SERVOS
-class Servo;
-typedef Servo hal_servo_t;
+#define HAL_SERVO_LIB Servo
 
 //
 // Interrupts
 //
-#define sei() noInterrupts()
-#define cli() interrupts()
+#define CRITICAL_SECTION_START()  uint32_t primask = __get_PRIMASK(); __disable_irq()
+#define CRITICAL_SECTION_END()    if (!primask) __enable_irq()
+#define ISRS_ENABLED() (!__get_PRIMASK())
+#define ENABLE_ISRS()  __enable_irq()
+#define DISABLE_ISRS() __disable_irq()
 
-#define CRITICAL_SECTION_START()  const bool _irqon = hal.isr_state(); hal.isr_off()
-#define CRITICAL_SECTION_END()    if (_irqon) hal.isr_on()
+void cli();                     // Disable interrupts
+void sei();                     // Enable interrupts
+
+void HAL_clear_reset_source();  // clear reset reason
+uint8_t HAL_get_reset_source(); // get reset reason
+
+void HAL_reboot();
 
 //
 // ADC
 //
-#define HAL_ADC_VREF         3.3
-#define HAL_ADC_RESOLUTION  10
+extern uint16_t HAL_adc_result;     // result of last ADC conversion
 
 #ifndef analogInputToDigitalPin
   #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
 #endif
 
+#define HAL_ANALOG_SELECT(ch)
+
+inline void HAL_adc_init() {}//todo
+
+#define HAL_ADC_VREF         3.3
+#define HAL_ADC_RESOLUTION  10
+#define HAL_START_ADC(ch)   HAL_adc_start_conversion(ch)
+#define HAL_READ_ADC()      HAL_adc_result
+#define HAL_ADC_READY()     true
+
+void HAL_adc_start_conversion(const uint8_t ch);
+uint16_t HAL_adc_get_result();
+
 //
-// Pin Mapping for M42, M43, M226
+// PWM
+//
+inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
+
+//
+// Pin Map
 //
 #define GET_PIN_MAP_PIN(index) index
 #define GET_PIN_MAP_INDEX(pin) pin
@@ -141,18 +159,27 @@ typedef Servo hal_servo_t;
 //
 // Tone
 //
+void toneInit();
 void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0);
 void noTone(const pin_t _pin);
 
-// ------------------------
-// Class Utilities
-// ------------------------
+// Enable hooks into idle and setup for HAL
+#define HAL_IDLETASK 1
+void HAL_idletask();
+void HAL_init();
+
+//
+// Utility functions
+//
+void _delay_ms(const int delay);
 
 #pragma GCC diagnostic push
 #if GCC_VERSION <= 50000
   #pragma GCC diagnostic ignored "-Wunused-function"
 #endif
 
+int freeMemory();
+
 #pragma GCC diagnostic pop
 
 #ifdef __cplusplus
@@ -162,70 +189,3 @@ char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s
 #ifdef __cplusplus
   }
 #endif
-
-// Return free RAM between end of heap (or end bss) and whatever is current
-int freeMemory();
-
-// ------------------------
-// MarlinHAL Class
-// ------------------------
-
-class MarlinHAL {
-public:
-
-  // Earliest possible init, before setup()
-  MarlinHAL() {}
-
-  static void init();       // Called early in setup()
-  static void init_board(); // Called less early in setup()
-  static void reboot();     // Software reset
-
-  static inline bool isr_state() { return !__get_PRIMASK(); }
-  static inline void isr_on()  { __enable_irq(); }
-  static inline void isr_off() { __disable_irq(); }
-
-  static inline void delay_ms(const int ms) { delay(ms); }
-
-  // Tasks, called from idle()
-  static void idletask();
-
-  // Reset
-  static uint8_t get_reset_source();
-  static inline void clear_reset_source() {}
-
-  // Free SRAM
-  static inline int freeMemory() { return ::freeMemory(); }
-
-  //
-  // ADC Methods
-  //
-
-  static uint16_t adc_result;
-
-  // Called by Temperature::init once at startup
-  static inline void adc_init() {}
-
-  // Called by Temperature::init for each sensor at startup
-  static inline void adc_enable(const int ch) {}
-
-  // Begin ADC sampling on the given channel
-  static inline void adc_start(const uint8_t ch) { adc_result = analogRead(ch); }
-
-  // Is the ADC ready for reading?
-  static inline bool adc_ready() { return true; }
-
-  // The current value of the ADC register
-  static inline uint16_t adc_value() { return adc_result; }
-
-  /**
-   * Set the PWM duty cycle for the pin to the given value.
-   * No inverting the duty cycle in this HAL.
-   * No changing the maximum size of the provided value to enable finer PWM duty control in this HAL.
-   */
-  static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
-    analogWrite(pin, v);
-  }
-
-};
-
-extern MarlinHAL hal;
diff --git a/Marlin/src/HAL/DUE/MarlinSerial.cpp b/Marlin/src/HAL/DUE/MarlinSerial.cpp
index 638f7a1007..fe62ff5607 100644
--- a/Marlin/src/HAL/DUE/MarlinSerial.cpp
+++ b/Marlin/src/HAL/DUE/MarlinSerial.cpp
@@ -406,7 +406,7 @@ size_t MarlinSerial<Cfg>::write(const uint8_t c) {
     const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1);
 
     // If global interrupts are disabled (as the result of being called from an ISR)...
-    if (!hal.isr_state()) {
+    if (!ISRS_ENABLED()) {
 
       // Make room by polling if it is possible to transmit, and do so!
       while (i == tx_buffer.tail) {
@@ -454,7 +454,7 @@ void MarlinSerial<Cfg>::flushTX() {
     if (!_written) return;
 
     // If global interrupts are disabled (as the result of being called from an ISR)...
-    if (!hal.isr_state()) {
+    if (!ISRS_ENABLED()) {
 
       // Wait until everything was transmitted - We must do polling, as interrupts are disabled
       while (tx_buffer.head != tx_buffer.tail || !(HWUART->UART_SR & UART_SR_TXEMPTY)) {
diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h
index bcfd07e268..e2932ff36f 100644
--- a/Marlin/src/HAL/DUE/timers.h
+++ b/Marlin/src/HAL/DUE/timers.h
@@ -125,4 +125,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
   pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_SR;
 }
 
-#define HAL_timer_isr_epilogue(T) NOOP
+#define HAL_timer_isr_epilogue(T)
diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp
index 604acae8dd..810e386894 100644
--- a/Marlin/src/HAL/ESP32/HAL.cpp
+++ b/Marlin/src/HAL/ESP32/HAL.cpp
@@ -52,7 +52,7 @@
 // Externs
 // ------------------------
 
-portMUX_TYPE MarlinHAL::spinlock = portMUX_INITIALIZER_UNLOCKED;
+portMUX_TYPE spinlock = portMUX_INITIALIZER_UNLOCKED;
 
 // ------------------------
 // Local defines
@@ -64,7 +64,7 @@ portMUX_TYPE MarlinHAL::spinlock = portMUX_INITIALIZER_UNLOCKED;
 // Public Variables
 // ------------------------
 
-uint16_t MarlinHAL::adc_result;
+uint16_t HAL_adc_result;
 
 // ------------------------
 // Private Variables
@@ -95,22 +95,20 @@ volatile int numPWMUsed = 0,
 #endif
 
 #if ENABLED(USE_ESP32_EXIO)
-
   HardwareSerial YSerial2(2);
 
   void Write_EXIO(uint8_t IO, uint8_t v) {
-    if (hal.isr_state()) {
-      hal.isr_off();
+    if (ISRS_ENABLED()) {
+      DISABLE_ISRS();
       YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100));
-      hal.isr_on();
+      ENABLE_ISRS();
     }
     else
       YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100));
   }
-
 #endif
 
-void MarlinHAL::init_board() {
+void HAL_init_board() {
   #if ENABLED(USE_ESP32_TASK_WDT)
     esp_task_wdt_init(10, true);
   #endif
@@ -156,24 +154,27 @@ void MarlinHAL::init_board() {
   #endif
 }
 
-void MarlinHAL::idletask() {
+void HAL_idletask() {
   #if BOTH(WIFISUPPORT, OTASUPPORT)
     OTA_handle();
   #endif
   TERN_(ESP3D_WIFISUPPORT, esp3dlib.idletask());
 }
 
-uint8_t MarlinHAL::get_reset_source() { return rtc_get_reset_reason(1); }
+void HAL_clear_reset_source() { }
 
-void MarlinHAL::reboot() { ESP.restart(); }
+uint8_t HAL_get_reset_source() { return rtc_get_reset_reason(1); }
+
+void HAL_reboot() { ESP.restart(); }
+
+void _delay_ms(int delay_ms) { delay(delay_ms); }
 
 // return free memory between end of heap (or end bss) and whatever is current
-int MarlinHAL::freeMemory() { return ESP.getFreeHeap(); }
+int freeMemory() { return ESP.getFreeHeap(); }
 
 // ------------------------
 // ADC
 // ------------------------
-
 #define ADC1_CHANNEL(pin) ADC1_GPIO ## pin ## _CHANNEL
 
 adc1_channel_t get_channel(int pin) {
@@ -195,7 +196,7 @@ void adc1_set_attenuation(adc1_channel_t chan, adc_atten_t atten) {
   }
 }
 
-void MarlinHAL::adc_init() {
+void HAL_adc_init() {
   // Configure ADC
   adc1_config_width(ADC_WIDTH_12Bit);
 
@@ -225,11 +226,11 @@ void MarlinHAL::adc_init() {
   }
 }
 
-void MarlinHAL::adc_start(const pin_t pin) {
-  const adc1_channel_t chan = get_channel(pin);
+void HAL_adc_start_conversion(const uint8_t adc_pin) {
+  const adc1_channel_t chan = get_channel(adc_pin);
   uint32_t mv;
   esp_adc_cal_get_voltage((adc_channel_t)chan, &characteristics[attenuations[chan]], &mv);
-  adc_result = mv * 1023.0 / 3300.0;
+  HAL_adc_result = mv * 1023.0 / 3300.0;
 
   // Change the attenuation level based on the new reading
   adc_atten_t atten;
diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h
index 138346b950..8473e3c4e4 100644
--- a/Marlin/src/HAL/ESP32/HAL.h
+++ b/Marlin/src/HAL/ESP32/HAL.h
@@ -49,6 +49,8 @@
 // Defines
 // ------------------------
 
+extern portMUX_TYPE spinlock;
+
 #define MYSERIAL1 flushableSerial
 
 #if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT)
@@ -63,6 +65,9 @@
 
 #define CRITICAL_SECTION_START() portENTER_CRITICAL(&spinlock)
 #define CRITICAL_SECTION_END()   portEXIT_CRITICAL(&spinlock)
+#define ISRS_ENABLED() (spinlock.owner == portMUX_FREE_VAL)
+#define ENABLE_ISRS()  if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock)
+#define DISABLE_ISRS() portENTER_CRITICAL(&spinlock)
 
 // ------------------------
 // Types
@@ -70,8 +75,14 @@
 
 typedef int16_t pin_t;
 
-class Servo;
-typedef Servo hal_servo_t;
+#define HAL_SERVO_LIB Servo
+
+// ------------------------
+// Public Variables
+// ------------------------
+
+/** result of last ADC conversion */
+extern uint16_t HAL_adc_result;
 
 // ------------------------
 // Public functions
@@ -80,18 +91,59 @@ typedef Servo hal_servo_t;
 //
 // Tone
 //
+void toneInit();
 void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0);
 void noTone(const pin_t _pin);
 
+// clear reset reason
+void HAL_clear_reset_source();
+
+// reset reason
+uint8_t HAL_get_reset_source();
+
+void HAL_reboot();
+
+void _delay_ms(int delay);
+
+#pragma GCC diagnostic push
+#if GCC_VERSION <= 50000
+  #pragma GCC diagnostic ignored "-Wunused-function"
+#endif
+
+int freeMemory();
+
+#pragma GCC diagnostic pop
+
 void analogWrite(pin_t pin, int value);
 
-//
-// Pin Mapping for M42, M43, M226
-//
+// ADC
+#define HAL_ANALOG_SELECT(pin)
+
+void HAL_adc_init();
+
+#define HAL_ADC_VREF         3.3
+#define HAL_ADC_RESOLUTION  10
+#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
+#define HAL_READ_ADC()      HAL_adc_result
+#define HAL_ADC_READY()     true
+
+void HAL_adc_start_conversion(const uint8_t adc_pin);
+
+// PWM
+inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
+
+// Pin Map
 #define GET_PIN_MAP_PIN(index) index
 #define GET_PIN_MAP_INDEX(pin) pin
 #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
 
+// Enable hooks into idle and setup for HAL
+#define HAL_IDLETASK 1
+#define BOARD_INIT() HAL_init_board();
+void HAL_idletask();
+inline void HAL_init() {}
+void HAL_init_board();
+
 #if ENABLED(USE_ESP32_EXIO)
   void Write_EXIO(uint8_t IO, uint8_t v);
 #endif
@@ -136,86 +188,3 @@ FORCE_INLINE static void DELAY_CYCLES(uint32_t x) {
   }
 
 }
-
-// ------------------------
-// Class Utilities
-// ------------------------
-
-#pragma GCC diagnostic push
-#if GCC_VERSION <= 50000
-  #pragma GCC diagnostic ignored "-Wunused-function"
-#endif
-
-int freeMemory();
-
-#pragma GCC diagnostic pop
-
-void _delay_ms(const int ms);
-
-// ------------------------
-// MarlinHAL Class
-// ------------------------
-
-#define HAL_ADC_VREF         3.3
-#define HAL_ADC_RESOLUTION  10
-
-class MarlinHAL {
-public:
-
-  // Earliest possible init, before setup()
-  MarlinHAL() {}
-
-  static inline void init() {}  // Called early in setup()
-  static void init_board();     // Called less early in setup()
-  static void reboot();         // Restart the firmware
-
-  static portMUX_TYPE spinlock;
-  static inline bool isr_state() { return spinlock.owner == portMUX_FREE_VAL; }
-  static inline void isr_on()  { if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock); }
-  static inline void isr_off() { portENTER_CRITICAL(&spinlock); }
-
-  static inline void delay_ms(const int ms) { _delay_ms(ms); }
-
-  // Tasks, called from idle()
-  static void idletask();
-
-  // Reset
-  static uint8_t get_reset_source();
-  static inline void clear_reset_source() {}
-
-  // Free SRAM
-  static int freeMemory();
-
-  //
-  // ADC Methods
-  //
-
-  static uint16_t adc_result;
-
-  // Called by Temperature::init once at startup
-  static void adc_init();
-
-  // Called by Temperature::init for each sensor at startup
-  static inline void adc_enable(const pin_t pin) {}
-
-  // Begin ADC sampling on the given channel
-  static void adc_start(const pin_t pin);
-
-  // Is the ADC ready for reading?
-  static inline bool adc_ready() { return true; }
-
-  // The current value of the ADC register
-  static inline uint16_t adc_value() { return adc_result; }
-
-  /**
-   * Set the PWM duty cycle for the pin to the given value.
-   * No inverting the duty cycle in this HAL.
-   * No changing the maximum size of the provided value to enable finer PWM duty control in this HAL.
-   */
-  static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
-    analogWrite(pin, v);
-  }
-
-};
-
-extern MarlinHAL hal;
diff --git a/Marlin/src/HAL/ESP32/timers.h b/Marlin/src/HAL/ESP32/timers.h
index efae594f6c..266169848d 100644
--- a/Marlin/src/HAL/ESP32/timers.h
+++ b/Marlin/src/HAL/ESP32/timers.h
@@ -136,5 +136,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num);
 void HAL_timer_disable_interrupt(const uint8_t timer_num);
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
 
-#define HAL_timer_isr_prologue(T) NOOP
-#define HAL_timer_isr_epilogue(T) NOOP
+#define HAL_timer_isr_prologue(T)
+#define HAL_timer_isr_epilogue(T)
diff --git a/Marlin/src/HAL/LINUX/HAL.cpp b/Marlin/src/HAL/LINUX/HAL.cpp
index 91739aaa7b..0b679170ef 100644
--- a/Marlin/src/HAL/LINUX/HAL.cpp
+++ b/Marlin/src/HAL/LINUX/HAL.cpp
@@ -24,12 +24,6 @@
 #include "../../inc/MarlinConfig.h"
 #include "../shared/Delay.h"
 
-extern MarlinHAL hal;
-
-// ------------------------
-// Serial ports
-// ------------------------
-
 MSerialT usb_serial(TERN0(EMERGENCY_PARSER, true));
 
 // U8glib required functions
@@ -43,21 +37,42 @@ extern "C" {
 //************************//
 
 // return free heap space
-int freeMemory() { return 0; }
+int freeMemory() {
+  return 0;
+}
 
 // ------------------------
 // ADC
 // ------------------------
 
-uint8_t MarlinHAL::active_ch = 0;
+void HAL_adc_init() {
 
-uint16_t MarlinHAL::adc_value() {
-  const pin_t pin = analogInputToDigitalPin(active_ch);
+}
+
+void HAL_adc_enable_channel(const uint8_t ch) {
+
+}
+
+uint8_t active_ch = 0;
+void HAL_adc_start_conversion(const uint8_t ch) {
+  active_ch = ch;
+}
+
+bool HAL_adc_finished() {
+  return true;
+}
+
+uint16_t HAL_adc_get_result() {
+  pin_t pin = analogInputToDigitalPin(active_ch);
   if (!VALID_PIN(pin)) return 0;
-  const uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF);
+  uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF);
   return data;    // return 10bit value as Marlin expects
 }
 
-void MarlinHAL::reboot() { /* Reset the application state and GPIO */ }
+void HAL_pwm_init() {
+
+}
+
+void HAL_reboot() { /* Reset the application state and GPIO */ }
 
 #endif // __PLAT_LINUX__
diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h
index 104c47ec61..d7d3a92b73 100644
--- a/Marlin/src/HAL/LINUX/HAL.h
+++ b/Marlin/src/HAL/LINUX/HAL.h
@@ -21,42 +21,25 @@
  */
 #pragma once
 
-#include <iostream>
-#include <stdint.h>
-#include <stdarg.h>
-#undef min
-#undef max
-#include <algorithm>
-
-#include "hardware/Clock.h"
-
-#include "../shared/Marduino.h"
-#include "../shared/math_32bit.h"
-#include "../shared/HAL_SPI.h"
-#include "fastio.h"
-#include "watchdog.h"
-#include "serial.h"
-
-// ------------------------
-// Defines
-// ------------------------
-
 #define CPU_32_BIT
-#define SHARED_SERVOS HAS_SERVOS  // Use shared/servos.cpp
 
 #define F_CPU 100000000UL
 #define SystemCoreClock F_CPU
+#include <iostream>
+#include <stdint.h>
+#include <stdarg.h>
 
-#define DELAY_CYCLES(x) Clock::delayCycles(x)
+#undef min
+#undef max
 
-#define CPU_ST7920_DELAY_1 600
-#define CPU_ST7920_DELAY_2 750
-#define CPU_ST7920_DELAY_3 750
+#include <algorithm>
 
-void _printf(const  char *format, ...);
+void _printf (const  char *format, ...);
 void _putc(uint8_t c);
 uint8_t _getc();
 
+//extern "C" volatile uint32_t _millis;
+
 //arduino: Print.h
 #define DEC 10
 #define HEX 16
@@ -66,27 +49,36 @@ uint8_t _getc();
 #define B01 1
 #define B10 2
 
-// ------------------------
-// Serial ports
-// ------------------------
+#include "hardware/Clock.h"
+
+#include "../shared/Marduino.h"
+#include "../shared/math_32bit.h"
+#include "../shared/HAL_SPI.h"
+#include "fastio.h"
+#include "watchdog.h"
+#include "serial.h"
+
+#define SHARED_SERVOS HAS_SERVOS
 
 extern MSerialT usb_serial;
 #define MYSERIAL1 usb_serial
 
+#define CPU_ST7920_DELAY_1 600
+#define CPU_ST7920_DELAY_2 750
+#define CPU_ST7920_DELAY_3 750
+
 //
 // Interrupts
 //
 #define CRITICAL_SECTION_START()
 #define CRITICAL_SECTION_END()
+#define ISRS_ENABLED()
+#define ENABLE_ISRS()
+#define DISABLE_ISRS()
 
-// ADC
-#define HAL_ADC_VREF           5.0
-#define HAL_ADC_RESOLUTION    10
-
-// ------------------------
-// Class Utilities
-// ------------------------
+inline void HAL_init() {}
 
+// Utility functions
 #pragma GCC diagnostic push
 #if GCC_VERSION <= 50000
   #pragma GCC diagnostic ignored "-Wunused-function"
@@ -96,67 +88,29 @@ int freeMemory();
 
 #pragma GCC diagnostic pop
 
-// ------------------------
-// MarlinHAL Class
-// ------------------------
+// ADC
+#define HAL_ADC_VREF           5.0
+#define HAL_ADC_RESOLUTION    10
+#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch)
+#define HAL_START_ADC(ch)     HAL_adc_start_conversion(ch)
+#define HAL_READ_ADC()        HAL_adc_get_result()
+#define HAL_ADC_READY()       true
 
-class MarlinHAL {
-public:
+void HAL_adc_init();
+void HAL_adc_enable_channel(const uint8_t ch);
+void HAL_adc_start_conversion(const uint8_t ch);
+uint16_t HAL_adc_get_result();
 
-  // Earliest possible init, before setup()
-  MarlinHAL() {}
+// PWM
+inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
 
-  static inline void init() {}        // Called early in setup()
-  static inline void init_board() {}  // Called less early in setup()
-  static void reboot();               // Reset the application state and GPIO
+// Reset source
+inline void HAL_clear_reset_source(void) {}
+inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; }
 
-  static inline bool isr_state() { return true; }
-  static inline void isr_on()  {}
-  static inline void isr_off() {}
+void HAL_reboot(); // Reset the application state and GPIO
 
-  static inline void delay_ms(const int ms) { _delay_ms(ms); }
-
-  // Tasks, called from idle()
-  static inline void idletask() {}
-
-  // Reset
-  static constexpr uint8_t reset_reason = RST_POWER_ON;
-  static inline uint8_t get_reset_source() { return reset_reason; }
-  static inline void clear_reset_source() {}
-
-  // Free SRAM
-  static inline int freeMemory() { return ::freeMemory(); }
-
-  //
-  // ADC Methods
-  //
-
-  static uint8_t active_ch;
-
-  // Called by Temperature::init once at startup
-  static inline void adc_init() {}
-
-  // Called by Temperature::init for each sensor at startup
-  static inline void adc_enable(const uint8_t) {}
-
-  // Begin ADC sampling on the given channel
-  static inline void adc_start(const uint8_t ch) { active_ch = ch; }
-
-  // Is the ADC ready for reading?
-  static inline bool adc_ready() { return true; }
-
-  // The current value of the ADC register
-  static uint16_t adc_value();
-
-  /**
-   * Set the PWM duty cycle for the pin to the given value.
-   * No option to change the resolution or invert the duty cycle.
-   */
-  static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
-    analogWrite(pin, v);
-  }
-
-  static inline void set_pwm_frequency(const pin_t, int) {}
-};
-
-extern MarlinHAL hal;
+/* ---------------- Delay in cycles */
+FORCE_INLINE static void DELAY_CYCLES(uint64_t x) {
+  Clock::delayCycles(x);
+}
diff --git a/Marlin/src/HAL/LINUX/arduino.cpp b/Marlin/src/HAL/LINUX/arduino.cpp
index 075b4ccde2..4b56d02a38 100644
--- a/Marlin/src/HAL/LINUX/arduino.cpp
+++ b/Marlin/src/HAL/LINUX/arduino.cpp
@@ -31,7 +31,9 @@ void cli() { } // Disable
 void sei() { } // Enable
 
 // Time functions
-void _delay_ms(const int ms) { delay(ms); }
+void _delay_ms(const int delay_ms) {
+  delay(delay_ms);
+}
 
 uint32_t millis() {
   return (uint32_t)Clock::millis();
diff --git a/Marlin/src/HAL/LINUX/include/Arduino.h b/Marlin/src/HAL/LINUX/include/Arduino.h
index 49e04d0cb7..d4086e259a 100644
--- a/Marlin/src/HAL/LINUX/include/Arduino.h
+++ b/Marlin/src/HAL/LINUX/include/Arduino.h
@@ -59,6 +59,7 @@ typedef uint8_t byte;
 #endif
 
 #define sq(v) ((v) * (v))
+#define square(v) sq(v)
 #define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value)))
 
 //Interrupts
@@ -73,8 +74,8 @@ extern "C" {
 }
 
 // Time functions
-extern "C" void delay(const int ms);
-void _delay_ms(const int ms);
+extern "C" void delay(const int milis);
+void _delay_ms(const int delay);
 void delayMicroseconds(unsigned long);
 uint32_t millis();
 
diff --git a/Marlin/src/HAL/LINUX/timers.h b/Marlin/src/HAL/LINUX/timers.h
index 2d2a95774c..a98ceb6f39 100644
--- a/Marlin/src/HAL/LINUX/timers.h
+++ b/Marlin/src/HAL/LINUX/timers.h
@@ -92,5 +92,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num);
 void HAL_timer_disable_interrupt(const uint8_t timer_num);
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
 
-#define HAL_timer_isr_prologue(T) NOOP
-#define HAL_timer_isr_epilogue(T) NOOP
+#define HAL_timer_isr_prologue(T)
+#define HAL_timer_isr_epilogue(T)
diff --git a/Marlin/src/HAL/LPC1768/HAL.cpp b/Marlin/src/HAL/LPC1768/HAL.cpp
index 541848b08a..cee9cfc5f7 100644
--- a/Marlin/src/HAL/LPC1768/HAL.cpp
+++ b/Marlin/src/HAL/LPC1768/HAL.cpp
@@ -31,7 +31,7 @@
 
 DefaultSerial1 USBSerial(false, UsbSerial);
 
-uint32_t MarlinHAL::adc_result = 0;
+uint32_t HAL_adc_reading = 0;
 
 // U8glib required functions
 extern "C" {
@@ -41,6 +41,8 @@ extern "C" {
   void u8g_Delay(uint16_t val)       { delay(val); }
 }
 
+//************************//
+
 // return free heap space
 int freeMemory() {
   char stack_end;
@@ -52,27 +54,7 @@ int freeMemory() {
   return result;
 }
 
-void MarlinHAL::reboot() { NVIC_SystemReset(); }
-
-uint8_t MarlinHAL::get_reset_source() {
-  #if ENABLED(USE_WATCHDOG)
-    if (watchdog_timed_out()) return RST_WATCHDOG;
-  #endif
-  return RST_POWER_ON;
-}
-
-void MarlinHAL::clear_reset_source() {
-  TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag());
-}
-
-void flashFirmware(const int16_t) {
-  delay(500);          // Give OS time to disconnect
-  USB_Connect(false);  // USB clear connection
-  delay(1000);         // Give OS time to notice
-  hal.reboot();
-}
-
-// For M42/M43, scan command line for pin code
+// scan command line for code
 //   return index into pin map array if found and the pin is valid.
 //   return dval if not found or not a valid pin.
 int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
@@ -81,4 +63,24 @@ int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
   return ind > -1 ? ind : dval;
 }
 
+void flashFirmware(const int16_t) {
+  delay(500);          // Give OS time to disconnect
+  USB_Connect(false);  // USB clear connection
+  delay(1000);         // Give OS time to notice
+  HAL_reboot();
+}
+
+void HAL_clear_reset_source(void) {
+  TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag());
+}
+
+uint8_t HAL_get_reset_source(void) {
+  #if ENABLED(USE_WATCHDOG)
+    if (watchdog_timed_out()) return RST_WATCHDOG;
+  #endif
+  return RST_POWER_ON;
+}
+
+void HAL_reboot() { NVIC_SystemReset(); }
+
 #endif // TARGET_LPC1768
diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h
index e1ade3d9a7..348ea6b21a 100644
--- a/Marlin/src/HAL/LPC1768/HAL.h
+++ b/Marlin/src/HAL/LPC1768/HAL.h
@@ -28,6 +28,8 @@
 
 #define CPU_32_BIT
 
+void HAL_init();
+
 #include <stdint.h>
 #include <stdarg.h>
 #include <algorithm>
@@ -45,9 +47,12 @@ extern "C" volatile uint32_t _millis;
 #include <pinmapping.h>
 #include <CDCSerial.h>
 
-// ------------------------
-// Serial ports
-// ------------------------
+//
+// Default graphical display delays
+//
+#define CPU_ST7920_DELAY_1 600
+#define CPU_ST7920_DELAY_2 750
+#define CPU_ST7920_DELAY_3 750
 
 typedef ForwardSerial1Class< decltype(UsbSerial) > DefaultSerial1;
 extern DefaultSerial1 USBSerial;
@@ -109,12 +114,26 @@ extern DefaultSerial1 USBSerial;
 //
 // Interrupts
 //
-
-#define CRITICAL_SECTION_START()  const bool irqon = !__get_PRIMASK(); __disable_irq()
-#define CRITICAL_SECTION_END()    if (irqon) __enable_irq()
+#define CRITICAL_SECTION_START()  uint32_t primask = __get_PRIMASK(); __disable_irq()
+#define CRITICAL_SECTION_END()    if (!primask) __enable_irq()
+#define ISRS_ENABLED() (!__get_PRIMASK())
+#define ENABLE_ISRS()  __enable_irq()
+#define DISABLE_ISRS() __disable_irq()
 
 //
-// ADC
+// Utility functions
+//
+#pragma GCC diagnostic push
+#if GCC_VERSION <= 50000
+  #pragma GCC diagnostic ignored "-Wunused-function"
+#endif
+
+int freeMemory();
+
+#pragma GCC diagnostic pop
+
+//
+// ADC API
 //
 
 #define ADC_MEDIAN_FILTER_SIZE (23) // Higher values increase step delay (phase shift),
@@ -133,9 +152,20 @@ extern DefaultSerial1 USBSerial;
 #define HAL_ADC_RESOLUTION     12   // 15 bit maximum, raw temperature is stored as int16_t
 #define HAL_ADC_FILTERED            // Disable oversampling done in Marlin as ADC values already filtered in HAL
 
-//
-// Pin Mapping for M42, M43, M226
-//
+using FilteredADC = LPC176x::ADC<ADC_LOWPASS_K_VALUE, ADC_MEDIAN_FILTER_SIZE>;
+extern uint32_t HAL_adc_reading;
+[[gnu::always_inline]] inline void HAL_adc_start_conversion(const pin_t pin) {
+  HAL_adc_reading = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits
+}
+[[gnu::always_inline]] inline uint16_t HAL_adc_get_result() {
+  return HAL_adc_reading;
+}
+
+#define HAL_adc_init()
+#define HAL_ANALOG_SELECT(pin) FilteredADC::enable_channel(pin)
+#define HAL_START_ADC(pin)     HAL_adc_start_conversion(pin)
+#define HAL_READ_ADC()         HAL_adc_get_result()
+#define HAL_ADC_READY()        (true)
 
 // Test whether the pin is valid
 constexpr bool VALID_PIN(const pin_t pin) {
@@ -162,104 +192,32 @@ int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
 // P0.6 thru P0.9 are for the onboard SD card
 #define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09,
 
-// ------------------------
-// Defines
-// ------------------------
+#define HAL_IDLETASK 1
+void HAL_idletask();
 
 #define PLATFORM_M997_SUPPORT
 void flashFirmware(const int16_t);
 
 #define HAL_CAN_SET_PWM_FREQ   // This HAL supports PWM Frequency adjustment
 
-// Default graphical display delays
-#define CPU_ST7920_DELAY_1 600
-#define CPU_ST7920_DELAY_2 750
-#define CPU_ST7920_DELAY_3 750
+/**
+ * set_pwm_frequency
+ *  Set the frequency of the timer corresponding to the provided pin
+ *  All Hardware PWM pins run at the same frequency and all
+ *  Software PWM pins run at the same frequency
+ */
+void set_pwm_frequency(const pin_t pin, int f_desired);
 
-// ------------------------
-// Class Utilities
-// ------------------------
+/**
+ * set_pwm_duty
+ *  Set the PWM duty cycle of the provided pin to the provided value
+ *  Optionally allows inverting the duty cycle [default = false]
+ *  Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255]
+ */
+void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
 
-#pragma GCC diagnostic push
-#if GCC_VERSION <= 50000
-  #pragma GCC diagnostic ignored "-Wunused-function"
-#endif
+// Reset source
+void HAL_clear_reset_source(void);
+uint8_t HAL_get_reset_source(void);
 
-int freeMemory();
-
-#pragma GCC diagnostic pop
-
-// ------------------------
-// MarlinHAL Class
-// ------------------------
-
-class MarlinHAL {
-public:
-
-  // Earliest possible init, before setup()
-  MarlinHAL() {}
-
-  static void init();                 // Called early in setup()
-  static inline void init_board() {}  // Called less early in setup()
-  static void reboot();               // Restart the firmware from 0x0
-
-  static inline bool isr_state() { return !__get_PRIMASK(); }
-  static inline void isr_on()  { __enable_irq(); }
-  static inline void isr_off() { __disable_irq(); }
-
-  static inline void delay_ms(const int ms) { _delay_ms(ms); }
-
-  // Tasks, called from idle()
-  static void idletask();
-
-  // Reset
-  static uint8_t get_reset_source();
-  static void clear_reset_source();
-
-  // Free SRAM
-  static inline int freeMemory() { return ::freeMemory(); }
-
-  //
-  // ADC Methods
-  //
-
-  using FilteredADC = LPC176x::ADC<ADC_LOWPASS_K_VALUE, ADC_MEDIAN_FILTER_SIZE>;
-
-  // Called by Temperature::init once at startup
-  static inline void adc_init() {}
-
-  // Called by Temperature::init for each sensor at startup
-  static inline void adc_enable(const pin_t pin) {
-    FilteredADC::enable_channel(pin);
-  }
-
-  // Begin ADC sampling on the given pin
-  static uint32_t adc_result;
-  FORCE_INLINE static void adc_start(const pin_t pin) {
-    adc_result = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits
-  }
-
-  // Is the ADC ready for reading?
-  static inline bool adc_ready() { return true; }
-
-  // The current value of the ADC register
-  FORCE_INLINE static uint16_t adc_value() {
-    return (uint16_t)adc_result;
-  }
-
-  /**
-   * Set the PWM duty cycle for the pin to the given value.
-   * Optionally invert the duty cycle [default = false]
-   * Optionally change the scale of the provided value to enable finer PWM duty control [default = 255]
-   */
-  static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
-
-  /**
-   * Set the frequency of the timer corresponding to the provided pin
-   * All Hardware PWM pins will run at the same frequency and
-   * All Software PWM pins will run at the same frequency
-   */
-  static void set_pwm_frequency(const pin_t pin, int f_desired);
-};
-
-extern MarlinHAL hal;
+void HAL_reboot();
diff --git a/Marlin/src/HAL/LPC1768/Servo.h b/Marlin/src/HAL/LPC1768/Servo.h
index f02f503a67..eb12fd20f4 100644
--- a/Marlin/src/HAL/LPC1768/Servo.h
+++ b/Marlin/src/HAL/LPC1768/Servo.h
@@ -65,5 +65,4 @@ class libServo: public Servo {
   }
 };
 
-class libServo;
-typedef libServo hal_servo_t;
+#define HAL_SERVO_LIB libServo
diff --git a/Marlin/src/HAL/LPC1768/fast_pwm.cpp b/Marlin/src/HAL/LPC1768/fast_pwm.cpp
index 91e92a1575..eae0e36b0b 100644
--- a/Marlin/src/HAL/LPC1768/fast_pwm.cpp
+++ b/Marlin/src/HAL/LPC1768/fast_pwm.cpp
@@ -21,17 +21,21 @@
  */
 #ifdef TARGET_LPC1768
 
-#include "../../inc/MarlinConfig.h"
+#include "../../inc/MarlinConfigPre.h"
 #include <pwm.h>
 
-void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
+void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
   if (!LPC176x::pin_is_valid(pin)) return;
   if (LPC176x::pwm_attach_pin(pin))
     LPC176x::pwm_write_ratio(pin, invert ? 1.0f - (float)v / v_size : (float)v / v_size);  // map 1-254 onto PWM range
 }
 
-void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) {
-  LPC176x::pwm_set_frequency(pin, f_desired);
-}
+#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM
+
+  void set_pwm_frequency(const pin_t pin, int f_desired) {
+    LPC176x::pwm_set_frequency(pin, f_desired);
+  }
+
+#endif
 
 #endif // TARGET_LPC1768
diff --git a/Marlin/src/HAL/LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp
index 419c99793f..ef0dc42c78 100644
--- a/Marlin/src/HAL/LPC1768/main.cpp
+++ b/Marlin/src/HAL/LPC1768/main.cpp
@@ -48,7 +48,7 @@ void SysTick_Callback() { disk_timerproc(); }
 
 TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
 
-void MarlinHAL::init() {
+void HAL_init() {
 
   // Init LEDs
   #if PIN_EXISTS(LED)
@@ -130,7 +130,7 @@ void MarlinHAL::init() {
   const millis_t usb_timeout = millis() + 2000;
   while (!USB_Configuration && PENDING(millis(), usb_timeout)) {
     delay(50);
-    idletask();
+    HAL_idletask();
     #if PIN_EXISTS(LED)
       TOGGLE(LED_PIN);     // Flash quickly during USB initialization
     #endif
@@ -142,7 +142,7 @@ void MarlinHAL::init() {
 }
 
 // HAL idle task
-void MarlinHAL::idletask() {
+void HAL_idletask() {
   #if HAS_SHARED_MEDIA
     // If Marlin is using the SD card we need to lock it to prevent access from
     // a PC via USB.
diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h
index c6d7bc632e..78e856db28 100644
--- a/Marlin/src/HAL/LPC1768/timers.h
+++ b/Marlin/src/HAL/LPC1768/timers.h
@@ -170,4 +170,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
   }
 }
 
-#define HAL_timer_isr_epilogue(T) NOOP
+#define HAL_timer_isr_epilogue(T)
diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h
index 50da5af2eb..436b4b4daa 100644
--- a/Marlin/src/HAL/NATIVE_SIM/HAL.h
+++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h
@@ -21,10 +21,18 @@
  */
 #pragma once
 
+#define CPU_32_BIT
+#define HAL_IDLETASK
+void HAL_idletask();
+
+#define F_CPU 100000000
+#define SystemCoreClock F_CPU
 #include <stdint.h>
 #include <stdarg.h>
+
 #undef min
 #undef max
+
 #include <algorithm>
 #include "pinmapping.h"
 
@@ -32,6 +40,8 @@ void _printf (const  char *format, ...);
 void _putc(uint8_t c);
 uint8_t _getc();
 
+//extern "C" volatile uint32_t _millis;
+
 //arduino: Print.h
 #define DEC 10
 #define HEX 16
@@ -48,23 +58,7 @@ uint8_t _getc();
 #include "watchdog.h"
 #include "serial.h"
 
-// ------------------------
-// Defines
-// ------------------------
-
-#define CPU_32_BIT
-#define SHARED_SERVOS HAS_SERVOS  // Use shared/servos.cpp
-
-#define F_CPU 100000000
-#define SystemCoreClock F_CPU
-
-#define CPU_ST7920_DELAY_1 600
-#define CPU_ST7920_DELAY_2 750
-#define CPU_ST7920_DELAY_3 750
-
-// ------------------------
-// Serial ports
-// ------------------------
+#define SHARED_SERVOS HAS_SERVOS
 
 extern MSerialT serial_stream_0;
 extern MSerialT serial_stream_1;
@@ -104,19 +98,49 @@ extern MSerialT serial_stream_3;
   #endif
 #endif
 
-// ------------------------
-// Interrupts
-// ------------------------
 
+#define CPU_ST7920_DELAY_1 600
+#define CPU_ST7920_DELAY_2 750
+#define CPU_ST7920_DELAY_3 750
+
+//
+// Interrupts
+//
 #define CRITICAL_SECTION_START()
 #define CRITICAL_SECTION_END()
+#define ISRS_ENABLED()
+#define ENABLE_ISRS()
+#define DISABLE_ISRS()
+
+inline void HAL_init() {}
+
+// Utility functions
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wunused-function"
+int freeMemory();
+#pragma GCC diagnostic pop
 
-// ------------------------
 // ADC
-// ------------------------
-
 #define HAL_ADC_VREF           5.0
 #define HAL_ADC_RESOLUTION    10
+#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch)
+#define HAL_START_ADC(ch)     HAL_adc_start_conversion(ch)
+#define HAL_READ_ADC()        HAL_adc_get_result()
+#define HAL_ADC_READY()       true
+
+void HAL_adc_init();
+void HAL_adc_enable_channel(const uint8_t ch);
+void HAL_adc_start_conversion(const uint8_t ch);
+uint16_t HAL_adc_get_result();
+
+// PWM
+inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
+
+// Reset source
+inline void HAL_clear_reset_source(void) {}
+inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; }
+
+void HAL_reboot();
 
 /* ---------------- Delay in cycles */
 
@@ -135,22 +159,29 @@ constexpr inline std::size_t strlen_constexpr(const char* str) {
   // https://github.com/gcc-mirror/gcc/blob/5c7634a0e5f202935aa6c11b6ea953b8bf80a00a/libstdc%2B%2B-v3/include/bits/char_traits.h#L329
   if (str != nullptr) {
     std::size_t i = 0;
-    while (str[i] != '\0') ++i;
+    while (str[i] != '\0') {
+      ++i;
+    }
+
     return i;
   }
+
   return 0;
 }
 
 constexpr inline int strncmp_constexpr(const char* lhs, const char* rhs, std::size_t count) {
   // https://github.com/gcc-mirror/gcc/blob/13b9cbfc32fe3ac4c81c4dd9c42d141c8fb95db4/libstdc%2B%2B-v3/include/bits/char_traits.h#L655
-  if (lhs == nullptr || rhs == nullptr)
+  if (lhs == nullptr || rhs == nullptr) {
     return rhs != nullptr ? -1 : 1;
+  }
 
-  for (std::size_t i = 0; i < count; ++i)
+  for (std::size_t i = 0; i < count; ++i) {
     if (lhs[i] != rhs[i]) {
       return lhs[i] < rhs[i] ? -1 : 1;
-    else if (lhs[i] == '\0')
+    } else if (lhs[i] == '\0') {
       return 0;
+    }
+  }
 
   return 0;
 }
@@ -162,11 +193,14 @@ constexpr inline const char* strstr_constexpr(const char* str, const char* targe
     do {
       char sc = {};
       do {
-        if ((sc = *str++) == '\0') return nullptr;
+        if ((sc = *str++) == '\0') {
+          return nullptr;
+        }
       } while (sc != c);
     } while (strncmp_constexpr(str, target, len) != 0);
     --str;
   }
+
   return str;
 }
 
@@ -177,88 +211,12 @@ constexpr inline char* strstr_constexpr(char* str, const char* target) {
     do {
       char sc = {};
       do {
-        if ((sc = *str++) == '\0') return nullptr;
+        if ((sc = *str++) == '\0') {
+          return nullptr;
+        }
       } while (sc != c);
     } while (strncmp_constexpr(str, target, len) != 0);
     --str;
   }
   return str;
 }
-
-// ------------------------
-// Class Utilities
-// ------------------------
-
-#pragma GCC diagnostic push
-#if GCC_VERSION <= 50000
-  #pragma GCC diagnostic ignored "-Wunused-function"
-#endif
-
-int freeMemory();
-
-#pragma GCC diagnostic pop
-
-// ------------------------
-// MarlinHAL Class
-// ------------------------
-
-class MarlinHAL {
-public:
-
-  // Earliest possible init, before setup()
-  MarlinHAL() {}
-
-  static inline void init() {}        // Called early in setup()
-  static inline void init_board() {}  // Called less early in setup()
-  static void reboot();               // Restart the firmware from 0x0
-
-  static inline bool isr_state() { return true; }
-  static inline void isr_on()  {}
-  static inline void isr_off() {}
-
-  static inline void delay_ms(const int ms) { _delay_ms(ms); }
-
-  // Tasks, called from idle()
-  static void idletask();
-
-  // Reset
-  static constexpr uint8_t reset_reason = RST_POWER_ON;
-  static inline uint8_t get_reset_source() { return reset_reason; }
-  static inline void clear_reset_source() {}
-
-  // Free SRAM
-  static inline int freeMemory() { return ::freeMemory(); }
-
-  //
-  // ADC Methods
-  //
-
-  static uint8_t active_ch;
-
-  // Called by Temperature::init once at startup
-  static void adc_init();
-
-  // Called by Temperature::init for each sensor at startup
-  static void adc_enable(const uint8_t ch);
-
-  // Begin ADC sampling on the given channel
-  static void adc_start(const uint8_t ch);
-
-  // Is the ADC ready for reading?
-  static bool adc_ready();
-
-  // The current value of the ADC register
-  static uint16_t adc_value();
-
-  /**
-   * Set the PWM duty cycle for the pin to the given value.
-   * No option to invert the duty cycle [default = false]
-   * No option to change the scale of the provided value to enable finer PWM duty control [default = 255]
-   */
-  static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
-    analogWrite(pin, v);
-  }
-
-};
-
-extern MarlinHAL hal;
diff --git a/Marlin/src/HAL/NATIVE_SIM/timers.h b/Marlin/src/HAL/NATIVE_SIM/timers.h
index be38d583b6..cedfdb62d6 100644
--- a/Marlin/src/HAL/NATIVE_SIM/timers.h
+++ b/Marlin/src/HAL/NATIVE_SIM/timers.h
@@ -87,5 +87,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num);
 void HAL_timer_disable_interrupt(const uint8_t timer_num);
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
 
-#define HAL_timer_isr_prologue(T) NOOP
-#define HAL_timer_isr_epilogue(T) NOOP
+#define HAL_timer_isr_prologue(T)
+#define HAL_timer_isr_epilogue(T)
diff --git a/Marlin/src/HAL/SAMD51/HAL.cpp b/Marlin/src/HAL/SAMD51/HAL.cpp
index f038325128..8baad31bc7 100644
--- a/Marlin/src/HAL/SAMD51/HAL.cpp
+++ b/Marlin/src/HAL/SAMD51/HAL.cpp
@@ -106,7 +106,7 @@
 // Private Variables
 // ------------------------
 
-uint16_t MarlinHAL::adc_result;
+uint16_t HAL_adc_result;
 
 #if ADC_IS_REQUIRED
 
@@ -402,7 +402,7 @@ uint16_t MarlinHAL::adc_result;
 // ------------------------
 
 // HAL initialization task
-void MarlinHAL::init() {
+void HAL_init() {
   TERN_(DMA_IS_REQUIRED, dma_init());
   #if ENABLED(SDSUPPORT)
     #if SD_CONNECTION_IS(ONBOARD) && PIN_EXISTS(SD_DETECT)
@@ -412,9 +412,17 @@ void MarlinHAL::init() {
   #endif
 }
 
+// HAL idle task
+/*
+void HAL_idletask() {
+}
+*/
+
+void HAL_clear_reset_source() { }
+
 #pragma push_macro("WDT")
 #undef WDT    // Required to be able to use '.bit.WDT'. Compiler wrongly replace struct field with WDT define
-uint8_t MarlinHAL::get_reset_source() {
+uint8_t HAL_get_reset_source() {
   RSTC_RCAUSE_Type resetCause;
 
   resetCause.reg = REG_RSTC_RCAUSE;
@@ -428,7 +436,7 @@ uint8_t MarlinHAL::get_reset_source() {
 }
 #pragma pop_macro("WDT")
 
-void MarlinHAL::reboot() { NVIC_SystemReset(); }
+void HAL_reboot() { NVIC_SystemReset(); }
 
 extern "C" {
   void * _sbrk(int incr);
@@ -446,7 +454,7 @@ int freeMemory() {
 // ADC
 // ------------------------
 
-void MarlinHAL::adc_init() {
+void HAL_adc_init() {
   #if ADC_IS_REQUIRED
     memset(HAL_adc_results, 0xFF, sizeof(HAL_adc_results));                 // Fill result with invalid values
 
@@ -483,17 +491,17 @@ void MarlinHAL::adc_init() {
   #endif // ADC_IS_REQUIRED
 }
 
-void MarlinHAL::adc_start(const pin_t pin) {
+void HAL_adc_start_conversion(const uint8_t adc_pin) {
   #if ADC_IS_REQUIRED
     LOOP_L_N(pi, COUNT(adc_pins)) {
-      if (pin == adc_pins[pi]) {
-        adc_result = HAL_adc_results[pi];
+      if (adc_pin == adc_pins[pi]) {
+        HAL_adc_result = HAL_adc_results[pi];
         return;
       }
     }
   #endif
 
-  adc_result = 0xFFFF;
+  HAL_adc_result = 0xFFFF;
 }
 
 #endif // __SAMD51__
diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h
index a88ed9ba79..c262752a8d 100644
--- a/Marlin/src/HAL/SAMD51/HAL.h
+++ b/Marlin/src/HAL/SAMD51/HAL.h
@@ -89,29 +89,51 @@
 
 typedef int8_t pin_t;
 
-#define SHARED_SERVOS HAS_SERVOS  // Use shared/servos.cpp
-class Servo;
-typedef Servo hal_servo_t;
+#define SHARED_SERVOS HAS_SERVOS
+#define HAL_SERVO_LIB Servo
 
 //
 // Interrupts
 //
-#define CRITICAL_SECTION_START()  const bool irqon = !__get_PRIMASK(); __disable_irq()
-#define CRITICAL_SECTION_END()    if (irqon) __enable_irq()
+#define CRITICAL_SECTION_START()  uint32_t primask = __get_PRIMASK(); __disable_irq()
+#define CRITICAL_SECTION_END()    if (!primask) __enable_irq()
+#define ISRS_ENABLED() (!__get_PRIMASK())
+#define ENABLE_ISRS()  __enable_irq()
+#define DISABLE_ISRS() __disable_irq()
 
-#define cli() __disable_irq() // Disable interrupts
-#define sei() __enable_irq()  // Enable interrupts
+#define cli() __disable_irq()       // Disable interrupts
+#define sei() __enable_irq()        // Enable interrupts
+
+void HAL_clear_reset_source();  // clear reset reason
+uint8_t HAL_get_reset_source(); // get reset reason
+
+void HAL_reboot();
 
 //
 // ADC
 //
+extern uint16_t HAL_adc_result;     // Most recent ADC conversion
+
+#define HAL_ANALOG_SELECT(pin)
+
+void HAL_adc_init();
 
 //#define HAL_ADC_FILTERED          // Disable Marlin's oversampling. The HAL filters ADC values.
 #define HAL_ADC_VREF         3.3
 #define HAL_ADC_RESOLUTION  10      // ... 12
+#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
+#define HAL_READ_ADC()      HAL_adc_result
+#define HAL_ADC_READY()     true
+
+void HAL_adc_start_conversion(const uint8_t adc_pin);
 
 //
-// Pin Mapping for M42, M43, M226
+// PWM
+//
+inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
+
+//
+// Pin Map
 //
 #define GET_PIN_MAP_PIN(index) index
 #define GET_PIN_MAP_INDEX(pin) pin
@@ -120,92 +142,35 @@ typedef Servo hal_servo_t;
 //
 // Tone
 //
+void toneInit();
 void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0);
 void noTone(const pin_t _pin);
 
-// ------------------------
-// Class Utilities
-// ------------------------
+// Enable hooks into idle and setup for HAL
+void HAL_init();
+/*
+#define HAL_IDLETASK 1
+void HAL_idletask();
+*/
+
+//
+// Utility functions
+//
+FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
 
 #pragma GCC diagnostic push
 #if GCC_VERSION <= 50000
   #pragma GCC diagnostic ignored "-Wunused-function"
 #endif
 
-#ifdef __cplusplus
-  extern "C" {
-#endif
-
-char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s);
-
-extern "C" int freeMemory();
-
-#ifdef __cplusplus
-  }
-#endif
+int freeMemory();
 
 #pragma GCC diagnostic pop
 
-// ------------------------
-// MarlinHAL Class
-// ------------------------
-
-class MarlinHAL {
-public:
-
-  // Earliest possible init, before setup()
-  MarlinHAL() {}
-
-  static void init();                 // Called early in setup()
-  static inline void init_board() {}  // Called less early in setup()
-  static void reboot();               // Restart the firmware from 0x0
-
-  static inline bool isr_state() { return !__get_PRIMASK(); }
-  static inline void isr_on()  { sei(); }
-  static inline void isr_off() { cli(); }
-
-  static inline void delay_ms(const int ms) { delay(ms); }
-
-  // Tasks, called from idle()
-  static inline void idletask() {}
-
-  // Reset
-  static uint8_t get_reset_source();
-  static inline void clear_reset_source() {}
-
-  // Free SRAM
-  static inline int freeMemory() { return ::freeMemory(); }
-
-  //
-  // ADC Methods
-  //
-
-  static uint16_t adc_result;
-
-  // Called by Temperature::init once at startup
-  static void adc_init();
-
-  // Called by Temperature::init for each sensor at startup
-  static inline void adc_enable(const uint8_t ch) {}
-
-  // Begin ADC sampling on the given channel
-  static void adc_start(const pin_t pin);
-
-  // Is the ADC ready for reading?
-  static inline bool adc_ready() { return true; }
-
-  // The current value of the ADC register
-  static uint16_t adc_value() { return adc_result; }
-
-  /**
-   * Set the PWM duty cycle for the pin to the given value.
-   * No option to invert the duty cycle [default = false]
-   * No option to change the scale of the provided value to enable finer PWM duty control [default = 255]
-   */
-  static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false) {
-    analogWrite(pin, v);
+#ifdef __cplusplus
+  extern "C" {
+#endif
+char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s);
+#ifdef __cplusplus
   }
-
-};
-
-extern MarlinHAL hal;
+#endif
diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp
index 324a78316a..0920a72ec1 100644
--- a/Marlin/src/HAL/STM32/HAL.cpp
+++ b/Marlin/src/HAL/STM32/HAL.cpp
@@ -53,18 +53,16 @@
 // Public Variables
 // ------------------------
 
-uint16_t MarlinHAL::adc_result;
+uint16_t HAL_adc_result;
 
 // ------------------------
 // Public functions
 // ------------------------
 
-#if ENABLED(POSTMORTEM_DEBUGGING)
-  extern void install_min_serial();
-#endif
+TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
 
 // HAL initialization task
-void MarlinHAL::init() {
+void HAL_init() {
   // Ensure F_CPU is a constant expression.
   // If the compiler breaks here, it means that delay code that should compute at compile time will not work.
   // So better safe than sorry here.
@@ -105,7 +103,7 @@ void MarlinHAL::init() {
 }
 
 // HAL idle task
-void MarlinHAL::idletask() {
+void HAL_idletask() {
   #if HAS_SHARED_MEDIA
     // Stm32duino currently doesn't have a "loop/idle" method
     CDC_resume_receive();
@@ -113,9 +111,9 @@ void MarlinHAL::idletask() {
   #endif
 }
 
-void MarlinHAL::reboot() { NVIC_SystemReset(); }
+void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); }
 
-uint8_t MarlinHAL::get_reset_source() {
+uint8_t HAL_get_reset_source() {
   return
     #ifdef RCC_FLAG_IWDGRST // Some sources may not exist...
       RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST)  ? RST_WATCHDOG :
@@ -139,14 +137,24 @@ uint8_t MarlinHAL::get_reset_source() {
   ;
 }
 
-void MarlinHAL::clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); }
+void HAL_reboot() { NVIC_SystemReset(); }
+
+void _delay_ms(const int delay_ms) { delay(delay_ms); }
 
 extern "C" {
   extern unsigned int _ebss; // end of bss section
 }
 
+// ------------------------
+// ADC
+// ------------------------
+
+// TODO: Make sure this doesn't cause any delay
+void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); }
+uint16_t HAL_adc_get_result() { return HAL_adc_result; }
+
 // Reset the system to initiate a firmware flash
-WEAK void flashFirmware(const int16_t) { hal.reboot(); }
+WEAK void flashFirmware(const int16_t) { HAL_reboot(); }
 
 // Maple Compatibility
 volatile uint32_t systick_uptime_millis = 0;
diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h
index f9bf1c938a..adaf14223f 100644
--- a/Marlin/src/HAL/STM32/HAL.h
+++ b/Marlin/src/HAL/STM32/HAL.h
@@ -44,9 +44,9 @@
 #define CPU_ST7920_DELAY_2  40
 #define CPU_ST7920_DELAY_3 340
 
-// ------------------------
-// Serial ports
-// ------------------------
+//
+// Serial Ports
+//
 #ifdef USBCON
   #include <USBSerial.h>
   #include "../../core/serial_hook.h"
@@ -115,14 +115,17 @@
   #define analogInputToDigitalPin(p) (p)
 #endif
 
-//
-// Interrupts
-//
-#define CRITICAL_SECTION_START()  const bool irqon = !__get_PRIMASK(); __disable_irq()
-#define CRITICAL_SECTION_END()    if (irqon) __enable_irq()
+#define CRITICAL_SECTION_START()  uint32_t primask = __get_PRIMASK(); __disable_irq()
+#define CRITICAL_SECTION_END()    if (!primask) __enable_irq()
+#define ISRS_ENABLED() (!__get_PRIMASK())
+#define ENABLE_ISRS()  __enable_irq()
+#define DISABLE_ISRS() __disable_irq()
 #define cli() __disable_irq()
 #define sei() __enable_irq()
 
+// On AVR this is in math.h?
+#define square(x) ((x)*(x))
+
 // ------------------------
 // Types
 // ------------------------
@@ -133,15 +136,57 @@
   typedef int16_t pin_t;
 #endif
 
-class libServo;
-typedef libServo hal_servo_t;
+#define HAL_SERVO_LIB libServo
 #define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos()
 #define RESUME_SERVO_OUTPUT() libServo::resume_all_servos()
 
 // ------------------------
-// ADC
+// Public Variables
 // ------------------------
 
+// result of last ADC conversion
+extern uint16_t HAL_adc_result;
+
+// ------------------------
+// Public functions
+// ------------------------
+
+// Memory related
+#define __bss_end __bss_end__
+
+// Enable hooks into  setup for HAL
+void HAL_init();
+#define HAL_IDLETASK 1
+void HAL_idletask();
+
+// Clear reset reason
+void HAL_clear_reset_source();
+
+// Reset reason
+uint8_t HAL_get_reset_source();
+
+void HAL_reboot();
+
+void _delay_ms(const int delay);
+
+extern "C" char* _sbrk(int incr);
+
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wunused-function"
+
+static inline int freeMemory() {
+  volatile char top;
+  return &top - reinterpret_cast<char*>(_sbrk(0));
+}
+
+#pragma GCC diagnostic pop
+
+//
+// ADC
+//
+
+#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT)
+
 #ifdef ADC_RESOLUTION
   #define HAL_ADC_RESOLUTION ADC_RESOLUTION
 #else
@@ -149,10 +194,16 @@ typedef libServo hal_servo_t;
 #endif
 
 #define HAL_ADC_VREF         3.3
+#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
+#define HAL_READ_ADC()      HAL_adc_result
+#define HAL_ADC_READY()     true
+
+inline void HAL_adc_init() { analogReadResolution(HAL_ADC_RESOLUTION); }
+
+void HAL_adc_start_conversion(const uint8_t adc_pin);
+
+uint16_t HAL_adc_get_result();
 
-//
-// Pin Mapping for M42, M43, M226
-//
 #define GET_PIN_MAP_PIN(index) index
 #define GET_PIN_MAP_INDEX(pin) pin
 #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
@@ -175,93 +226,17 @@ extern volatile uint32_t systick_uptime_millis;
 
 #define HAL_CAN_SET_PWM_FREQ   // This HAL supports PWM Frequency adjustment
 
-// ------------------------
-// Class Utilities
-// ------------------------
+/**
+ * set_pwm_frequency
+ *  Set the frequency of the timer corresponding to the provided pin
+ *  All Timer PWM pins run at the same frequency
+ */
+void set_pwm_frequency(const pin_t pin, int f_desired);
 
-// Memory related
-#define __bss_end __bss_end__
-
-extern "C" char* _sbrk(int incr);
-
-#pragma GCC diagnostic push
-#if GCC_VERSION <= 50000
-  #pragma GCC diagnostic ignored "-Wunused-function"
-#endif
-
-static inline int freeMemory() {
-  volatile char top;
-  return &top - reinterpret_cast<char*>(_sbrk(0));
-}
-
-#pragma GCC diagnostic pop
-
-// ------------------------
-// MarlinHAL Class
-// ------------------------
-
-class MarlinHAL {
-public:
-
-  // Earliest possible init, before setup()
-  MarlinHAL() {}
-
-  static void init();                 // Called early in setup()
-  static inline void init_board() {}  // Called less early in setup()
-  static void reboot();               // Restart the firmware from 0x0
-
-  static inline bool isr_state() { return !__get_PRIMASK(); }
-  static inline void isr_on()  { sei(); }
-  static inline void isr_off() { cli(); }
-
-  static inline void delay_ms(const int ms) { delay(ms); }
-
-  // Tasks, called from idle()
-  static void idletask();
-
-  // Reset
-  static uint8_t get_reset_source();
-  static void clear_reset_source();
-
-  // Free SRAM
-  static inline int freeMemory() { return ::freeMemory(); }
-
-  //
-  // ADC Methods
-  //
-
-  static uint16_t adc_result;
-
-  // Called by Temperature::init once at startup
-  static inline void adc_init() {
-    analogReadResolution(HAL_ADC_RESOLUTION);
-  }
-
-  // Called by Temperature::init for each sensor at startup
-  static inline void adc_enable(const pin_t pin) { pinMode(pin, INPUT); }
-
-  // Begin ADC sampling on the given channel
-  static void adc_start(const pin_t pin) { adc_result = analogRead(pin); }
-
-  // Is the ADC ready for reading?
-  static inline bool adc_ready() { return true; }
-
-  // The current value of the ADC register
-  static uint16_t adc_value() { return adc_result; }
-
-  /**
-   * Set the PWM duty cycle for the pin to the given value.
-   * Optionally invert the duty cycle [default = false]
-   * Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255]
-   */
-  static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
-
-  /**
-   * Set the frequency of the timer for the given pin.
-   * All Timer PWM pins run at the same frequency.
-   */
-  static void set_pwm_frequency(const pin_t pin, int f_desired);
-
-};
-
-extern MarlinHAL hal;
+/**
+ * set_pwm_duty
+ *  Set the PWM duty cycle of the provided pin to the provided value
+ *  Optionally allows inverting the duty cycle [default = false]
+ *  Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255]
+ */
+void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp
index 40d320d5e8..8ee4761647 100644
--- a/Marlin/src/HAL/STM32/HAL_SPI.cpp
+++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp
@@ -102,9 +102,9 @@ static SPISettings spiConfig;
 
   // Soft SPI receive byte
   uint8_t spiRec() {
-    hal.isr_off();                                                // No interrupts during byte receive
+    DISABLE_ISRS();                                               // No interrupts during byte receive
     const uint8_t data = HAL_SPI_STM32_SpiTransfer_Mode_3(0xFF);
-    hal.isr_on();                                                 // Enable interrupts
+    ENABLE_ISRS();                                                // Enable interrupts
     return data;
   }
 
@@ -116,9 +116,9 @@ static SPISettings spiConfig;
 
   // Soft SPI send byte
   void spiSend(uint8_t data) {
-    hal.isr_off();                          // No interrupts during byte send
+    DISABLE_ISRS();                         // No interrupts during byte send
     HAL_SPI_STM32_SpiTransfer_Mode_3(data); // Don't care what is received
-    hal.isr_on();                           // Enable interrupts
+    ENABLE_ISRS();                          // Enable interrupts
   }
 
   // Soft SPI send block
diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp
index 7c8cc8dd21..252b057362 100644
--- a/Marlin/src/HAL/STM32/eeprom_flash.cpp
+++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp
@@ -174,9 +174,9 @@ bool PersistentStore::access_finish() {
         UNLOCK_FLASH();
 
         TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT());
-        hal.isr_off();
+        DISABLE_ISRS();
         status = HAL_FLASHEx_Erase(&EraseInitStruct, &SectorError);
-        hal.isr_on();
+        ENABLE_ISRS();
         TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT());
         if (status != HAL_OK) {
           DEBUG_ECHOLNPGM("HAL_FLASHEx_Erase=", status);
@@ -229,9 +229,9 @@ bool PersistentStore::access_finish() {
       // output. Servo output still glitches with interrupts disabled, but recovers after the
       // erase.
       TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT());
-      hal.isr_off();
+      DISABLE_ISRS();
       eeprom_buffer_flush();
-      hal.isr_on();
+      ENABLE_ISRS();
       TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT());
 
       eeprom_data_written = false;
diff --git a/Marlin/src/HAL/STM32/fast_pwm.cpp b/Marlin/src/HAL/STM32/fast_pwm.cpp
index f6d0481c05..b1bea5ce20 100644
--- a/Marlin/src/HAL/STM32/fast_pwm.cpp
+++ b/Marlin/src/HAL/STM32/fast_pwm.cpp
@@ -29,7 +29,7 @@
 // Array to support sticky frequency sets per timer
 static uint16_t timer_freq[TIMER_NUM];
 
-void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
+void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
   if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
   const PinName pin_name = digitalPinToPinName(pin);
   TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM);
@@ -56,7 +56,7 @@ void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v
   if (previousMode != TIMER_OUTPUT_COMPARE_PWM1) HT->resume();
 }
 
-void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) {
+void set_pwm_frequency(const pin_t pin, int f_desired) {
   if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
   const PinName pin_name = digitalPinToPinName(pin);
   TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance
diff --git a/Marlin/src/HAL/STM32/pinsDebug.h b/Marlin/src/HAL/STM32/pinsDebug.h
index a7f022a0b6..73d850fc43 100644
--- a/Marlin/src/HAL/STM32/pinsDebug.h
+++ b/Marlin/src/HAL/STM32/pinsDebug.h
@@ -115,6 +115,7 @@ const XrefInfo pin_xref[] PROGMEM = {
 #define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d)  "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
 #define PRINT_PORT(ANUM) port_print(ANUM)
 #define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1  // will report analog pin number in the print port routine
+#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num
 
 // x is a variable used to search pin_array
 #define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital)
@@ -122,11 +123,6 @@ const XrefInfo pin_xref[] PROGMEM = {
 #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
 #define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin
 
-//
-// Pin Mapping for M43
-//
-#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num
-
 #ifndef M43_NEVER_TOUCH
   #define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP)
   #ifdef KILL_PIN
diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h
index 6828998198..aad543229e 100644
--- a/Marlin/src/HAL/STM32/timers.h
+++ b/Marlin/src/HAL/STM32/timers.h
@@ -116,5 +116,5 @@ FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const ha
   }
 }
 
-#define HAL_timer_isr_prologue(T) NOOP
-#define HAL_timer_isr_epilogue(T) NOOP
+#define HAL_timer_isr_prologue(T)
+#define HAL_timer_isr_epilogue(T)
diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp
index efc513cf94..f29b305361 100644
--- a/Marlin/src/HAL/STM32F1/HAL.cpp
+++ b/Marlin/src/HAL/STM32F1/HAL.cpp
@@ -79,7 +79,7 @@
 #define SCB_AIRCR_PRIGROUP_Msk             (7UL << SCB_AIRCR_PRIGROUP_Pos)                /*!< SCB AIRCR: PRIGROUP Mask */
 
 // ------------------------
-// Serial ports
+// Public Variables
 // ------------------------
 
 #if defined(SERIAL_USB) && !HAS_SD_HOST_DRIVE
@@ -112,21 +112,72 @@
   #endif
 #endif
 
+uint16_t HAL_adc_result;
+
 // ------------------------
-// ADC
+// Private Variables
 // ------------------------
+STM32ADC adc(ADC1);
 
-uint16_t analogRead(pin_t pin) {
-  const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG;
-  return is_analog ? analogRead(uint8_t(pin)) : 0;
-}
-
-// Wrapper to maple unprotected analogWrite
-void analogWrite(pin_t pin, int pwm_val8) {
-  if (PWM_PIN(pin)) analogWrite(uint8_t(pin), pwm_val8);
-}
-
-uint16_t MarlinHAL::adc_result;
+const uint8_t adc_pins[] = {
+  #if HAS_TEMP_ADC_0
+    TEMP_0_PIN,
+  #endif
+  #if HAS_TEMP_ADC_PROBE
+    TEMP_PROBE_PIN,
+  #endif
+  #if HAS_HEATED_BED
+    TEMP_BED_PIN,
+  #endif
+  #if HAS_TEMP_CHAMBER
+    TEMP_CHAMBER_PIN,
+  #endif
+  #if HAS_TEMP_COOLER
+    TEMP_COOLER_PIN,
+  #endif
+  #if HAS_TEMP_ADC_1
+    TEMP_1_PIN,
+  #endif
+  #if HAS_TEMP_ADC_2
+    TEMP_2_PIN,
+  #endif
+  #if HAS_TEMP_ADC_3
+    TEMP_3_PIN,
+  #endif
+  #if HAS_TEMP_ADC_4
+    TEMP_4_PIN,
+  #endif
+  #if HAS_TEMP_ADC_5
+    TEMP_5_PIN,
+  #endif
+  #if HAS_TEMP_ADC_6
+    TEMP_6_PIN,
+  #endif
+  #if HAS_TEMP_ADC_7
+    TEMP_7_PIN,
+  #endif
+  #if ENABLED(FILAMENT_WIDTH_SENSOR)
+    FILWIDTH_PIN,
+  #endif
+  #if HAS_ADC_BUTTONS
+    ADC_KEYPAD_PIN,
+  #endif
+  #if HAS_JOY_ADC_X
+    JOY_X_PIN,
+  #endif
+  #if HAS_JOY_ADC_Y
+    JOY_Y_PIN,
+  #endif
+  #if HAS_JOY_ADC_Z
+    JOY_Z_PIN,
+  #endif
+  #if ENABLED(POWER_MONITOR_CURRENT)
+    POWER_MONITOR_CURRENT_PIN,
+  #endif
+  #if ENABLED(POWER_MONITOR_VOLTAGE)
+    POWER_MONITOR_VOLTAGE_PIN,
+  #endif
+};
 
 enum TempPinIndex : char {
   #if HAS_TEMP_ADC_0
@@ -194,16 +245,15 @@ uint16_t HAL_adc_results[ADC_PIN_COUNT];
 // ------------------------
 // Private functions
 // ------------------------
-
 static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) {
   uint32_t reg_value;
-  uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07);               // only values 0..7 are used
+  uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07);               /* only values 0..7 are used          */
 
-  reg_value  =  SCB->AIRCR;                                                   // read old register configuration
-  reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk);             // clear bits to change
+  reg_value  =  SCB->AIRCR;                                                   /* read old register configuration    */
+  reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk);             /* clear bits to change               */
   reg_value  =  (reg_value                                 |
                 ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) |
-                (PriorityGroupTmp << 8));                                     // Insert write key & priority group
+                (PriorityGroupTmp << 8));                                     /* Insert write key & priority group  */
   SCB->AIRCR =  reg_value;
 }
 
@@ -211,8 +261,6 @@ static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) {
 // Public functions
 // ------------------------
 
-void flashFirmware(const int16_t) { hal.reboot(); }
-
 //
 // Leave PA11/PA12 intact if USBSerial is not used
 //
@@ -232,11 +280,7 @@ void flashFirmware(const int16_t) { hal.reboot(); }
 
 TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
 
-// ------------------------
-// MarlinHAL class
-// ------------------------
-
-void MarlinHAL::init() {
+void HAL_init() {
   NVIC_SetPriorityGrouping(0x3);
   #if PIN_EXISTS(LED)
     OUT_WRITE(LED_PIN, LOW);
@@ -255,7 +299,7 @@ void MarlinHAL::init() {
 }
 
 // HAL idle task
-void MarlinHAL::idletask() {
+void HAL_idletask() {
   #if HAS_SHARED_MEDIA
     // If Marlin is using the SD card we need to lock it to prevent access from
     // a PC via USB.
@@ -270,7 +314,14 @@ void MarlinHAL::idletask() {
   #endif
 }
 
-void MarlinHAL::reboot() { nvic_sys_reset(); }
+void HAL_clear_reset_source() { }
+
+/**
+ * TODO: Check this and change or remove.
+ */
+uint8_t HAL_get_reset_source() { return RST_POWER_ON; }
+
+void _delay_ms(const int delay_ms) { delay(delay_ms); }
 
 extern "C" {
   extern unsigned int _ebss; // end of bss section
@@ -304,70 +355,11 @@ extern "C" {
 }
 */
 
+// ------------------------
 // ADC
-
+// ------------------------
 // Init the AD in continuous capture mode
-void MarlinHAL::adc_init() {
-  static const uint8_t adc_pins[] = {
-    #if HAS_TEMP_ADC_0
-      TEMP_0_PIN,
-    #endif
-    #if HAS_TEMP_ADC_PROBE
-      TEMP_PROBE_PIN,
-    #endif
-    #if HAS_HEATED_BED
-      TEMP_BED_PIN,
-    #endif
-    #if HAS_TEMP_CHAMBER
-      TEMP_CHAMBER_PIN,
-    #endif
-    #if HAS_TEMP_COOLER
-      TEMP_COOLER_PIN,
-    #endif
-    #if HAS_TEMP_ADC_1
-      TEMP_1_PIN,
-    #endif
-    #if HAS_TEMP_ADC_2
-      TEMP_2_PIN,
-    #endif
-    #if HAS_TEMP_ADC_3
-      TEMP_3_PIN,
-    #endif
-    #if HAS_TEMP_ADC_4
-      TEMP_4_PIN,
-    #endif
-    #if HAS_TEMP_ADC_5
-      TEMP_5_PIN,
-    #endif
-    #if HAS_TEMP_ADC_6
-      TEMP_6_PIN,
-    #endif
-    #if HAS_TEMP_ADC_7
-      TEMP_7_PIN,
-    #endif
-    #if ENABLED(FILAMENT_WIDTH_SENSOR)
-      FILWIDTH_PIN,
-    #endif
-    #if HAS_ADC_BUTTONS
-      ADC_KEYPAD_PIN,
-    #endif
-    #if HAS_JOY_ADC_X
-      JOY_X_PIN,
-    #endif
-    #if HAS_JOY_ADC_Y
-      JOY_Y_PIN,
-    #endif
-    #if HAS_JOY_ADC_Z
-      JOY_Z_PIN,
-    #endif
-    #if ENABLED(POWER_MONITOR_CURRENT)
-      POWER_MONITOR_CURRENT_PIN,
-    #endif
-    #if ENABLED(POWER_MONITOR_VOLTAGE)
-      POWER_MONITOR_VOLTAGE_PIN,
-    #endif
-  };
-  static STM32ADC adc(ADC1);
+void HAL_adc_init() {
   // configure the ADC
   adc.calibrate();
   #if F_CPU > 72000000
@@ -382,10 +374,10 @@ void MarlinHAL::adc_init() {
   adc.startConversion();
 }
 
-void MarlinHAL::adc_start(const pin_t pin) {
+void HAL_adc_start_conversion(const uint8_t adc_pin) {
   //TEMP_PINS pin_index;
   TempPinIndex pin_index;
-  switch (pin) {
+  switch (adc_pin) {
     default: return;
     #if HAS_TEMP_ADC_0
       case TEMP_0_PIN: pin_index = TEMP_0; break;
@@ -448,4 +440,20 @@ void MarlinHAL::adc_start(const pin_t pin) {
   HAL_adc_result = HAL_adc_results[(int)pin_index] >> (12 - HAL_ADC_RESOLUTION); // shift out unused bits
 }
 
+uint16_t HAL_adc_get_result() { return HAL_adc_result; }
+
+uint16_t analogRead(pin_t pin) {
+  const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG;
+  return is_analog ? analogRead(uint8_t(pin)) : 0;
+}
+
+// Wrapper to maple unprotected analogWrite
+void analogWrite(pin_t pin, int pwm_val8) {
+  if (PWM_PIN(pin)) analogWrite(uint8_t(pin), pwm_val8);
+}
+
+void HAL_reboot() { nvic_sys_reset(); }
+
+void flashFirmware(const int16_t) { HAL_reboot(); }
+
 #endif // __STM32F1__
diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h
index 9b973c3ea4..153cfe8ac8 100644
--- a/Marlin/src/HAL/STM32F1/HAL.h
+++ b/Marlin/src/HAL/STM32F1/HAL.h
@@ -66,10 +66,6 @@
   #endif
 #endif
 
-// ------------------------
-// Serial ports
-// ------------------------
-
 #ifdef SERIAL_USB
   typedef ForwardSerial1Class< USBSerial > DefaultSerial1;
   extern DefaultSerial1 MSerial0;
@@ -145,6 +141,11 @@
   #endif
 #endif
 
+// Set interrupt grouping for this MCU
+void HAL_init();
+#define HAL_IDLETASK 1
+void HAL_idletask();
+
 /**
  * TODO: review this to return 1 for pins that are not analog input
  */
@@ -157,7 +158,15 @@
   #define NO_COMPILE_TIME_PWM
 #endif
 
-// Reset Reason
+#define CRITICAL_SECTION_START()  uint32_t primask = __get_primask(); (void)__iCliRetVal()
+#define CRITICAL_SECTION_END()    if (!primask) (void)__iSeiRetVal()
+#define ISRS_ENABLED() (!__get_primask())
+#define ENABLE_ISRS()  ((void)__iSeiRetVal())
+#define DISABLE_ISRS() ((void)__iCliRetVal())
+
+// On AVR this is in math.h?
+#define square(x) ((x)*(x))
+
 #define RST_POWER_ON   1
 #define RST_EXTERNAL   2
 #define RST_BROWN_OUT  4
@@ -172,66 +181,46 @@
 
 typedef int8_t pin_t;
 
+// ------------------------
+// Public Variables
+// ------------------------
+
 // Result of last ADC conversion
 extern uint16_t HAL_adc_result;
 
 // ------------------------
-// Interrupts
+// Public functions
 // ------------------------
 
-#define CRITICAL_SECTION_START()  const bool irqon = !__get_primask(); (void)__iCliRetVal()
-#define CRITICAL_SECTION_END()    if (!primask) (void)__iSeiRetVal()
+// Disable interrupts
 #define cli() noInterrupts()
+
+// Enable interrupts
 #define sei() interrupts()
 
-// ------------------------
-// ADC
-// ------------------------
-
-#ifdef ADC_RESOLUTION
-  #define HAL_ADC_RESOLUTION ADC_RESOLUTION
-#else
-  #define HAL_ADC_RESOLUTION 12
-#endif
-
-#define HAL_ADC_VREF         3.3
-
-uint16_t analogRead(pin_t pin); // need HAL_ANALOG_SELECT() first
-void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!?
-
-//
-// Pin Mapping for M42, M43, M226
-//
-#define GET_PIN_MAP_PIN(index) index
-#define GET_PIN_MAP_INDEX(pin) pin
-#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
-
-#define JTAG_DISABLE()    afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY)
-#define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE)
-
-#define PLATFORM_M997_SUPPORT
-void flashFirmware(const int16_t);
-
-#define HAL_CAN_SET_PWM_FREQ      // This HAL supports PWM Frequency adjustment
-#ifndef PWM_FREQUENCY
-  #define PWM_FREQUENCY      1000 // Default PWM Frequency
-#endif
-
-// ------------------------
-// Class Utilities
-// ------------------------
-
 // Memory related
 #define __bss_end __bss_end__
 
-void _delay_ms(const int ms);
+// Clear reset reason
+void HAL_clear_reset_source();
 
-extern "C" char* _sbrk(int incr);
+// Reset reason
+uint8_t HAL_get_reset_source();
+
+void HAL_reboot();
+
+void _delay_ms(const int delay);
 
 #pragma GCC diagnostic push
-#if GCC_VERSION <= 50000
-  #pragma GCC diagnostic ignored "-Wunused-function"
-#endif
+#pragma GCC diagnostic ignored "-Wunused-function"
+
+/*
+extern "C" {
+  int freeMemory();
+}
+*/
+
+extern "C" char* _sbrk(int incr);
 
 static inline int freeMemory() {
   volatile char top;
@@ -240,71 +229,58 @@ static inline int freeMemory() {
 
 #pragma GCC diagnostic pop
 
-// ------------------------
-// MarlinHAL Class
-// ------------------------
+//
+// ADC
+//
 
-class MarlinHAL {
-public:
+#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT_ANALOG);
 
-  // Earliest possible init, before setup()
-  MarlinHAL() {}
+void HAL_adc_init();
 
-  static void init();                 // Called early in setup()
-  static inline void init_board() {}  // Called less early in setup()
-  static void reboot();               // Restart the firmware from 0x0
+#ifdef ADC_RESOLUTION
+  #define HAL_ADC_RESOLUTION ADC_RESOLUTION
+#else
+  #define HAL_ADC_RESOLUTION 12
+#endif
 
-  static inline bool isr_state() { return !__get_primask(); }
-  static inline void isr_on()  { ((void)__iSeiRetVal()); }
-  static inline void isr_off() { ((void)__iCliRetVal()); }
+#define HAL_ADC_VREF         3.3
+#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
+#define HAL_READ_ADC()      HAL_adc_result
+#define HAL_ADC_READY()     true
 
-  static inline void delay_ms(const int ms) { delay(ms); }
+void HAL_adc_start_conversion(const uint8_t adc_pin);
+uint16_t HAL_adc_get_result();
 
-  // Tasks, called from idle()
-  static void idletask();
+uint16_t analogRead(pin_t pin); // need HAL_ANALOG_SELECT() first
+void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!?
 
-  // Reset
-  static inline uint8_t get_reset_source() { return RST_POWER_ON; }
-  static inline void clear_reset_source() {}
+#define GET_PIN_MAP_PIN(index) index
+#define GET_PIN_MAP_INDEX(pin) pin
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
 
-  // Free SRAM
-  static inline int freeMemory() { return ::freeMemory(); }
+#define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY)
+#define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE)
 
-  //
-  // ADC Methods
-  //
+#define PLATFORM_M997_SUPPORT
+void flashFirmware(const int16_t);
 
-  static uint16_t adc_result;
+#ifndef PWM_FREQUENCY
+  #define PWM_FREQUENCY      1000 // Default PWM Frequency
+#endif
+#define HAL_CAN_SET_PWM_FREQ      // This HAL supports PWM Frequency adjustment
 
-  // Called by Temperature::init once at startup
-  static void adc_init();
+/**
+ * set_pwm_frequency
+ *  Set the frequency of the timer corresponding to the provided pin
+ *  All Timer PWM pins run at the same frequency
+ */
+void set_pwm_frequency(const pin_t pin, int f_desired);
 
-  // Called by Temperature::init for each sensor at startup
-  static inline void adc_enable(const pin_t pin) { pinMode(pin, INPUT_ANALOG); }
-
-  // Begin ADC sampling on the given channel
-  static void adc_start(const pin_t pin);
-
-  // Is the ADC ready for reading?
-  static inline bool adc_ready() { return true; }
-
-  // The current value of the ADC register
-  static uint16_t adc_value() { return adc_result; }
-
-  /**
-   * Set the PWM duty cycle for the pin to the given value.
-   * Optionally invert the duty cycle [default = false]
-   * Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255]
-   * The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired.
-   */
-  static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false);
-
-  /**
-   * Set the frequency of the timer for the given pin.
-   * All Timer PWM pins run at the same frequency.
-   */
-  static void set_pwm_frequency(const pin_t pin, int f_desired);
-
-};
-
-extern MarlinHAL hal;
+/**
+ * set_pwm_duty
+ *  Set the PWM duty cycle of the provided pin to the provided value
+ *  Optionally allows inverting the duty cycle [default = false]
+ *  Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255]
+ *  The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired.
+ */
+void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
diff --git a/Marlin/src/HAL/STM32F1/Servo.h b/Marlin/src/HAL/STM32F1/Servo.h
index 745a1c93f0..b6143de81d 100644
--- a/Marlin/src/HAL/STM32F1/Servo.h
+++ b/Marlin/src/HAL/STM32F1/Servo.h
@@ -35,8 +35,7 @@
 #define SERVO_DEFAULT_MIN_ANGLE         0
 #define SERVO_DEFAULT_MAX_ANGLE         180
 
-class libServo;
-typedef libServo hal_servo_t;
+#define HAL_SERVO_LIB libServo
 
 class libServo {
   public:
diff --git a/Marlin/src/HAL/STM32F1/fast_pwm.cpp b/Marlin/src/HAL/STM32F1/fast_pwm.cpp
index 11a1a10712..98d56bc5e9 100644
--- a/Marlin/src/HAL/STM32F1/fast_pwm.cpp
+++ b/Marlin/src/HAL/STM32F1/fast_pwm.cpp
@@ -21,9 +21,11 @@
  */
 #ifdef __STM32F1__
 
-#include "../../inc/MarlinConfig.h"
+#include "../../inc/MarlinConfigPre.h"
 
 #include <pwm.h>
+#include "HAL.h"
+#include "timers.h"
 
 #define NR_TIMERS TERN(STM32_XL_DENSITY, 14, 8) // Maple timers, 14 for STM32_XL_DENSITY (F/G chips), 8 for HIGH density (C D E)
 
@@ -36,7 +38,7 @@ inline uint8_t timer_and_index_for_pin(const pin_t pin, timer_dev **timer_ptr) {
   return 0;
 }
 
-void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
+void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
   if (!PWM_PIN(pin)) return;
 
   timer_dev *timer; UNUSED(timer);
@@ -49,7 +51,7 @@ void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v
   timer_set_mode(timer, channel, TIMER_PWM); // PWM Output Mode
 }
 
-void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) {
+void set_pwm_frequency(const pin_t pin, int f_desired) {
   if (!PWM_PIN(pin)) return;                    // Don't proceed if no hardware timer
 
   timer_dev *timer; UNUSED(timer);
diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h
index 0cd807fc84..f9ab6d13d3 100644
--- a/Marlin/src/HAL/STM32F1/timers.h
+++ b/Marlin/src/HAL/STM32F1/timers.h
@@ -188,7 +188,7 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
   }
 }
 
-#define HAL_timer_isr_epilogue(T) NOOP
+#define HAL_timer_isr_epilogue(T)
 
 // No command is available in framework to turn off ARPE bit, which is turned on by default in libmaple.
 // Needed here to reset ARPE=0 for stepper timer
diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.cpp b/Marlin/src/HAL/TEENSY31_32/HAL.cpp
index b923ab77b1..f08cf799e9 100644
--- a/Marlin/src/HAL/TEENSY31_32/HAL.cpp
+++ b/Marlin/src/HAL/TEENSY31_32/HAL.cpp
@@ -31,10 +31,6 @@
 
 #include <Wire.h>
 
-// ------------------------
-// Serial ports
-// ------------------------
-
 #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
 #define IMPLEMENT_SERIAL(X)  _IMPLEMENT_SERIAL(X)
 #if WITHIN(SERIAL_PORT, 0, 3)
@@ -44,9 +40,45 @@
 #endif
 USBSerialType USBSerial(false, SerialUSB);
 
-// ------------------------
-// Class Utilities
-// ------------------------
+uint16_t HAL_adc_result;
+
+static const uint8_t pin2sc1a[] = {
+    5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 0, 19, 3, 31, // 0-13, we treat them as A0-A13
+    5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 (A0-A9)
+    31, 31, 31, 31, 31, 31, 31, 31, 31, 31, // 24-33
+    0+64, 19+64, 3+64, 31+64, // 34-37 (A10-A13)
+    26, 22, 23, 27, 29, 30 // 38-43: temp. sensor, VREF_OUT, A14, bandgap, VREFH, VREFL. A14 isn't connected to anything in Teensy 3.0.
+};
+
+/*
+  // disable interrupts
+  void cli() { noInterrupts(); }
+
+  // enable interrupts
+  void sei() { interrupts(); }
+*/
+
+void HAL_adc_init() {
+  analog_init();
+  while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish
+  NVIC_ENABLE_IRQ(IRQ_FTM1);
+}
+
+void HAL_clear_reset_source() { }
+
+uint8_t HAL_get_reset_source() {
+  switch (RCM_SRS0) {
+    case 128: return RST_POWER_ON; break;
+    case 64: return RST_EXTERNAL; break;
+    case 32: return RST_WATCHDOG; break;
+    // case 8: return RST_LOSS_OF_LOCK; break;
+    // case 4: return RST_LOSS_OF_CLOCK; break;
+    // case 2: return RST_LOW_VOLTAGE; break;
+  }
+  return 0;
+}
+
+void HAL_reboot() { _reboot_Teensyduino_(); }
 
 extern "C" {
   extern char __bss_end;
@@ -63,43 +95,8 @@ extern "C" {
   }
 }
 
-// ------------------------
-// MarlinHAL Class
-// ------------------------
+void HAL_adc_start_conversion(const uint8_t adc_pin) { ADC0_SC1A = pin2sc1a[adc_pin]; }
 
-void MarlinHAL::reboot() { _reboot_Teensyduino_(); }
-
-uint8_t MarlinHAL::get_reset_source() {
-  switch (RCM_SRS0) {
-    case 128: return RST_POWER_ON; break;
-    case 64: return RST_EXTERNAL; break;
-    case 32: return RST_WATCHDOG; break;
-    // case 8: return RST_LOSS_OF_LOCK; break;
-    // case 4: return RST_LOSS_OF_CLOCK; break;
-    // case 2: return RST_LOW_VOLTAGE; break;
-  }
-  return 0;
-}
-
-// ADC
-
-void MarlinHAL::adc_init() {
-  analog_init();
-  while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish
-  NVIC_ENABLE_IRQ(IRQ_FTM1);
-}
-
-void MarlinHAL::adc_start(const pin_t pin) {
-  static const uint8_t pin2sc1a[] = {
-      5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 0, 19, 3, 31, // 0-13, we treat them as A0-A13
-      5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 (A0-A9)
-      31, 31, 31, 31, 31, 31, 31, 31, 31, 31, // 24-33
-      0+64, 19+64, 3+64, 31+64, // 34-37 (A10-A13)
-      26, 22, 23, 27, 29, 30 // 38-43: temp. sensor, VREF_OUT, A14, bandgap, VREFH, VREFL. A14 isn't connected to anything in Teensy 3.0.
-  };
-  ADC0_SC1A = pin2sc1a[pin];
-}
-
-uint16_t MarlinHAL::adc_value() { return ADC0_RA; }
+uint16_t HAL_adc_get_result() { return ADC0_RA; }
 
 #endif // __MK20DX256__
diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h
index 14f463708b..61d8b34604 100644
--- a/Marlin/src/HAL/TEENSY31_32/HAL.h
+++ b/Marlin/src/HAL/TEENSY31_32/HAL.h
@@ -36,9 +36,12 @@
 
 #include <stdint.h>
 
-// ------------------------
-// Defines
-// ------------------------
+#define CPU_ST7920_DELAY_1 600
+#define CPU_ST7920_DELAY_2 750
+#define CPU_ST7920_DELAY_3 750
+
+//#undef MOTHERBOARD
+//#define MOTHERBOARD BOARD_TEENSY31_32
 
 #define IS_32BIT_TEENSY 1
 #define IS_TEENSY_31_32 1
@@ -46,14 +49,6 @@
   #define IS_TEENSY32 1
 #endif
 
-#define CPU_ST7920_DELAY_1 600
-#define CPU_ST7920_DELAY_2 750
-#define CPU_ST7920_DELAY_3 750
-
-// ------------------------
-// Serial ports
-// ------------------------
-
 #include "../../core/serial_hook.h"
 
 #define Serial0 Serial
@@ -77,44 +72,31 @@ extern USBSerialType USBSerial;
   #error "The required SERIAL_PORT must be from 0 to 3, or -1 for Native USB."
 #endif
 
-// ------------------------
-// Types
-// ------------------------
-
-class libServo;
-typedef libServo hal_servo_t;
+#define HAL_SERVO_LIB libServo
 
 typedef int8_t pin_t;
 
-// ------------------------
-// Interrupts
-// ------------------------
-
-uint32_t __get_PRIMASK(void); // CMSIS
-#define CRITICAL_SECTION_START()  const bool irqon = !__get_PRIMASK(); __disable_irq()
-#define CRITICAL_SECTION_END()    if (irqon) __enable_irq()
-
-// ------------------------
-// ADC
-// ------------------------
-
 #ifndef analogInputToDigitalPin
   #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
 #endif
 
-#define HAL_ADC_VREF         3.3
-#define HAL_ADC_RESOLUTION  10
+#define CRITICAL_SECTION_START()  uint32_t primask = __get_PRIMASK(); __disable_irq()
+#define CRITICAL_SECTION_END()    if (!primask) __enable_irq()
+#define ISRS_ENABLED() (!__get_PRIMASK())
+#define ENABLE_ISRS()  __enable_irq()
+#define DISABLE_ISRS() __disable_irq()
 
-//
-// Pin Mapping for M42, M43, M226
-//
-#define GET_PIN_MAP_PIN(index) index
-#define GET_PIN_MAP_INDEX(pin) pin
-#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
+inline void HAL_init() {}
 
-// ------------------------
-// Class Utilities
-// ------------------------
+// Clear the reset reason
+void HAL_clear_reset_source();
+
+// Get the reason for the reset
+uint8_t HAL_get_reset_source();
+
+void HAL_reboot();
+
+FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
 
 #pragma GCC diagnostic push
 #if GCC_VERSION <= 50000
@@ -125,64 +107,27 @@ extern "C" int freeMemory();
 
 #pragma GCC diagnostic pop
 
-// ------------------------
-// MarlinHAL Class
-// ------------------------
+// ADC
 
-class MarlinHAL {
-public:
+void HAL_adc_init();
 
-  // Earliest possible init, before setup()
-  MarlinHAL() {}
+#define HAL_ADC_VREF         3.3
+#define HAL_ADC_RESOLUTION  10
+#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
+#define HAL_READ_ADC()      HAL_adc_get_result()
+#define HAL_ADC_READY()     true
 
-  static inline void init() {}        // Called early in setup()
-  static inline void init_board() {}  // Called less early in setup()
-  static void reboot();               // Restart the firmware from 0x0
+#define HAL_ANALOG_SELECT(pin)
 
-  static inline bool isr_state() { return !__get_PRIMASK(); }
-  static inline void isr_on()  { __enable_irq(); }
-  static inline void isr_off() { __disable_irq(); }
+void HAL_adc_start_conversion(const uint8_t adc_pin);
+uint16_t HAL_adc_get_result();
 
-  static inline void delay_ms(const int ms) { delay(ms); }
+// PWM
 
-  // Tasks, called from idle()
-  static inline void idletask() {}
+inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
 
-  // Reset
-  static uint8_t get_reset_source();
-  static inline void clear_reset_source() {}
+// Pin Map
 
-  // Free SRAM
-  static inline int freeMemory() { return ::freeMemory(); }
-
-  //
-  // ADC Methods
-  //
-
-  // Called by Temperature::init once at startup
-  static void adc_init();
-
-  // Called by Temperature::init for each sensor at startup
-  static inline void adc_enable(const pin_t ch) {}
-
-  // Begin ADC sampling on the given channel
-  static void adc_start(const pin_t ch);
-
-  // Is the ADC ready for reading?
-  static inline bool adc_ready() { return true; }
-
-  // The current value of the ADC register
-  static uint16_t adc_value();
-
-  /**
-   * Set the PWM duty cycle for the pin to the given value.
-   * No option to invert the duty cycle [default = false]
-   * No option to change the scale of the provided value to enable finer PWM duty control [default = 255]
-   */
-  static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
-    analogWrite(pin, v);
-  }
-
-};
-
-extern MarlinHAL hal;
+#define GET_PIN_MAP_PIN(index) index
+#define GET_PIN_MAP_INDEX(pin) pin
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
diff --git a/Marlin/src/HAL/TEENSY31_32/timers.h b/Marlin/src/HAL/TEENSY31_32/timers.h
index 9fcbb6f232..3b073d63ab 100644
--- a/Marlin/src/HAL/TEENSY31_32/timers.h
+++ b/Marlin/src/HAL/TEENSY31_32/timers.h
@@ -110,4 +110,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num);
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
 
 void HAL_timer_isr_prologue(const uint8_t timer_num);
-#define HAL_timer_isr_epilogue(T) NOOP
+#define HAL_timer_isr_epilogue(T)
diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.cpp b/Marlin/src/HAL/TEENSY35_36/HAL.cpp
index 54a5ad3855..046c00b56e 100644
--- a/Marlin/src/HAL/TEENSY35_36/HAL.cpp
+++ b/Marlin/src/HAL/TEENSY35_36/HAL.cpp
@@ -31,10 +31,6 @@
 
 #include <Wire.h>
 
-// ------------------------
-// Serial ports
-// ------------------------
-
 #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
 #define IMPLEMENT_SERIAL(X)  _IMPLEMENT_SERIAL(X)
 #if WITHIN(SERIAL_PORT, 0, 3)
@@ -43,9 +39,54 @@
 
 USBSerialType USBSerial(false, SerialUSB);
 
-// ------------------------
-// Class Utilities
-// ------------------------
+uint16_t HAL_adc_result, HAL_adc_select;
+
+static const uint8_t pin2sc1a[] = {
+  5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 3, 19+128, 14+128, 15+128, // 0-13 -> A0-A13
+  5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 are A0-A9
+  255, 255, 255, 255, 255, 255, 255, // 24-30 are digital only
+  14+128, 15+128, 17, 18, 4+128, 5+128, 6+128, 7+128, 17+128,  // 31-39 are A12-A20
+  255, 255, 255, 255, 255, 255, 255, 255, 255,  // 40-48 are digital only
+  10+128, 11+128, // 49-50 are A23-A24
+  255, 255, 255, 255, 255, 255, 255, // 51-57 are digital only
+  255, 255, 255, 255, 255, 255, // 58-63 (sd card pins) are digital only
+  3, 19+128, // 64-65 are A10-A11
+  23, 23+128,// 66-67 are A21-A22 (DAC pins)
+  1, 1+128,  // 68-69 are A25-A26 (unused USB host port on Teensy 3.5)
+  26,        // 70 is Temperature Sensor
+  18+128     // 71 is Vref
+};
+
+/*
+  // disable interrupts
+  void cli() { noInterrupts(); }
+
+  // enable interrupts
+  void sei() { interrupts(); }
+*/
+
+void HAL_adc_init() {
+  analog_init();
+  while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish
+  while (ADC1_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish
+  NVIC_ENABLE_IRQ(IRQ_FTM1);
+}
+
+void HAL_clear_reset_source() { }
+
+uint8_t HAL_get_reset_source() {
+  switch (RCM_SRS0) {
+    case 128: return RST_POWER_ON; break;
+    case 64: return RST_EXTERNAL; break;
+    case 32: return RST_WATCHDOG; break;
+    // case 8: return RST_LOSS_OF_LOCK; break;
+    // case 4: return RST_LOSS_OF_CLOCK; break;
+    // case 2: return RST_LOW_VOLTAGE; break;
+  }
+  return 0;
+}
+
+void HAL_reboot() { _reboot_Teensyduino_(); }
 
 extern "C" {
   extern char __bss_end;
@@ -62,69 +103,24 @@ extern "C" {
   }
 }
 
-// ------------------------
-// MarlinHAL Class
-// ------------------------
-
-void MarlinHAL::reboot() { _reboot_Teensyduino_(); }
-
-// Reset
-
-uint8_t MarlinHAL::get_reset_source() {
-  switch (RCM_SRS0) {
-    case 128: return RST_POWER_ON; break;
-    case 64: return RST_EXTERNAL; break;
-    case 32: return RST_WATCHDOG; break;
-    // case 8: return RST_LOSS_OF_LOCK; break;
-    // case 4: return RST_LOSS_OF_CLOCK; break;
-    // case 2: return RST_LOW_VOLTAGE; break;
-  }
-  return 0;
-}
-
-// ADC
-
-int8_t MarlinHAL::adc_select;
-
-void MarlinHAL::adc_init() {
-  analog_init();
-  while (ADC0_SC3 & ADC_SC3_CAL) { /* Wait for calibration to finish */ }
-  while (ADC1_SC3 & ADC_SC3_CAL) { /* Wait for calibration to finish */ }
-  NVIC_ENABLE_IRQ(IRQ_FTM1);
-}
-
-void MarlinHAL::adc_start(const pin_t adc_pin) {
-  static const uint8_t pin2sc1a[] = {
-    5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 3, 19+128, 14+128, 15+128, // 0-13 -> A0-A13
-    5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 are A0-A9
-    255, 255, 255, 255, 255, 255, 255, // 24-30 are digital only
-    14+128, 15+128, 17, 18, 4+128, 5+128, 6+128, 7+128, 17+128,  // 31-39 are A12-A20
-    255, 255, 255, 255, 255, 255, 255, 255, 255,  // 40-48 are digital only
-    10+128, 11+128, // 49-50 are A23-A24
-    255, 255, 255, 255, 255, 255, 255, // 51-57 are digital only
-    255, 255, 255, 255, 255, 255, // 58-63 (sd card pins) are digital only
-    3, 19+128, // 64-65 are A10-A11
-    23, 23+128,// 66-67 are A21-A22 (DAC pins)
-    1, 1+128,  // 68-69 are A25-A26 (unused USB host port on Teensy 3.5)
-    26,        // 70 is Temperature Sensor
-    18+128     // 71 is Vref
-  };
+void HAL_adc_start_conversion(const uint8_t adc_pin) {
   const uint16_t pin = pin2sc1a[adc_pin];
   if (pin == 0xFF) {
-    adc_select = -1;    // Digital only
+    // Digital only
+    HAL_adc_select = -1;
   }
   else if (pin & 0x80) {
-    adc_select = 1;
+    HAL_adc_select = 1;
     ADC1_SC1A = pin & 0x7F;
   }
   else {
-    adc_select = 0;
+    HAL_adc_select = 0;
     ADC0_SC1A = pin;
   }
 }
 
-uint16_t MarlinHAL::adc_value() {
-  switch (adc_select) {
+uint16_t HAL_adc_get_result() {
+  switch (HAL_adc_select) {
     case 0: return ADC0_RA;
     case 1: return ADC1_RA;
   }
diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h
index 1cc465c4bb..892eb2d3c5 100644
--- a/Marlin/src/HAL/TEENSY35_36/HAL.h
+++ b/Marlin/src/HAL/TEENSY35_36/HAL.h
@@ -37,6 +37,10 @@
 #include <stdint.h>
 #include <util/atomic.h>
 
+#define CPU_ST7920_DELAY_1 600
+#define CPU_ST7920_DELAY_2 750
+#define CPU_ST7920_DELAY_3 750
+
 // ------------------------
 // Defines
 // ------------------------
@@ -49,17 +53,6 @@
   #define IS_TEENSY35 1
 #endif
 
-#define CPU_ST7920_DELAY_1 600
-#define CPU_ST7920_DELAY_2 750
-#define CPU_ST7920_DELAY_3 750
-
-#undef sq
-#define sq(x) ((x)*(x))
-
-// ------------------------
-// Serial ports
-// ------------------------
-
 #include "../../core/serial_hook.h"
 
 #define Serial0 Serial
@@ -83,43 +76,34 @@ extern USBSerialType USBSerial;
   #error "SERIAL_PORT must be from 0 to 3, or -1 for Native USB."
 #endif
 
-// ------------------------
-// Types
-// ------------------------
-
-class libServo;
-typedef libServo hal_servo_t;
+#define HAL_SERVO_LIB libServo
 
 typedef int8_t pin_t;
 
-// ------------------------
-// Interrupts
-// ------------------------
-
-#define CRITICAL_SECTION_START()  const bool irqon = !__get_primask(); __disable_irq()
-#define CRITICAL_SECTION_END()    if (irqon) __enable_irq()
-
-// ------------------------
-// ADC
-// ------------------------
-
 #ifndef analogInputToDigitalPin
   #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
 #endif
 
-#define HAL_ADC_VREF         3.3
-#define HAL_ADC_RESOLUTION  10
+#define CRITICAL_SECTION_START()  uint32_t primask = __get_primask(); __disable_irq()
+#define CRITICAL_SECTION_END()    if (!primask) __enable_irq()
+#define ISRS_ENABLED() (!__get_primask())
+#define ENABLE_ISRS()  __enable_irq()
+#define DISABLE_ISRS() __disable_irq()
 
-//
-// Pin Mapping for M42, M43, M226
-//
-#define GET_PIN_MAP_PIN(index) index
-#define GET_PIN_MAP_INDEX(pin) pin
-#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
+#undef sq
+#define sq(x) ((x)*(x))
 
-// ------------------------
-// Class Utilities
-// ------------------------
+inline void HAL_init() {}
+
+// Clear reset reason
+void HAL_clear_reset_source();
+
+// Reset reason
+uint8_t HAL_get_reset_source();
+
+void HAL_reboot();
+
+FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
 
 #pragma GCC diagnostic push
 #if GCC_VERSION <= 50000
@@ -130,66 +114,27 @@ extern "C" int freeMemory();
 
 #pragma GCC diagnostic pop
 
-// ------------------------
-// MarlinHAL Class
-// ------------------------
+// ADC
 
-class MarlinHAL {
-public:
+void HAL_adc_init();
 
-  // Earliest possible init, before setup()
-  MarlinHAL() {}
+#define HAL_ADC_VREF         3.3
+#define HAL_ADC_RESOLUTION  10
+#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
+#define HAL_READ_ADC()      HAL_adc_get_result()
+#define HAL_ADC_READY()     true
 
-  static inline void init() {}        // Called early in setup()
-  static inline void init_board() {}  // Called less early in setup()
-  static void reboot();               // Restart the firmware from 0x0
+#define HAL_ANALOG_SELECT(pin)
 
-  static inline bool isr_state() { return true; }
-  static inline void isr_on()  { __enable_irq(); }
-  static inline void isr_off() { __disable_irq(); }
+void HAL_adc_start_conversion(const uint8_t adc_pin);
+uint16_t HAL_adc_get_result();
 
-  static inline void delay_ms(const int ms) { delay(ms); }
+// PWM
 
-  // Tasks, called from idle()
-  static inline void idletask() {}
+inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
 
-  // Reset
-  static uint8_t get_reset_source();
-  static inline void clear_reset_source() {}
+// Pin Map
 
-  // Free SRAM
-  static inline int freeMemory() { return ::freeMemory(); }
-
-  //
-  // ADC Methods
-  //
-
-  static int8_t adc_select;
-
-  // Called by Temperature::init once at startup
-  static void adc_init();
-
-  // Called by Temperature::init for each sensor at startup
-  static inline void adc_enable(const pin_t) {}
-
-  // Begin ADC sampling on the given channel
-  static void adc_start(const pin_t pin);
-
-  // Is the ADC ready for reading?
-  static inline bool adc_ready() { return true; }
-
-  // The current value of the ADC register
-  static uint16_t adc_value();
-
-  /**
-   * Set the PWM duty cycle for the pin to the given value.
-   * No option to invert the duty cycle [default = false]
-   * No option to change the scale of the provided value to enable finer PWM duty control [default = 255]
-   */
-  static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
-    analogWrite(pin, v);
-  }
-
-};
-
-extern MarlinHAL hal;
+#define GET_PIN_MAP_PIN(index) index
+#define GET_PIN_MAP_INDEX(pin) pin
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h
index 8af79d7392..6c342bbe0d 100644
--- a/Marlin/src/HAL/TEENSY35_36/timers.h
+++ b/Marlin/src/HAL/TEENSY35_36/timers.h
@@ -109,4 +109,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num);
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
 
 void HAL_timer_isr_prologue(const uint8_t timer_num);
-#define HAL_timer_isr_epilogue(T) NOOP
+#define HAL_timer_isr_epilogue(T)
diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.cpp b/Marlin/src/HAL/TEENSY40_41/HAL.cpp
index 68bd38f72f..270bee0dc9 100644
--- a/Marlin/src/HAL/TEENSY40_41/HAL.cpp
+++ b/Marlin/src/HAL/TEENSY40_41/HAL.cpp
@@ -33,10 +33,6 @@
 #include "timers.h"
 #include <Wire.h>
 
-// ------------------------
-// Serial ports
-// ------------------------
-
 #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
 #define IMPLEMENT_SERIAL(X)  _IMPLEMENT_SERIAL(X)
 #if WITHIN(SERIAL_PORT, 0, 3)
@@ -44,42 +40,75 @@
 #endif
 USBSerialType USBSerial(false, SerialUSB);
 
-// ------------------------
-// Class Utilities
-// ------------------------
+uint16_t HAL_adc_result, HAL_adc_select;
 
-#define __bss_end _ebss
+static const uint8_t pin2sc1a[] = {
+  0x07,  // 0/A0  AD_B1_02
+  0x08,  // 1/A1  AD_B1_03
+  0x0C,  // 2/A2  AD_B1_07
+  0x0B,  // 3/A3  AD_B1_06
+  0x06,  // 4/A4  AD_B1_01
+  0x05,  // 5/A5  AD_B1_00
+  0x0F,  // 6/A6  AD_B1_10
+  0x00,  // 7/A7  AD_B1_11
+  0x0D,  // 8/A8  AD_B1_08
+  0x0E,  // 9/A9  AD_B1_09
+  0x01,  // 24/A10 AD_B0_12
+  0x02,  // 25/A11 AD_B0_13
+  0x83,  // 26/A12 AD_B1_14 - only on ADC2, 3
+  0x84,  // 27/A13 AD_B1_15 - only on ADC2, 4
+  0x07,  // 14/A0  AD_B1_02
+  0x08,  // 15/A1  AD_B1_03
+  0x0C,  // 16/A2  AD_B1_07
+  0x0B,  // 17/A3  AD_B1_06
+  0x06,  // 18/A4  AD_B1_01
+  0x05,  // 19/A5  AD_B1_00
+  0x0F,  // 20/A6  AD_B1_10
+  0x00,  // 21/A7  AD_B1_11
+  0x0D,  // 22/A8  AD_B1_08
+  0x0E,  // 23/A9  AD_B1_09
+  0x01,  // 24/A10 AD_B0_12
+  0x02,  // 25/A11 AD_B0_13
+  0x83,  // 26/A12 AD_B1_14 - only on ADC2, 3
+  0x84,  // 27/A13 AD_B1_15 - only on ADC2, 4
+  #ifdef ARDUINO_TEENSY41
+    0xFF,  // 28
+    0xFF,  // 29
+    0xFF,  // 30
+    0xFF,  // 31
+    0xFF,  // 32
+    0xFF,  // 33
+    0xFF,  // 34
+    0xFF,  // 35
+    0xFF,  // 36
+    0xFF,  // 37
+    0x81,  // 38/A14 AD_B1_12 - only on ADC2, 1
+    0x82,  // 39/A15 AD_B1_13 - only on ADC2, 2
+    0x09,  // 40/A16 AD_B1_04
+    0x0A,  // 41/A17 AD_B1_05
+  #endif
+};
 
-extern "C" {
-  extern char __bss_end;
-  extern char __heap_start;
-  extern void* __brkval;
+/*
+// disable interrupts
+void cli() { noInterrupts(); }
 
-  // Doesn't work on Teensy 4.x
-  uint32_t freeMemory() {
-    uint32_t free_memory;
-    free_memory = ((uint32_t)&free_memory) - (((uint32_t)__brkval) ?: ((uint32_t)&__bss_end));
-    return free_memory;
-  }
+// enable interrupts
+void sei() { interrupts(); }
+*/
+
+void HAL_adc_init() {
+  analog_init();
+  while (ADC1_GC & ADC_GC_CAL) ;
+  while (ADC2_GC & ADC_GC_CAL) ;
 }
 
-// ------------------------
-// FastIO
-// ------------------------
-
-bool is_output(pin_t pin) {
-  const struct digital_pin_bitband_and_config_table_struct *p;
-  p = digital_pin_to_info_PGM + pin;
-  return (*(p->reg + 1) & p->mask);
+void HAL_clear_reset_source() {
+  uint32_t reset_source = SRC_SRSR;
+  SRC_SRSR = reset_source;
 }
 
-// ------------------------
-// MarlinHAL Class
-// ------------------------
-
-void MarlinHAL::reboot() { _reboot_Teensyduino_(); }
-
-uint8_t MarlinHAL::get_reset_source() {
+uint8_t HAL_get_reset_source() {
   switch (SRC_SRSR & 0xFF) {
     case 1: return RST_POWER_ON; break;
     case 2: return RST_SOFTWARE; break;
@@ -92,92 +121,57 @@ uint8_t MarlinHAL::get_reset_source() {
   return 0;
 }
 
-void MarlinHAL::clear_reset_source() {
-  uint32_t reset_source = SRC_SRSR;
-  SRC_SRSR = reset_source;
+void HAL_reboot() { _reboot_Teensyduino_(); }
+
+#define __bss_end _ebss
+
+extern "C" {
+  extern char __bss_end;
+  extern char __heap_start;
+  extern void* __brkval;
+
+  // Doesn't work on Teensy 4.x
+  uint32_t freeMemory() {
+    uint32_t free_memory;
+    if ((uint32_t)__brkval == 0)
+      free_memory = ((uint32_t)&free_memory) - ((uint32_t)&__bss_end);
+    else
+      free_memory = ((uint32_t)&free_memory) - ((uint32_t)__brkval);
+    return free_memory;
+  }
 }
 
-// ADC
-
-int8_t MarlinHAL::adc_select;
-
-void MarlinHAL::adc_init() {
-  analog_init();
-  while (ADC1_GC & ADC_GC_CAL) { /* wait */ }
-  while (ADC2_GC & ADC_GC_CAL) { /* wait */ }
-}
-
-void MarlinHAL::adc_start(const pin_t adc_pin) {
-  static const uint8_t pin2sc1a[] = {
-    0x07,  // 0/A0  AD_B1_02
-    0x08,  // 1/A1  AD_B1_03
-    0x0C,  // 2/A2  AD_B1_07
-    0x0B,  // 3/A3  AD_B1_06
-    0x06,  // 4/A4  AD_B1_01
-    0x05,  // 5/A5  AD_B1_00
-    0x0F,  // 6/A6  AD_B1_10
-    0x00,  // 7/A7  AD_B1_11
-    0x0D,  // 8/A8  AD_B1_08
-    0x0E,  // 9/A9  AD_B1_09
-    0x01,  // 24/A10 AD_B0_12
-    0x02,  // 25/A11 AD_B0_13
-    0x83,  // 26/A12 AD_B1_14 - only on ADC2, 3
-    0x84,  // 27/A13 AD_B1_15 - only on ADC2, 4
-    0x07,  // 14/A0  AD_B1_02
-    0x08,  // 15/A1  AD_B1_03
-    0x0C,  // 16/A2  AD_B1_07
-    0x0B,  // 17/A3  AD_B1_06
-    0x06,  // 18/A4  AD_B1_01
-    0x05,  // 19/A5  AD_B1_00
-    0x0F,  // 20/A6  AD_B1_10
-    0x00,  // 21/A7  AD_B1_11
-    0x0D,  // 22/A8  AD_B1_08
-    0x0E,  // 23/A9  AD_B1_09
-    0x01,  // 24/A10 AD_B0_12
-    0x02,  // 25/A11 AD_B0_13
-    0x83,  // 26/A12 AD_B1_14 - only on ADC2, 3
-    0x84,  // 27/A13 AD_B1_15 - only on ADC2, 4
-    #ifdef ARDUINO_TEENSY41
-      0xFF,  // 28
-      0xFF,  // 29
-      0xFF,  // 30
-      0xFF,  // 31
-      0xFF,  // 32
-      0xFF,  // 33
-      0xFF,  // 34
-      0xFF,  // 35
-      0xFF,  // 36
-      0xFF,  // 37
-      0x81,  // 38/A14 AD_B1_12 - only on ADC2, 1
-      0x82,  // 39/A15 AD_B1_13 - only on ADC2, 2
-      0x09,  // 40/A16 AD_B1_04
-      0x0A,  // 41/A17 AD_B1_05
-    #endif
-  };
+void HAL_adc_start_conversion(const uint8_t adc_pin) {
   const uint16_t pin = pin2sc1a[adc_pin];
   if (pin == 0xFF) {
-    adc_select = -1; // Digital only
+    HAL_adc_select = -1; // Digital only
   }
   else if (pin & 0x80) {
-    adc_select = 1;
+    HAL_adc_select = 1;
     ADC2_HC0 = pin & 0x7F;
   }
   else {
-    adc_select = 0;
+    HAL_adc_select = 0;
     ADC1_HC0 = pin;
   }
 }
 
-uint16_t MarlinHAL::adc_value() {
-  switch (adc_select) {
+uint16_t HAL_adc_get_result() {
+  switch (HAL_adc_select) {
     case 0:
-      while (!(ADC1_HS & ADC_HS_COCO0)) { /* wait */ }
+      while (!(ADC1_HS & ADC_HS_COCO0)) ; // wait
       return ADC1_R0;
     case 1:
-      while (!(ADC2_HS & ADC_HS_COCO0)) { /* wait */ }
+      while (!(ADC2_HS & ADC_HS_COCO0)) ; // wait
       return ADC2_R0;
   }
   return 0;
 }
 
+bool is_output(pin_t pin) {
+  const struct digital_pin_bitband_and_config_table_struct *p;
+  p = digital_pin_to_info_PGM + pin;
+  return (*(p->reg + 1) & p->mask);
+}
+
 #endif // __IMXRT1062__
diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h
index b7a8070281..2b730768a8 100644
--- a/Marlin/src/HAL/TEENSY40_41/HAL.h
+++ b/Marlin/src/HAL/TEENSY40_41/HAL.h
@@ -41,6 +41,10 @@
   #include "../../feature/ethernet.h"
 #endif
 
+#define CPU_ST7920_DELAY_1 600
+#define CPU_ST7920_DELAY_2 750
+#define CPU_ST7920_DELAY_3 750
+
 // ------------------------
 // Defines
 // ------------------------
@@ -51,23 +55,7 @@
   #define IS_TEENSY41 1
 #endif
 
-#define CPU_ST7920_DELAY_1 600
-#define CPU_ST7920_DELAY_2 750
-#define CPU_ST7920_DELAY_3 750
-
-#undef sq
-#define sq(x) ((x)*(x))
-
-// Don't place string constants in PROGMEM
-#undef PSTR
-#define PSTR(str) ({static const char *data = (str); &data[0];})
-
-// ------------------------
-// Serial ports
-// ------------------------
-
 #include "../../core/serial_hook.h"
-
 #define Serial0 Serial
 #define _DECLARE_SERIAL(X) \
   typedef ForwardSerial1Class<decltype(Serial##X)> DefaultSerial##X; \
@@ -101,47 +89,41 @@ extern USBSerialType USBSerial;
   #endif
 #endif
 
-// ------------------------
-// Types
-// ------------------------
-
-class libServo;
-typedef libServo hal_servo_t;
+#define HAL_SERVO_LIB libServo
 
 typedef int8_t pin_t;
 
-// ------------------------
-// Interrupts
-// ------------------------
-
-#define CRITICAL_SECTION_START()  const bool irqon = !__get_primask(); __disable_irq()
-#define CRITICAL_SECTION_END()    if (irqon) __enable_irq()
-
-// ------------------------
-// ADC
-// ------------------------
-
 #ifndef analogInputToDigitalPin
   #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
 #endif
 
-#define HAL_ADC_VREF         3.3
-#define HAL_ADC_RESOLUTION  10
-#define HAL_ADC_FILTERED      // turn off ADC oversampling
+#define CRITICAL_SECTION_START()  uint32_t primask = __get_primask(); __disable_irq()
+#define CRITICAL_SECTION_END()    if (!primask) __enable_irq()
+#define ISRS_ENABLED() (!__get_primask())
+#define ENABLE_ISRS()  __enable_irq()
+#define DISABLE_ISRS() __disable_irq()
 
-//
-// Pin Mapping for M42, M43, M226
-//
-#define GET_PIN_MAP_PIN(index) index
-#define GET_PIN_MAP_INDEX(pin) pin
-#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
+#undef sq
+#define sq(x) ((x)*(x))
 
-// FastIO
-bool is_output(pin_t pin);
+// Don't place string constants in PROGMEM
+#undef PSTR
+#define PSTR(str) ({static const char *data = (str); &data[0];})
 
-// ------------------------
-// Class Utilities
-// ------------------------
+// Enable hooks into idle and setup for HAL
+#define HAL_IDLETASK 1
+FORCE_INLINE void HAL_idletask() {}
+FORCE_INLINE void HAL_init() {}
+
+// Clear reset reason
+void HAL_clear_reset_source();
+
+// Reset reason
+uint8_t HAL_get_reset_source();
+
+void HAL_reboot();
+
+FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
 
 #pragma GCC diagnostic push
 #if GCC_VERSION <= 50000
@@ -152,66 +134,30 @@ extern "C" uint32_t freeMemory();
 
 #pragma GCC diagnostic pop
 
-// ------------------------
-// MarlinHAL Class
-// ------------------------
+// ADC
 
-class MarlinHAL {
-public:
+void HAL_adc_init();
 
-  // Earliest possible init, before setup()
-  MarlinHAL() {}
+#define HAL_ADC_VREF         3.3
+#define HAL_ADC_RESOLUTION  10
+#define HAL_ADC_FILTERED      // turn off ADC oversampling
+#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
+#define HAL_READ_ADC()      HAL_adc_get_result()
+#define HAL_ADC_READY()     true
 
-  static inline void init() {}        // Called early in setup()
-  static inline void init_board() {}  // Called less early in setup()
-  static void reboot();               // Restart the firmware from 0x0
+#define HAL_ANALOG_SELECT(pin)
 
-  static inline bool isr_state() { return !__get_primask(); }
-  static inline void isr_on()  { __enable_irq(); }
-  static inline void isr_off() { __disable_irq(); }
+void HAL_adc_start_conversion(const uint8_t adc_pin);
+uint16_t HAL_adc_get_result();
 
-  static inline void delay_ms(const int ms) { delay(ms); }
+// PWM
 
-  // Tasks, called from idle()
-  static inline void idletask() {}
+inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
 
-  // Reset
-  static uint8_t get_reset_source();
-  static void clear_reset_source();
+// Pin Map
 
-  // Free SRAM
-  static inline int freeMemory() { return ::freeMemory(); }
+#define GET_PIN_MAP_PIN(index) index
+#define GET_PIN_MAP_INDEX(pin) pin
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
 
-  //
-  // ADC Methods
-  //
-
-  static int8_t adc_select;
-
-  // Called by Temperature::init once at startup
-  static void adc_init();
-
-  // Called by Temperature::init for each sensor at startup
-  static inline void adc_enable(const pin_t pin) {}
-
-  // Begin ADC sampling on the given channel
-  static void adc_start(const pin_t pin);
-
-  // Is the ADC ready for reading?
-  static inline bool adc_ready() { return true; }
-
-  // The current value of the ADC register
-  static uint16_t adc_value();
-
-  /**
-   * Set the PWM duty cycle for the pin to the given value.
-   * No option to invert the duty cycle [default = false]
-   * No option to change the scale of the provided value to enable finer PWM duty control [default = 255]
-   */
-  static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
-    analogWrite(pin, v);
-  }
-
-};
-
-extern MarlinHAL hal;
+bool is_output(pin_t pin);
diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h
index 77fe0953d3..81cf67f7bc 100644
--- a/Marlin/src/HAL/TEENSY40_41/timers.h
+++ b/Marlin/src/HAL/TEENSY40_41/timers.h
@@ -114,4 +114,4 @@ bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
 
 void HAL_timer_isr_prologue(const uint8_t timer_num);
 //void HAL_timer_isr_epilogue(const uint8_t timer_num) {}
-#define HAL_timer_isr_epilogue(T) NOOP
+#define HAL_timer_isr_epilogue(T)
diff --git a/Marlin/src/HAL/shared/HAL.cpp b/Marlin/src/HAL/shared/HAL.cpp
deleted file mode 100644
index a5fe407188..0000000000
--- a/Marlin/src/HAL/shared/HAL.cpp
+++ /dev/null
@@ -1,36 +0,0 @@
-/**
- * Marlin 3D Printer Firmware
- * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
- *
- * Based on Sprinter and grbl.
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
- *
- * This program is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * This program is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
- *
- */
-
-/**
- * HAL/shared/HAL.cpp
- */
-
-#include "../../inc/MarlinConfig.h"
-
-MarlinHAL hal;
-
-#if ENABLED(SOFT_RESET_VIA_SERIAL)
-
-  // Global for use by e_parser.h
-  void HAL_reboot() { hal.reboot(); }
-
-#endif
diff --git a/Marlin/src/HAL/shared/HAL_spi_L6470.cpp b/Marlin/src/HAL/shared/HAL_spi_L6470.cpp
index 5d4ce89b27..bd85dbe7bd 100644
--- a/Marlin/src/HAL/shared/HAL_spi_L6470.cpp
+++ b/Marlin/src/HAL/shared/HAL_spi_L6470.cpp
@@ -92,9 +92,9 @@ uint8_t L64XX_Marlin::transfer_single(uint8_t data, int16_t ss_pin) {
   // First device in chain has data sent last
   extDigitalWrite(ss_pin, LOW);
 
-  hal.isr_off();  // Disable interrupts during SPI transfer (can't allow partial command to chips)
+  DISABLE_ISRS(); // Disable interrupts during SPI transfer (can't allow partial command to chips)
   const uint8_t data_out = L6470_SpiTransfer_Mode_3(data);
-  hal.isr_on();   // Enable interrupts
+  ENABLE_ISRS();  // Enable interrupts
 
   extDigitalWrite(ss_pin, HIGH);
   return data_out;
@@ -107,9 +107,9 @@ uint8_t L64XX_Marlin::transfer_chain(uint8_t data, int16_t ss_pin, uint8_t chain
   extDigitalWrite(ss_pin, LOW);
 
   for (uint8_t i = L64XX::chain[0]; !L64xxManager.spi_abort && i >= 1; i--) {   // Send data unless aborted
-    hal.isr_off();    // Disable interrupts during SPI transfer (can't allow partial command to chips)
+    DISABLE_ISRS();   // Disable interrupts during SPI transfer (can't allow partial command to chips)
     const uint8_t temp = L6470_SpiTransfer_Mode_3(uint8_t(i == chain_position ? data : dSPIN_NOP));
-    hal.isr_on();     // Enable interrupts
+    ENABLE_ISRS();    // Enable interrupts
     if (i == chain_position) data_out = temp;
   }
 
diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp
index 009edeba2f..5132d07e87 100644
--- a/Marlin/src/MarlinCore.cpp
+++ b/Marlin/src/MarlinCore.cpp
@@ -790,7 +790,7 @@ void idle(bool no_stepper_sleep/*=false*/) {
   #endif
 
   // Run HAL idle tasks
-  hal.idletask();
+  TERN_(HAL_IDLETASK, HAL_idletask());
 
   // Check network connection
   TERN_(HAS_ETHERNET, ethernet.check());
@@ -929,7 +929,7 @@ void minkill(const bool steppers_off/*=false*/) {
       watchdog_refresh();
 
     // Reboot the board
-    hal.reboot();
+    HAL_reboot();
 
   #else
 
@@ -1041,7 +1041,7 @@ inline void tmc_standby_setup() {
  *    • L64XX Stepper Drivers (SPI)
  *    • Stepper Driver Reset: DISABLE
  *    • TMC Stepper Drivers (SPI)
- *    • Run hal.init_board() for additional pins setup
+ *    • Run BOARD_INIT if defined
  *    • ESP WiFi
  *  - Get the Reset Reason and report it
  *  - Print startup messages and diagnostics
@@ -1119,8 +1119,8 @@ void setup() {
   tmc_standby_setup();  // TMC Low Power Standby pins must be set early or they're not usable
 
   // Check startup - does nothing if bootloader sets MCUSR to 0
-  const byte mcu = hal.get_reset_source();
-  hal.clear_reset_source();
+  const byte mcu = HAL_get_reset_source();
+  HAL_clear_reset_source();
 
   #if ENABLED(MARLIN_DEV_MODE)
     auto log_current_ms = [&](PGM_P const msg) {
@@ -1181,20 +1181,23 @@ void setup() {
     JTAGSWD_RESET();
   #endif
 
-  // Disable any hardware debug to free up pins for IO
-  #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE)
+  #if EITHER(DISABLE_DEBUG, DISABLE_JTAG)
     delay(10);
-    SETUP_LOG("JTAGSWD_DISABLE");
-    JTAGSWD_DISABLE();
-  #elif ENABLED(DISABLE_JTAG) && defined(JTAG_DISABLE)
-    delay(10);
-    SETUP_LOG("JTAG_DISABLE");
-    JTAG_DISABLE();
+    // Disable any hardware debug to free up pins for IO
+    #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE)
+      SETUP_LOG("JTAGSWD_DISABLE");
+      JTAGSWD_DISABLE();
+    #elif defined(JTAG_DISABLE)
+      SETUP_LOG("JTAG_DISABLE");
+      JTAG_DISABLE();
+    #else
+      #error "DISABLE_(DEBUG|JTAG) is not supported for the selected MCU/Board."
+    #endif
   #endif
 
   TERN_(DYNAMIC_VECTORTABLE, hook_cpu_exceptions()); // If supported, install Marlin exception handlers at runtime
 
-  SETUP_RUN(hal.init());
+  SETUP_RUN(HAL_init());
 
   // Init and disable SPI thermocouples; this is still needed
   #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E0))
@@ -1240,16 +1243,19 @@ void setup() {
     SETUP_RUN(tmc_init_cs_pins());
   #endif
 
-  SETUP_RUN(hal.init_board());
+  #ifdef BOARD_INIT
+    SETUP_LOG("BOARD_INIT");
+    BOARD_INIT();
+  #endif
 
   SETUP_RUN(esp_wifi_init());
 
   // Report Reset Reason
-  if (mcu & RST_POWER_ON)  SERIAL_ECHOLNPGM(STR_POWERUP);
-  if (mcu & RST_EXTERNAL)  SERIAL_ECHOLNPGM(STR_EXTERNAL_RESET);
+  if (mcu & RST_POWER_ON) SERIAL_ECHOLNPGM(STR_POWERUP);
+  if (mcu & RST_EXTERNAL) SERIAL_ECHOLNPGM(STR_EXTERNAL_RESET);
   if (mcu & RST_BROWN_OUT) SERIAL_ECHOLNPGM(STR_BROWNOUT_RESET);
-  if (mcu & RST_WATCHDOG)  SERIAL_ECHOLNPGM(STR_WATCHDOG_RESET);
-  if (mcu & RST_SOFTWARE)  SERIAL_ECHOLNPGM(STR_SOFTWARE_RESET);
+  if (mcu & RST_WATCHDOG) SERIAL_ECHOLNPGM(STR_WATCHDOG_RESET);
+  if (mcu & RST_SOFTWARE) SERIAL_ECHOLNPGM(STR_SOFTWARE_RESET);
 
   // Identify myself as Marlin x.x.x
   SERIAL_ECHOLNPGM("Marlin " SHORT_BUILD_VERSION);
@@ -1260,7 +1266,7 @@ void setup() {
     );
   #endif
   SERIAL_ECHO_MSG(" Compiled: " __DATE__);
-  SERIAL_ECHO_MSG(STR_FREE_MEMORY, hal.freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE));
+  SERIAL_ECHO_MSG(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE));
 
   // Some HAL need precise delay adjustment
   calibrate_delay_loop();
@@ -1532,7 +1538,7 @@ void setup() {
   #endif
 
   #if ENABLED(USE_WATCHDOG)
-    SETUP_RUN(watchdog_init());       // Reinit watchdog after hal.get_reset_source call
+    SETUP_RUN(watchdog_init());       // Reinit watchdog after HAL_get_reset_source call
   #endif
 
   #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER)
diff --git a/Marlin/src/feature/caselight.cpp b/Marlin/src/feature/caselight.cpp
index a58cb66aff..59832fd6ed 100644
--- a/Marlin/src/feature/caselight.cpp
+++ b/Marlin/src/feature/caselight.cpp
@@ -69,7 +69,7 @@ void CaseLight::update(const bool sflag) {
 
     #if CASELIGHT_USES_BRIGHTNESS
       if (pin_is_pwm())
-        hal.set_pwm_duty(pin_t(CASE_LIGHT_PIN), (
+        set_pwm_duty(pin_t(CASE_LIGHT_PIN), (
           #if CASE_LIGHT_MAX_PWM == 255
             n10ct
           #else
diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp
index f42bf52ae4..59ba665e11 100644
--- a/Marlin/src/feature/controllerfan.cpp
+++ b/Marlin/src/feature/controllerfan.cpp
@@ -76,7 +76,7 @@ void ControllerFan::update() {
       thermalManager.soft_pwm_controller_speed = speed;
     #else
       if (PWM_PIN(CONTROLLER_FAN_PIN))
-        hal.set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed);
+        set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed);
       else
         WRITE(CONTROLLER_FAN_PIN, speed > 0);
     #endif
diff --git a/Marlin/src/feature/e_parser.h b/Marlin/src/feature/e_parser.h
index fda1ba144b..1dee0cf755 100644
--- a/Marlin/src/feature/e_parser.h
+++ b/Marlin/src/feature/e_parser.h
@@ -41,9 +41,7 @@ extern bool wait_for_user, wait_for_heatup;
   void quickresume_stepper();
 #endif
 
-#if ENABLED(SOFT_RESET_VIA_SERIAL)
-  void HAL_reboot();
-#endif
+void HAL_reboot();
 
 class EmergencyParser {
 
diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp
index 0a4b511476..17d790b8cc 100644
--- a/Marlin/src/feature/leds/leds.cpp
+++ b/Marlin/src/feature/leds/leds.cpp
@@ -123,7 +123,7 @@ void LEDLights::set_color(const LEDColor &incol
     // If the pins can do PWM then their intensity will be set.
     #define _UPDATE_RGBW(C,c) do {                 \
       if (PWM_PIN(RGB_LED_##C##_PIN))              \
-        hal.set_pwm_duty(pin_t(RGB_LED_##C##_PIN), c); \
+        set_pwm_duty(pin_t(RGB_LED_##C##_PIN), c); \
       else                                         \
         WRITE(RGB_LED_##C##_PIN, c ? HIGH : LOW);  \
     }while(0)
diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp
index 2840a92c58..cde2b47d90 100644
--- a/Marlin/src/feature/spindle_laser.cpp
+++ b/Marlin/src/feature/spindle_laser.cpp
@@ -66,10 +66,10 @@ void SpindleLaser::init() {
   #endif
   #if ENABLED(SPINDLE_LASER_USE_PWM)
     SET_PWM(SPINDLE_LASER_PWM_PIN);
-    hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed
+    set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed
   #endif
   #if ENABLED(HAL_CAN_SET_PWM_FREQ) && defined(SPINDLE_LASER_FREQUENCY)
-    hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY);
+    set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY);
     TERN_(MARLIN_DEV_MODE, frequency = SPINDLE_LASER_FREQUENCY);
   #endif
   #if ENABLED(AIR_EVACUATION)
@@ -90,10 +90,10 @@ void SpindleLaser::init() {
    * @param ocr Power value
    */
   void SpindleLaser::_set_ocr(const uint8_t ocr) {
-    #if BOTH(NEEDS_HARDWARE_PWM, HAL_CAN_SET_PWM_FREQ) && SPINDLE_LASER_FREQUENCY
-      hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY));
+    #if NEEDS_HARDWARE_PWM && SPINDLE_LASER_FREQUENCY
+      set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY));
     #endif
-    hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF);
+    set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF);
   }
 
   void SpindleLaser::set_ocr(const uint8_t ocr) {
diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h
index 0415c9c8bb..95d60ae486 100644
--- a/Marlin/src/feature/spindle_laser.h
+++ b/Marlin/src/feature/spindle_laser.h
@@ -103,7 +103,7 @@ public:
   static void init();
 
   #if ENABLED(MARLIN_DEV_MODE)
-    static inline void refresh_frequency() { hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); }
+    static inline void refresh_frequency() { set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); }
   #endif
 
   // Modifying this function should update everywhere
diff --git a/Marlin/src/gcode/control/M42.cpp b/Marlin/src/gcode/control/M42.cpp
index 8076818317..77c0ccc49b 100644
--- a/Marlin/src/gcode/control/M42.cpp
+++ b/Marlin/src/gcode/control/M42.cpp
@@ -126,10 +126,10 @@ void GcodeSuite::M42() {
   extDigitalWrite(pin, pin_status);
 
   #ifdef ARDUINO_ARCH_STM32
-    // A simple I/O will be set to 0 by hal.set_pwm_duty()
+    // A simple I/O will be set to 0 by set_pwm_duty()
     if (pin_status <= 1 && !PWM_PIN(pin)) return;
   #endif
-  hal.set_pwm_duty(pin, pin_status);
+  set_pwm_duty(pin, pin_status);
 }
 
 #endif // DIRECT_PIN_CONTROL
diff --git a/Marlin/src/gcode/gcode_d.cpp b/Marlin/src/gcode/gcode_d.cpp
index 2dd1de0001..204455e65e 100644
--- a/Marlin/src/gcode/gcode_d.cpp
+++ b/Marlin/src/gcode/gcode_d.cpp
@@ -38,7 +38,7 @@
 #include "../sd/cardreader.h"
 #include "../MarlinCore.h" // for kill
 
-void dump_delay_accuracy_check();
+extern void dump_delay_accuracy_check();
 
 /**
  * Dn: G-code for development and testing
@@ -54,7 +54,7 @@ void GcodeSuite::D(const int16_t dcode) {
       for (;;) { /* loop forever (watchdog reset) */ }
 
     case 0:
-      hal.reboot();
+      HAL_reboot();
       break;
 
     case 10:
@@ -74,7 +74,7 @@ void GcodeSuite::D(const int16_t dcode) {
         settings.reset();
         settings.save();
       #endif
-      hal.reboot();
+      HAL_reboot();
     } break;
 
     case 2: { // D2 Read / Write SRAM
@@ -189,12 +189,12 @@ void GcodeSuite::D(const int16_t dcode) {
       SERIAL_ECHOLNPGM("(USE_WATCHDOG " TERN(USE_WATCHDOG, "ENABLED", "DISABLED") ")");
       thermalManager.disable_all_heaters();
       delay(1000); // Allow time to print
-      hal.isr_off();
+      DISABLE_ISRS();
       // Use a low-level delay that does not rely on interrupts to function
       // Do not spin forever, to avoid thermal risks if heaters are enabled and
       // watchdog does not work.
       for (int i = 10000; i--;) DELAY_US(1000UL);
-      hal.isr_on();
+      ENABLE_ISRS();
       SERIAL_ECHOLNPGM("FAILURE: Watchdog did not trigger board reset.");
     } break;
 
diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h
index 6ee58f769b..c8ac48f7cf 100644
--- a/Marlin/src/inc/SanityCheck.h
+++ b/Marlin/src/inc/SanityCheck.h
@@ -3850,10 +3850,3 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive.");
 #undef _TEST_PWM
 #undef _LINEAR_AXES_STR
 #undef _LOGICAL_AXES_STR
-
-// JTAG support in the HAL
-#if ENABLED(DISABLE_DEBUG) && !defined(JTAGSWD_DISABLE)
-  #error "DISABLE_DEBUG is not supported for the selected MCU/Board."
-#elif ENABLED(DISABLE_JTAG) && !defined(JTAG_DISABLE)
-  #error "DISABLE_JTAG is not supported for the selected MCU/Board."
-#endif
diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp
index 61db2db920..59c74148ad 100644
--- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp
+++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp
@@ -282,9 +282,9 @@ void MarlinUI::init_lcd() {
   #if PIN_EXISTS(LCD_RESET)
     // Perform a clean hardware reset with needed delays
     OUT_WRITE(LCD_RESET_PIN, LOW);
-    hal.delay_ms(5);
+    _delay_ms(5);
     WRITE(LCD_RESET_PIN, HIGH);
-    hal.delay_ms(5);
+    _delay_ms(5);
     u8g.begin();
   #endif
 
diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp
index 64a65bb686..d1a9ba7077 100644
--- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp
+++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp
@@ -2149,7 +2149,7 @@ void RebootPrinter() {
   thermalManager.disable_all_heaters();
   planner.finish_and_disable();
   DWIN_RebootScreen();
-  hal.reboot();
+  HAL_reboot();
 }
 
 void Goto_InfoMenu(){
diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp
index df6a857803..7a2cefdd4c 100644
--- a/Marlin/src/module/endstops.cpp
+++ b/Marlin/src/module/endstops.cpp
@@ -1345,7 +1345,7 @@ void Endstops::update() {
         ES_REPORT_CHANGE(K_MAX);
       #endif
       SERIAL_ECHOLNPGM("\n");
-      hal.set_pwm_duty(pin_t(LED_PIN), local_LED_status);
+      set_pwm_duty(pin_t(LED_PIN), local_LED_status);
       local_LED_status ^= 255;
       old_live_state_local = live_state_local;
     }
diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp
index 752834c6ab..45ccdd1702 100644
--- a/Marlin/src/module/planner.cpp
+++ b/Marlin/src/module/planner.cpp
@@ -1264,7 +1264,7 @@ void Planner::recalculate() {
     #if ENABLED(FAN_SOFT_PWM)
       #define _FAN_SET(F) thermalManager.soft_pwm_amount_fan[F] = CALC_FAN_SPEED(F);
     #else
-      #define _FAN_SET(F) hal.set_pwm_duty(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F));
+      #define _FAN_SET(F) set_pwm_duty(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F));
     #endif
     #define FAN_SET(F) do{ kickstart_fan(fan_speed, ms, F); _FAN_SET(F); }while(0)
 
@@ -1400,8 +1400,8 @@ void Planner::check_axes_activity() {
   TERN_(AUTOTEMP, autotemp_task());
 
   #if ENABLED(BARICUDA)
-    TERN_(HAS_HEATER_1, hal.set_pwm_duty(pin_t(HEATER_1_PIN), tail_valve_pressure));
-    TERN_(HAS_HEATER_2, hal.set_pwm_duty(pin_t(HEATER_2_PIN), tail_e_to_p_pressure));
+    TERN_(HAS_HEATER_1, set_pwm_duty(pin_t(HEATER_1_PIN), tail_valve_pressure));
+    TERN_(HAS_HEATER_2, set_pwm_duty(pin_t(HEATER_2_PIN), tail_e_to_p_pressure));
   #endif
 }
 
diff --git a/Marlin/src/module/servo.cpp b/Marlin/src/module/servo.cpp
index 96d5ba9da8..231efe84e1 100644
--- a/Marlin/src/module/servo.cpp
+++ b/Marlin/src/module/servo.cpp
@@ -30,7 +30,7 @@
 
 #include "servo.h"
 
-hal_servo_t servo[NUM_SERVOS];
+HAL_SERVO_LIB servo[NUM_SERVOS];
 
 #if ENABLED(EDITABLE_SERVO_ANGLES)
   uint16_t servo_angles[NUM_SERVOS][2];
diff --git a/Marlin/src/module/servo.h b/Marlin/src/module/servo.h
index cd55a317a2..73dbbdddb7 100644
--- a/Marlin/src/module/servo.h
+++ b/Marlin/src/module/servo.h
@@ -112,5 +112,5 @@
 #define MOVE_SERVO(I, P) servo[I].move(P)
 #define DETACH_SERVO(I) servo[I].detach()
 
-extern hal_servo_t servo[NUM_SERVOS];
+extern HAL_SERVO_LIB servo[NUM_SERVOS];
 void servo_init();
diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp
index 0f47d66791..c100051f98 100644
--- a/Marlin/src/module/stepper.cpp
+++ b/Marlin/src/module/stepper.cpp
@@ -1474,7 +1474,7 @@ void Stepper::isr() {
   #ifndef __AVR__
     // Disable interrupts, to avoid ISR preemption while we reprogram the period
     // (AVR enters the ISR with global interrupts disabled, so no need to do it here)
-    hal.isr_off();
+    DISABLE_ISRS();
   #endif
 
   // Program timer compare for the maximum period, so it does NOT
@@ -1492,7 +1492,7 @@ void Stepper::isr() {
   hal_timer_t min_ticks;
   do {
     // Enable ISRs to reduce USART processing latency
-    hal.isr_on();
+    ENABLE_ISRS();
 
     if (!nextMainISR) pulse_phase_isr();                            // 0 = Do coordinated axes Stepper pulses
 
@@ -1576,7 +1576,7 @@ void Stepper::isr() {
      * is less than the current count due to something preempting between the
      * read and the write of the new period value).
      */
-    hal.isr_off();
+    DISABLE_ISRS();
 
     /**
      * Get the current tick value + margin
@@ -1611,7 +1611,7 @@ void Stepper::isr() {
   HAL_timer_set_compare(MF_TIMER_STEP, hal_timer_t(next_isr_ticks));
 
   // Don't forget to finally reenable interrupts
-  hal.isr_on();
+  ENABLE_ISRS();
 }
 
 #if MINIMUM_STEPPER_PULSE || MAXIMUM_STEPPER_RATE
@@ -3261,7 +3261,7 @@ void Stepper::report_positions() {
 
       #elif HAS_MOTOR_CURRENT_PWM
 
-        #define _WRITE_CURRENT_PWM(P) hal.set_pwm_duty(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE))
+        #define _WRITE_CURRENT_PWM(P) set_pwm_duty(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE))
         switch (driver) {
           case 0:
             #if PIN_EXISTS(MOTOR_CURRENT_PWM_X)
diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp
index 1960dc5d9b..dccdc55034 100644
--- a/Marlin/src/module/temperature.cpp
+++ b/Marlin/src/module/temperature.cpp
@@ -326,7 +326,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED);
   #define _INIT_FAN_PIN(P) do{ if (PWM_PIN(P)) SET_PWM(P); else _INIT_SOFT_FAN(P); }while(0)
 #endif
 #if ENABLED(FAST_PWM_FAN)
-  #define SET_FAST_PWM_FREQ(P) hal.set_pwm_frequency(pin_t(P), FAST_PWM_FAN_FREQUENCY)
+  #define SET_FAST_PWM_FREQ(P) set_pwm_frequency(P, FAST_PWM_FAN_FREQUENCY)
 #else
   #define SET_FAST_PWM_FREQ(P) NOOP
 #endif
@@ -813,7 +813,7 @@ volatile bool Temperature::raw_temps_ready = false;
       }
 
       // Run HAL idle tasks
-      hal.idletask();
+      TERN_(HAL_IDLETASK, HAL_idletask());
 
       // Run UI update
       TERN(HAS_DWIN_E3V2_BASIC, DWIN_Update(), ui.update());
@@ -912,7 +912,7 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) {
 
     #define _UPDATE_AUTO_FAN(P,D,A) do{                   \
       if (PWM_PIN(P##_AUTO_FAN_PIN) && A < 255)           \
-        hal.set_pwm_duty(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \
+        set_pwm_duty(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \
       else                                                \
         WRITE(P##_AUTO_FAN_PIN, D);                       \
     }while(0)
@@ -2326,73 +2326,73 @@ void Temperature::init() {
 
   TERN_(HAS_MAXTC_SW_SPI, max_tc_spi.init());
 
-  hal.adc_init();
+  HAL_adc_init();
 
   #if HAS_TEMP_ADC_0
-    hal.adc_enable(TEMP_0_PIN);
+    HAL_ANALOG_SELECT(TEMP_0_PIN);
   #endif
   #if HAS_TEMP_ADC_1
-    hal.adc_enable(TEMP_1_PIN);
+    HAL_ANALOG_SELECT(TEMP_1_PIN);
   #endif
   #if HAS_TEMP_ADC_2
-    hal.adc_enable(TEMP_2_PIN);
+    HAL_ANALOG_SELECT(TEMP_2_PIN);
   #endif
   #if HAS_TEMP_ADC_3
-    hal.adc_enable(TEMP_3_PIN);
+    HAL_ANALOG_SELECT(TEMP_3_PIN);
   #endif
   #if HAS_TEMP_ADC_4
-    hal.adc_enable(TEMP_4_PIN);
+    HAL_ANALOG_SELECT(TEMP_4_PIN);
   #endif
   #if HAS_TEMP_ADC_5
-    hal.adc_enable(TEMP_5_PIN);
+    HAL_ANALOG_SELECT(TEMP_5_PIN);
   #endif
   #if HAS_TEMP_ADC_6
-    hal.adc_enable(TEMP_6_PIN);
+    HAL_ANALOG_SELECT(TEMP_6_PIN);
   #endif
   #if HAS_TEMP_ADC_7
-    hal.adc_enable(TEMP_7_PIN);
+    HAL_ANALOG_SELECT(TEMP_7_PIN);
   #endif
   #if HAS_JOY_ADC_X
-    hal.adc_enable(JOY_X_PIN);
+    HAL_ANALOG_SELECT(JOY_X_PIN);
   #endif
   #if HAS_JOY_ADC_Y
-    hal.adc_enable(JOY_Y_PIN);
+    HAL_ANALOG_SELECT(JOY_Y_PIN);
   #endif
   #if HAS_JOY_ADC_Z
-    hal.adc_enable(JOY_Z_PIN);
+    HAL_ANALOG_SELECT(JOY_Z_PIN);
   #endif
   #if HAS_JOY_ADC_EN
     SET_INPUT_PULLUP(JOY_EN_PIN);
   #endif
   #if HAS_TEMP_ADC_BED
-    hal.adc_enable(TEMP_BED_PIN);
+    HAL_ANALOG_SELECT(TEMP_BED_PIN);
   #endif
   #if HAS_TEMP_ADC_CHAMBER
-    hal.adc_enable(TEMP_CHAMBER_PIN);
+    HAL_ANALOG_SELECT(TEMP_CHAMBER_PIN);
   #endif
   #if HAS_TEMP_ADC_COOLER
-    hal.adc_enable(TEMP_COOLER_PIN);
+    HAL_ANALOG_SELECT(TEMP_COOLER_PIN);
   #endif
   #if HAS_TEMP_ADC_PROBE
-    hal.adc_enable(TEMP_PROBE_PIN);
+    HAL_ANALOG_SELECT(TEMP_PROBE_PIN);
   #endif
   #if HAS_TEMP_ADC_BOARD
-    hal.adc_enable(TEMP_BOARD_PIN);
+    HAL_ANALOG_SELECT(TEMP_BOARD_PIN);
   #endif
   #if HAS_TEMP_ADC_REDUNDANT
-    hal.adc_enable(TEMP_REDUNDANT_PIN);
+    HAL_ANALOG_SELECT(TEMP_REDUNDANT_PIN);
   #endif
   #if ENABLED(FILAMENT_WIDTH_SENSOR)
-    hal.adc_enable(FILWIDTH_PIN);
+    HAL_ANALOG_SELECT(FILWIDTH_PIN);
   #endif
   #if HAS_ADC_BUTTONS
-    hal.adc_enable(ADC_KEYPAD_PIN);
+    HAL_ANALOG_SELECT(ADC_KEYPAD_PIN);
   #endif
   #if ENABLED(POWER_MONITOR_CURRENT)
-    hal.adc_enable(POWER_MONITOR_CURRENT_PIN);
+    HAL_ANALOG_SELECT(POWER_MONITOR_CURRENT_PIN);
   #endif
   #if ENABLED(POWER_MONITOR_VOLTAGE)
-    hal.adc_enable(POWER_MONITOR_VOLTAGE_PIN);
+    HAL_ANALOG_SELECT(POWER_MONITOR_VOLTAGE_PIN);
   #endif
 
   HAL_timer_start(MF_TIMER_TEMP, TEMP_TIMER_FREQUENCY);
@@ -3333,8 +3333,8 @@ void Temperature::isr() {
    * This gives each ADC 0.9765ms to charge up.
    */
   #define ACCUMULATE_ADC(obj) do{ \
-    if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; \
-    else obj.sample(hal.adc_value()); \
+    if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; \
+    else obj.sample(HAL_READ_ADC()); \
   }while(0)
 
   ADCSensorState next_sensor_state = adc_sensor_state < SensorsReady ? (ADCSensorState)(int(adc_sensor_state) + 1) : StartSampling;
@@ -3366,115 +3366,115 @@ void Temperature::isr() {
       break;
 
     #if HAS_TEMP_ADC_0
-      case PrepareTemp_0: hal.adc_start(TEMP_0_PIN); break;
+      case PrepareTemp_0: HAL_START_ADC(TEMP_0_PIN); break;
       case MeasureTemp_0: ACCUMULATE_ADC(temp_hotend[0]); break;
     #endif
 
     #if HAS_TEMP_ADC_BED
-      case PrepareTemp_BED: hal.adc_start(TEMP_BED_PIN); break;
+      case PrepareTemp_BED: HAL_START_ADC(TEMP_BED_PIN); break;
       case MeasureTemp_BED: ACCUMULATE_ADC(temp_bed); break;
     #endif
 
     #if HAS_TEMP_ADC_CHAMBER
-      case PrepareTemp_CHAMBER: hal.adc_start(TEMP_CHAMBER_PIN); break;
+      case PrepareTemp_CHAMBER: HAL_START_ADC(TEMP_CHAMBER_PIN); break;
       case MeasureTemp_CHAMBER: ACCUMULATE_ADC(temp_chamber); break;
     #endif
 
     #if HAS_TEMP_ADC_COOLER
-      case PrepareTemp_COOLER: hal.adc_start(TEMP_COOLER_PIN); break;
+      case PrepareTemp_COOLER: HAL_START_ADC(TEMP_COOLER_PIN); break;
       case MeasureTemp_COOLER: ACCUMULATE_ADC(temp_cooler); break;
     #endif
 
     #if HAS_TEMP_ADC_PROBE
-      case PrepareTemp_PROBE: hal.adc_start(TEMP_PROBE_PIN); break;
+      case PrepareTemp_PROBE: HAL_START_ADC(TEMP_PROBE_PIN); break;
       case MeasureTemp_PROBE: ACCUMULATE_ADC(temp_probe); break;
     #endif
 
     #if HAS_TEMP_ADC_BOARD
-      case PrepareTemp_BOARD: hal.adc_start(TEMP_BOARD_PIN); break;
+      case PrepareTemp_BOARD: HAL_START_ADC(TEMP_BOARD_PIN); break;
       case MeasureTemp_BOARD: ACCUMULATE_ADC(temp_board); break;
     #endif
 
     #if HAS_TEMP_ADC_REDUNDANT
-      case PrepareTemp_REDUNDANT: hal.adc_start(TEMP_REDUNDANT_PIN); break;
+      case PrepareTemp_REDUNDANT: HAL_START_ADC(TEMP_REDUNDANT_PIN); break;
       case MeasureTemp_REDUNDANT: ACCUMULATE_ADC(temp_redundant); break;
     #endif
 
     #if HAS_TEMP_ADC_1
-      case PrepareTemp_1: hal.adc_start(TEMP_1_PIN); break;
+      case PrepareTemp_1: HAL_START_ADC(TEMP_1_PIN); break;
       case MeasureTemp_1: ACCUMULATE_ADC(temp_hotend[1]); break;
     #endif
 
     #if HAS_TEMP_ADC_2
-      case PrepareTemp_2: hal.adc_start(TEMP_2_PIN); break;
+      case PrepareTemp_2: HAL_START_ADC(TEMP_2_PIN); break;
       case MeasureTemp_2: ACCUMULATE_ADC(temp_hotend[2]); break;
     #endif
 
     #if HAS_TEMP_ADC_3
-      case PrepareTemp_3: hal.adc_start(TEMP_3_PIN); break;
+      case PrepareTemp_3: HAL_START_ADC(TEMP_3_PIN); break;
       case MeasureTemp_3: ACCUMULATE_ADC(temp_hotend[3]); break;
     #endif
 
     #if HAS_TEMP_ADC_4
-      case PrepareTemp_4: hal.adc_start(TEMP_4_PIN); break;
+      case PrepareTemp_4: HAL_START_ADC(TEMP_4_PIN); break;
       case MeasureTemp_4: ACCUMULATE_ADC(temp_hotend[4]); break;
     #endif
 
     #if HAS_TEMP_ADC_5
-      case PrepareTemp_5: hal.adc_start(TEMP_5_PIN); break;
+      case PrepareTemp_5: HAL_START_ADC(TEMP_5_PIN); break;
       case MeasureTemp_5: ACCUMULATE_ADC(temp_hotend[5]); break;
     #endif
 
     #if HAS_TEMP_ADC_6
-      case PrepareTemp_6: hal.adc_start(TEMP_6_PIN); break;
+      case PrepareTemp_6: HAL_START_ADC(TEMP_6_PIN); break;
       case MeasureTemp_6: ACCUMULATE_ADC(temp_hotend[6]); break;
     #endif
 
     #if HAS_TEMP_ADC_7
-      case PrepareTemp_7: hal.adc_start(TEMP_7_PIN); break;
+      case PrepareTemp_7: HAL_START_ADC(TEMP_7_PIN); break;
       case MeasureTemp_7: ACCUMULATE_ADC(temp_hotend[7]); break;
     #endif
 
     #if ENABLED(FILAMENT_WIDTH_SENSOR)
-      case Prepare_FILWIDTH: hal.adc_start(FILWIDTH_PIN); break;
+      case Prepare_FILWIDTH: HAL_START_ADC(FILWIDTH_PIN); break;
       case Measure_FILWIDTH:
-        if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state
-        else filwidth.accumulate(hal.adc_value());
+        if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state
+        else filwidth.accumulate(HAL_READ_ADC());
       break;
     #endif
 
     #if ENABLED(POWER_MONITOR_CURRENT)
       case Prepare_POWER_MONITOR_CURRENT:
-        hal.adc_start(POWER_MONITOR_CURRENT_PIN);
+        HAL_START_ADC(POWER_MONITOR_CURRENT_PIN);
         break;
       case Measure_POWER_MONITOR_CURRENT:
-        if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state
-        else power_monitor.add_current_sample(hal.adc_value());
+        if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state
+        else power_monitor.add_current_sample(HAL_READ_ADC());
         break;
     #endif
 
     #if ENABLED(POWER_MONITOR_VOLTAGE)
       case Prepare_POWER_MONITOR_VOLTAGE:
-        hal.adc_start(POWER_MONITOR_VOLTAGE_PIN);
+        HAL_START_ADC(POWER_MONITOR_VOLTAGE_PIN);
         break;
       case Measure_POWER_MONITOR_VOLTAGE:
-        if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state
-        else power_monitor.add_voltage_sample(hal.adc_value());
+        if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state
+        else power_monitor.add_voltage_sample(HAL_READ_ADC());
         break;
     #endif
 
     #if HAS_JOY_ADC_X
-      case PrepareJoy_X: hal.adc_start(JOY_X_PIN); break;
+      case PrepareJoy_X: HAL_START_ADC(JOY_X_PIN); break;
       case MeasureJoy_X: ACCUMULATE_ADC(joystick.x); break;
     #endif
 
     #if HAS_JOY_ADC_Y
-      case PrepareJoy_Y: hal.adc_start(JOY_Y_PIN); break;
+      case PrepareJoy_Y: HAL_START_ADC(JOY_Y_PIN); break;
       case MeasureJoy_Y: ACCUMULATE_ADC(joystick.y); break;
     #endif
 
     #if HAS_JOY_ADC_Z
-      case PrepareJoy_Z: hal.adc_start(JOY_Z_PIN); break;
+      case PrepareJoy_Z: HAL_START_ADC(JOY_Z_PIN); break;
       case MeasureJoy_Z: ACCUMULATE_ADC(joystick.z); break;
     #endif
 
@@ -3482,12 +3482,12 @@ void Temperature::isr() {
       #ifndef ADC_BUTTON_DEBOUNCE_DELAY
         #define ADC_BUTTON_DEBOUNCE_DELAY 16
       #endif
-      case Prepare_ADC_KEY: hal.adc_start(ADC_KEYPAD_PIN); break;
+      case Prepare_ADC_KEY: HAL_START_ADC(ADC_KEYPAD_PIN); break;
       case Measure_ADC_KEY:
-        if (!hal.adc_ready())
+        if (!HAL_ADC_READY())
           next_sensor_state = adc_sensor_state; // redo this state
         else if (ADCKey_count < ADC_BUTTON_DEBOUNCE_DELAY) {
-          raw_ADCKey_value = hal.adc_value();
+          raw_ADCKey_value = HAL_READ_ADC();
           if (raw_ADCKey_value <= 900UL * HAL_ADC_RANGE / 1024UL) {
             NOMORE(current_ADCKey_raw, raw_ADCKey_value);
             ADCKey_count++;
diff --git a/ini/native.ini b/ini/native.ini
index eba34afc83..fe5fe3a5d0 100644
--- a/ini/native.ini
+++ b/ini/native.ini
@@ -34,14 +34,14 @@ src_filter      = ${common.default_src_filter} +<src/HAL/LINUX>
 [simulator_common]
 platform          = native
 framework         =
-build_flags       = ${common.build_flags} -std=gnu++17 -D__PLAT_NATIVE_SIM__ -DU8G_HAL_LINKS -I/usr/include/SDL2 -IMarlin -IMarlin/src/HAL/NATIVE_SIM/u8g
+build_flags       = ${common.build_flags} -std=gnu++17 -D__PLAT_NATIVE_SIM__ -DU8G_HAL_LINKS -I/usr/include/SDL2 -IMarlin -IMarlin/src/HAL/NATIVE_SIM/include -IMarlin/src/HAL/NATIVE_SIM/u8g
 src_build_flags   = -Wall -Wno-expansion-to-defined -Wcast-align
 release_flags     = -g0 -O3 -flto
 debug_build_flags = -fstack-protector-strong -g -g3 -ggdb
 lib_compat_mode   = off
 src_filter        = ${common.default_src_filter} +<src/HAL/NATIVE_SIM>
 lib_deps          = ${common.lib_deps}
-  MarlinSimUI=https://github.com/thinkyhead/MarlinSimUI/archive/updated_marlin_hal_2093.zip
+  MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/master.zip
   Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/marlin_sim_native.zip
   LiquidCrystal=https://github.com/p3p/LiquidCrystal/archive/master.zip
 extra_scripts = ${common.extra_scripts}