From 9e699811d25918fe64793824b2a2fdbccdf3b7bd Mon Sep 17 00:00:00 2001
From: Thomas Moore <tcm0116@users.noreply.github.com>
Date: Thu, 26 Oct 2017 13:37:26 -0500
Subject: [PATCH] Make LPC1768 pinmapping not specific to Re-ARM (#8063)

* Merging early because of build failures.  See #8105

* Make LPC1768 pinmapping not specific to Re-ARM

* Add HAL_PIN_TYPE and LPC1768 pin features

* M43 Updates

* Move pin map into pinsDebug_LPC1768.h

* Incorporate comments and M226

* Fix persistent store compilation issues

* Update pin features

* Update MKS SBASE pins

* Use native LPC1768 pin numbers in M42, M43, and M226
---
 .gitignore                                    |   1 +
 Marlin/src/HAL/HAL_AVR/HAL_AVR.h              |  10 +-
 Marlin/src/HAL/HAL_AVR/HAL_pinsDebug_AVR.h    |   4 +-
 Marlin/src/HAL/HAL_AVR/pinsDebug_AVR_8_bit.h  |   2 +-
 Marlin/src/HAL/HAL_DUE/HAL_Due.h              |   4 +
 Marlin/src/HAL/HAL_DUE/HAL_timers_Due.h       |   4 +-
 Marlin/src/HAL/HAL_LPC1768/HAL.cpp            |  27 +-
 Marlin/src/HAL/HAL_LPC1768/HAL_timers.h       |   8 +-
 Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.cpp    | 509 ++++++++++++++++++
 Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.h      | 452 +---------------
 Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.cpp  |   5 +-
 Marlin/src/HAL/HAL_LPC1768/SoftwareSerial.cpp |   5 +-
 Marlin/src/HAL/HAL_LPC1768/WInterrupts.cpp    |   8 +-
 Marlin/src/HAL/HAL_LPC1768/arduino.cpp        |  39 +-
 Marlin/src/HAL/HAL_LPC1768/fastio.h           |  12 +-
 Marlin/src/HAL/HAL_LPC1768/include/Wire.h     |   2 +-
 Marlin/src/HAL/HAL_LPC1768/include/arduino.h  |  13 +-
 .../include/digipot_mcp4451_I2C_routines.c    |   2 +-
 .../HAL/HAL_LPC1768/lpc1768_flag_script.py    |   3 +-
 Marlin/src/HAL/HAL_LPC1768/main.cpp           |   1 -
 .../HAL/HAL_LPC1768/persistent_store_impl.cpp |   7 +-
 Marlin/src/HAL/HAL_LPC1768/pinmap_re_arm.h    | 464 ----------------
 Marlin/src/HAL/HAL_LPC1768/pinmapping.cpp     |  50 ++
 Marlin/src/HAL/HAL_LPC1768/pinmapping.h       | 192 ++++++-
 ...pinsDebug_Re_ARM.h => pinsDebug_LPC1768.h} |  64 +--
 Marlin/src/HAL/HAL_LPC1768/spi_pins.h         |  10 +-
 Marlin/src/HAL/HAL_STM32F1/HAL_Stm32f1.h      |   6 +
 .../src/HAL/HAL_STM32F1/HAL_timers_Stm32f1.h  |  10 +-
 Marlin/src/HAL/HAL_TEENSY35_36/HAL_Teensy.h   |   6 +
 .../HAL/HAL_TEENSY35_36/HAL_timers_Teensy.h   |   4 +-
 Marlin/src/HAL/HAL_pinsDebug.h                |   2 +-
 Marlin/src/Marlin.cpp                         |  11 +-
 Marlin/src/Marlin.h                           |   2 +-
 Marlin/src/core/serial.cpp                    |   1 +
 Marlin/src/core/serial.h                      |   1 -
 Marlin/src/gcode/config/M43.cpp               |  25 +-
 Marlin/src/gcode/control/M226.cpp             |  13 +-
 Marlin/src/gcode/control/M42.cpp              |  13 +-
 Marlin/src/gcode/parser.h                     |  19 +-
 Marlin/src/module/stepper.cpp                 |  22 +-
 Marlin/src/module/stepper.h                   |  10 +-
 Marlin/src/pins/pins.h                        |   9 +-
 Marlin/src/pins/pinsDebug.h                   |  11 +-
 Marlin/src/pins/pins_MKS_SBASE.h              | 159 +++---
 Marlin/src/pins/pins_RAMPS.h                  |   2 +-
 Marlin/src/pins/pins_RAMPS_RE_ARM.h           | 278 ++++------
 Marlin/src/sd/Sd2Card.cpp                     |   2 +-
 Marlin/src/sd/Sd2Card.h                       |   4 +-
 platformio.ini                                |   8 +-
 49 files changed, 1177 insertions(+), 1339 deletions(-)
 create mode 100644 Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.cpp
 delete mode 100644 Marlin/src/HAL/HAL_LPC1768/pinmap_re_arm.h
 create mode 100644 Marlin/src/HAL/HAL_LPC1768/pinmapping.cpp
 rename Marlin/src/HAL/HAL_LPC1768/{pinsDebug_Re_ARM.h => pinsDebug_LPC1768.h} (63%)

diff --git a/.gitignore b/.gitignore
index 3e6642840d..bd07c9ce7a 100755
--- a/.gitignore
+++ b/.gitignore
@@ -158,6 +158,7 @@ vc-fileutils.settings
 
 #Visual Studio Code
 .vscode
+.vscode/c_cpp_properties.json
 
 #cmake
 CMakeLists.txt
diff --git a/Marlin/src/HAL/HAL_AVR/HAL_AVR.h b/Marlin/src/HAL/HAL_AVR/HAL_AVR.h
index 60a73581c0..42bd6680a1 100644
--- a/Marlin/src/HAL/HAL_AVR/HAL_AVR.h
+++ b/Marlin/src/HAL/HAL_AVR/HAL_AVR.h
@@ -66,9 +66,11 @@
 // Types
 // --------------------------------------------------------------------------
 
-#define HAL_TIMER_TYPE uint16_t
+typedef uint16_t timer_t;
 #define HAL_TIMER_TYPE_MAX 0xFFFF
 
+typedef int8_t pin_t;
+
 #define HAL_SERVO_LIB Servo
 
 // --------------------------------------------------------------------------
@@ -153,4 +155,10 @@ inline void HAL_adc_init(void) {
 
 #define HAL_READ_ADC ADC
 
+#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 HAL_SENSITIVE_PINS 0, 1
+
 #endif // _HAL_AVR_H_
diff --git a/Marlin/src/HAL/HAL_AVR/HAL_pinsDebug_AVR.h b/Marlin/src/HAL/HAL_AVR/HAL_pinsDebug_AVR.h
index a278c08b99..87b9693000 100644
--- a/Marlin/src/HAL/HAL_AVR/HAL_pinsDebug_AVR.h
+++ b/Marlin/src/HAL/HAL_AVR/HAL_pinsDebug_AVR.h
@@ -82,7 +82,7 @@ void HAL_analog_pin_state(char buffer[], int8_t pin) {
 
 typedef struct {
   const char * const name;
-  uint8_t pin;
+  pin_t pin;
   bool is_digital;
 } PinInfo;
 
@@ -457,7 +457,7 @@ static void print_input_or_output(const bool isout) {
 }
 
 // pretty report with PWM info
-inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = false, const char *start_string = "") {
+inline void report_pin_state_extended(pin_t pin, bool ignore, bool extended = false, const char *start_string = "") {
   uint8_t temp_char;
   char *name_mem_pointer, buffer[30];   // for the sprintf statements
   bool found = false, multi_name_pin = false;
diff --git a/Marlin/src/HAL/HAL_AVR/pinsDebug_AVR_8_bit.h b/Marlin/src/HAL/HAL_AVR/pinsDebug_AVR_8_bit.h
index 595283f9c7..60a98446a9 100644
--- a/Marlin/src/HAL/HAL_AVR/pinsDebug_AVR_8_bit.h
+++ b/Marlin/src/HAL/HAL_AVR/pinsDebug_AVR_8_bit.h
@@ -397,6 +397,6 @@ static void pwm_details(uint8_t pin) {
 
 #endif
 
-#define GET_PIN_INFO(pin) do{}while(0)
+#define PRINT_PIN(p) do {sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer);} while (0)
 
 #endif // _PINSDEBUG_AVR_8_BIT_
diff --git a/Marlin/src/HAL/HAL_DUE/HAL_Due.h b/Marlin/src/HAL/HAL_DUE/HAL_Due.h
index 9c6721b8a1..e1a9094d7c 100644
--- a/Marlin/src/HAL/HAL_DUE/HAL_Due.h
+++ b/Marlin/src/HAL/HAL_DUE/HAL_Due.h
@@ -96,6 +96,7 @@
 // Types
 // --------------------------------------------------------------------------
 
+typedef int8_t pin_t;
 
 // --------------------------------------------------------------------------
 // Public Variables
@@ -166,6 +167,9 @@ uint16_t HAL_getAdcFreerun(uint8_t chan, bool wait_for_conversion = false);
 void HAL_enable_AdcFreerun(void);
 //void HAL_disable_AdcFreerun(uint8_t chan);
 
+#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/HAL_DUE/HAL_timers_Due.h b/Marlin/src/HAL/HAL_DUE/HAL_timers_Due.h
index 5dfd42ce94..733c92e2c8 100644
--- a/Marlin/src/HAL/HAL_DUE/HAL_timers_Due.h
+++ b/Marlin/src/HAL/HAL_DUE/HAL_timers_Due.h
@@ -40,7 +40,7 @@
 
 #define FORCE_INLINE __attribute__((always_inline)) inline
 
-#define HAL_TIMER_TYPE uint32_t
+typedef uint32_t timer_t;
 #define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
 
 #define STEP_TIMER_NUM 3  // index of timer to use for stepper
@@ -92,7 +92,7 @@ static FORCE_INLINE void HAL_timer_set_count(const uint8_t timer_num, const uint
   pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_RC = count;
 }
 
-static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count(const uint8_t timer_num) {
+static FORCE_INLINE timer_t HAL_timer_get_count(const uint8_t timer_num) {
   const tTimerConfig *pConfig = &TimerConfig[timer_num];
   return pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_RC;
 }
diff --git a/Marlin/src/HAL/HAL_LPC1768/HAL.cpp b/Marlin/src/HAL/HAL_LPC1768/HAL.cpp
index 29c0964e9b..3c852e8e03 100644
--- a/Marlin/src/HAL/HAL_LPC1768/HAL.cpp
+++ b/Marlin/src/HAL/HAL_LPC1768/HAL.cpp
@@ -81,14 +81,16 @@ void HAL_adc_init(void) {
 extern void kill(const char*);
 extern const char errormagic[];
 
-void HAL_adc_enable_channel(int pin) {
-  if (!WITHIN(pin, 0, NUM_ANALOG_INPUTS - 1)) {
-    MYSERIAL.printf("%sINVALID ANALOG PORT:%d\n", errormagic, pin);
+void HAL_adc_enable_channel(int ch) {
+  pin_t pin = analogInputToDigitalPin(ch);
+
+  if (pin == -1) {
+    MYSERIAL.printf("%sINVALID ANALOG PORT:%d\n", errormagic, ch);
     kill(MSG_KILLED);
   }
 
-  int8_t pin_port = adc_pin_map[pin].port,
-         pin_port_pin = adc_pin_map[pin].pin,
+  int8_t pin_port = LPC1768_PIN_PORT(pin),
+         pin_port_pin = LPC1768_PIN_PIN(pin),
          pinsel_start_bit = pin_port_pin > 15 ? 2 * (pin_port_pin - 16) : 2 * pin_port_pin;
   uint8_t pin_sel_register = (pin_port == 0 && pin_port_pin <= 15) ? 0 :
                               pin_port == 0                        ? 1 :
@@ -111,15 +113,16 @@ void HAL_adc_enable_channel(int pin) {
 }
 
 uint8_t active_adc = 0;
-void HAL_adc_start_conversion(const uint8_t adc_pin) {
-  if (adc_pin >= (NUM_ANALOG_INPUTS) || adc_pin_map[adc_pin].port == 0xFF) {
-    MYSERIAL.printf("HAL: HAL_adc_start_conversion: no pinmap for %d\n", adc_pin);
+void HAL_adc_start_conversion(const uint8_t ch) {
+  if (analogInputToDigitalPin(ch) == -1) {
+    MYSERIAL.printf("HAL: HAL_adc_start_conversion: invalid channel %d\n", ch);
     return;
   }
-  LPC_ADC->ADCR &= ~0xFF;                       // Reset
-  SBI(LPC_ADC->ADCR, adc_pin_map[adc_pin].adc); // Select Channel
-  SBI(LPC_ADC->ADCR, 24);                       // Start conversion
-  active_adc = adc_pin;
+
+  LPC_ADC->ADCR &= ~0xFF; // Reset
+  SBI(LPC_ADC->ADCR, ch); // Select Channel
+  SBI(LPC_ADC->ADCR, 24); // Start conversion
+  active_adc = ch;
 }
 
 bool HAL_adc_finished(void) {
diff --git a/Marlin/src/HAL/HAL_LPC1768/HAL_timers.h b/Marlin/src/HAL/HAL_LPC1768/HAL_timers.h
index 03d782ba7e..596c526ed7 100644
--- a/Marlin/src/HAL/HAL_LPC1768/HAL_timers.h
+++ b/Marlin/src/HAL/HAL_LPC1768/HAL_timers.h
@@ -40,7 +40,7 @@
 
 #define FORCE_INLINE __attribute__((always_inline)) inline
 
-#define HAL_TIMER_TYPE uint32_t
+typedef uint32_t timer_t;
 #define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
 
 #define STEP_TIMER_NUM 0  // index of timer to use for stepper
@@ -77,7 +77,7 @@
 void HAL_timer_init(void);
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
 
-static FORCE_INLINE void HAL_timer_set_count(const uint8_t timer_num, const HAL_TIMER_TYPE count) {
+static FORCE_INLINE void HAL_timer_set_count(const uint8_t timer_num, const timer_t count) {
   switch (timer_num) {
     case 0:
       LPC_TIM0->MR0 = count;
@@ -92,7 +92,7 @@ static FORCE_INLINE void HAL_timer_set_count(const uint8_t timer_num, const HAL_
   }
 }
 
-static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count(const uint8_t timer_num) {
+static FORCE_INLINE timer_t HAL_timer_get_count(const uint8_t timer_num) {
   switch (timer_num) {
     case 0: return LPC_TIM0->MR0;
     case 1: return LPC_TIM1->MR0;
@@ -100,7 +100,7 @@ static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count(const uint8_t timer_num)
   return 0;
 }
 
-static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_current_count(const uint8_t timer_num) {
+static FORCE_INLINE timer_t HAL_timer_get_current_count(const uint8_t timer_num) {
   switch (timer_num) {
     case 0: return LPC_TIM0->TC;
     case 1: return LPC_TIM1->TC;
diff --git a/Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.cpp b/Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.cpp
new file mode 100644
index 0000000000..65cfb56635
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.cpp
@@ -0,0 +1,509 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (C) 2017 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 <http://www.gnu.org/licenses/>.
+ *
+ */
+
+/**
+ * The class Servo uses the PWM class to implement its functions
+ *
+ * All PWMs use the same repetition rate - 20mS because that's the normal servo rate
+*/
+
+/**
+ * This is a hybrid system.
+ *
+ * The PWM1 module is used to directly control the Servo 0, 1 & 3 pins.  This keeps
+ * the pulse width jitter to under a microsecond.
+ *
+ * For all other pins the PWM1 module is used to generate interrupts.  The ISR
+ * routine does the actual setting/clearing of pins.  The upside is that any pin can
+ * have a PWM channel assigned to it.  The downside is that there is more pulse width
+ * jitter. The jitter depends on what else is happening in the system and what ISRs
+ * prempt the PWM ISR.  Writing to the SD card can add 20 microseconds to the pulse
+ * width.
+ */
+
+/**
+ * The data structures are setup to minimize the computation done by the ISR which
+ * minimizes ISR execution time.  Execution times are 2.2 - 3.7 microseconds.
+ *
+ * Two tables are used.  active_table is used by the ISR.  Changes to the table are
+ * are done by copying the active_table into the work_table, updating the work_table
+ * and then swapping the two tables.  Swapping is done by manipulating pointers.
+ *
+ * Immediately after the swap the ISR uses the work_table until the start of the
+ * next 20mS cycle. During this transition the "work_table" is actually the table
+ * that was being used before the swap.  The "active_table" contains the data that
+ * will start being used at the start of the next 20mS period.  This keeps the pins
+ * well behaved during the transition.
+ *
+ * The ISR's priority is set to the maximum otherwise other ISRs can cause considerable
+ * jitter in the PWM high time.
+ *
+ * See the end of this file for details on the hardware/firmware interaction
+ */
+
+
+#ifdef TARGET_LPC1768
+#include <lpc17xx_pinsel.h>
+#include "LPC1768_PWM.h"
+#include "arduino.h"
+
+#define NUM_PWMS 6
+
+typedef struct {            // holds all data needed to control/init one of the PWM channels
+    uint8_t             sequence;       // 0: available slot, 1 - 6: PWM channel assigned to that slot
+    pin_t               pin;
+    uint16_t            PWM_mask;       // MASK TO CHECK/WRITE THE IR REGISTER
+    volatile uint32_t*  set_register;
+    volatile uint32_t*  clr_register;
+    uint32_t            write_mask;     // USED BY SET/CLEAR COMMANDS
+    uint32_t            microseconds;   // value written to MR register
+    uint32_t            min;            // lower value limit checked by WRITE routine before writing to the MR register
+    uint32_t            max;            // upper value limit checked by WRITE routine before writing to the MR register
+    bool                PWM_flag;       // 0 - USED BY sERVO, 1 - USED BY ANALOGWRITE
+    uint8_t             servo_index;    // 0 - MAX_SERVO -1 : servo index,  0xFF : PWM channel
+    bool                active_flag;    // THIS TABLE ENTRY IS ACTIVELY TOGGLING A PIN
+    uint8_t             assigned_MR;    // Which MR (1-6) is used by this logical channel
+    uint32_t            PCR_bit;        // PCR register bit to enable PWM1 control of this pin
+    uint32_t            PINSEL3_bits;   // PINSEL3 register bits to set pin mode to PWM1 control
+
+} PWM_map;
+
+
+#define MICRO_MAX 0xffffffff
+
+#define PWM_MAP_INIT_ROW {0, 0xff, 0, 0, 0, 0, MICRO_MAX, 0, 0, 0, 0, 0, 0, 0, 0}
+#define PWM_MAP_INIT {PWM_MAP_INIT_ROW,\
+                      PWM_MAP_INIT_ROW,\
+                      PWM_MAP_INIT_ROW,\
+                      PWM_MAP_INIT_ROW,\
+                      PWM_MAP_INIT_ROW,\
+                      PWM_MAP_INIT_ROW,\
+                     };
+
+PWM_map PWM1_map_A[NUM_PWMS] = PWM_MAP_INIT;
+PWM_map PWM1_map_B[NUM_PWMS] = PWM_MAP_INIT;
+
+PWM_map *active_table = PWM1_map_A;
+PWM_map *work_table = PWM1_map_B;
+PWM_map *ISR_table;
+
+
+#define IR_BIT(p) (p >= 0 && p <= 3 ? p : p + 4 )
+#define COPY_ACTIVE_TABLE    for (uint8_t i = 0; i < 6 ; i++) work_table[i] = active_table[i]
+#define PIN_IS_INVERTED(p) 0  // place holder in case inverting PWM output is offered
+
+
+/**
+ *  Prescale register and MR0 register values
+ *
+ *               100MHz PCLK          50MHz PCLK          25MHz PCLK         12.5MHz PCLK
+ *             -----------------   -----------------   -----------------   -----------------
+ *  desired    prescale  MR0       prescale  MR0       prescale  MR0       prescale  MR0        resolution
+ *  prescale   register  register  register  register  register  register  register  register   in degrees
+ *  freq       value     value     value     value     value     value     value     value
+ *
+ *      8        11.5    159,999      5.25   159,999       2.13  159,999    0.5625   159,999    0.023
+ *      4        24       79,999     11.5     79,999       5.25   79,999    2.125     79,999    0.045
+ *      2        49       39,999     24       39,999      11.5    39,999    5.25      39,999    0.090
+ *      1        99       19,999     49       19,999      24      19,999   11.5       19,999    0.180
+ *    0.5       199        9,999     99        9,999      49       9,999   24          9,999    0.360
+ *   0.25       399        4,999    199        4,999      99       4,999   49          4,999    0.720
+ *  0.125       799        2,499    399        2,499     199       2,499   99          2,499    1.440
+ *
+ *  The desired prescale frequency comes from an input in the range of 544 - 2400 microseconds and the
+ *  desire to just shift the input left or right as needed.
+ *
+ *  A resolution of 0.2 degrees seems reasonable so a prescale frequency output of 1MHz is being used.
+ *  It also means we don't need to scale the input.
+ *
+ *  The PCLK is set to 25MHz because that's the slowest one that gives whole numbers for prescale and
+ *  MR0 registers.
+ *
+ *  Final settings:
+ *   PCLKSEL0: 0x0
+ *   PWM1PR:   0x018 (24)
+ *   PWM1MR0:  0x04E1F (19,999)
+ *
+ */
+
+
+void LPC1768_PWM_init(void) {
+  #define SBIT_CNTEN     0  // PWM1 counter & pre-scaler enable/disable
+  #define SBIT_CNTRST    1  // reset counters to known state
+  #define SBIT_PWMEN     3  // 1 - PWM, 0 - timer
+  #define SBIT_PWMMR0R   1
+  #define PCPWM1         6
+  #define PCLK_PWM1      12
+
+  LPC_SC->PCONP |= (1 << PCPWM1);      // enable PWM1 controller (enabled on power up)
+  LPC_SC->PCLKSEL0 &= ~(0x3 << PCLK_PWM1);
+  LPC_SC->PCLKSEL0 |= (LPC_PWM1_PCLKSEL0 << PCLK_PWM1);
+  LPC_PWM1->MR0 = LPC_PWM1_MR0;                // TC resets every 19,999 + 1 cycles - sets PWM cycle(Ton+Toff) to 20 mS
+                                        // MR0 must be set before TCR enables the PWM
+  LPC_PWM1->TCR = _BV(SBIT_CNTEN) | _BV(SBIT_CNTRST)| _BV(SBIT_PWMEN);;  // enable counters, reset counters, set mode to PWM
+  LPC_PWM1->TCR &= ~(_BV(SBIT_CNTRST));  // take counters out of reset
+  LPC_PWM1->PR  =  LPC_PWM1_PR;
+  LPC_PWM1->MCR = (_BV(SBIT_PWMMR0R) | _BV(0));     // Reset TC if it matches MR0, disable all interrupts except for MR0
+  LPC_PWM1->CTCR = 0;                   // disable counter mode (enable PWM mode)
+
+  LPC_PWM1->LER = 0x07F;  // Set the latch Enable Bits to load the new Match Values for MR0 - MR6
+  // Set all PWMs to single edge
+  LPC_PWM1->PCR = 0;    // single edge mode for all channels, PWM1 control of outputs off
+
+  NVIC_EnableIRQ(PWM1_IRQn);     // Enable interrupt handler
+  //      NVIC_SetPriority(PWM1_IRQn, NVIC_EncodePriority(0, 10, 0));  // normal priority for PWM module
+  NVIC_SetPriority(PWM1_IRQn, NVIC_EncodePriority(0, 0, 0));  // minimizes jitter due to higher priority ISRs
+}
+
+
+bool PWM_table_swap = false;  // flag to tell the ISR that the tables have been swapped
+bool PWM_MR0_wait = false;  // flag to ensure don't delay MR0 interrupt
+
+
+bool LPC1768_PWM_attach_pin(pin_t pin, uint32_t min /* = 1 */, uint32_t max /* = (LPC_PWM1_MR0 - MR0_MARGIN) */, uint8_t servo_index /* = 0xff */) {
+  while (PWM_table_swap) delay(5);  // don't do anything until the previous change has been implemented by the ISR
+  COPY_ACTIVE_TABLE;  // copy active table into work table
+  uint8_t slot = 0;
+  for (uint8_t i = 0; i < NUM_PWMS ; i++)         // see if already in table
+    if (work_table[i].pin == pin) return 1;
+
+  for (uint8_t i = 1; (i < NUM_PWMS + 1) && !slot; i++)         // find empty slot
+    if ( !(work_table[i - 1].set_register)) slot = i;  // any item that can't be zero when active or just attached is OK
+  if (!slot) return 0;
+  slot--;  // turn it into array index
+
+  work_table[slot].pin = pin;     // init slot
+  work_table[slot].PWM_mask = 0;  // real value set by PWM_write
+  work_table[slot].set_register = PIN_IS_INVERTED(pin) ? &LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOCLR : &LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOSET;
+  work_table[slot].clr_register = PIN_IS_INVERTED(pin) ? &LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOSET : &LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOCLR;
+  work_table[slot].write_mask = LPC_PIN(LPC1768_PIN_PIN(pin));
+  work_table[slot].microseconds = MICRO_MAX;
+  work_table[slot].min = min;
+  work_table[slot].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
+  work_table[slot].servo_index = servo_index;
+  work_table[slot].active_flag = false;
+
+  //swap tables
+  PWM_MR0_wait = true;
+  while (PWM_MR0_wait) delay(5);  //wait until MR0 interrupt has happend so don't delay it.
+
+  NVIC_DisableIRQ(PWM1_IRQn);
+  PWM_map *pointer_swap = active_table;
+  active_table = work_table;
+  work_table = pointer_swap;
+  PWM_table_swap = true;  // tell the ISR that the tables have been swapped
+  NVIC_EnableIRQ(PWM1_IRQn);  // re-enable PWM interrupts
+
+  return 1;
+}
+
+#define pin_11_PWM_channel 2
+#define pin_6_PWM_channel  3
+#define pin_4_PWM_channel  1
+
+// used to keep track of which Match Registers have been used and if they will be used by the
+// PWM1 module to directly control the pin or will be used to generate an interrupt
+typedef struct {                        // status of PWM1 channel
+    uint8_t map_used;                   // 0 - this MR register not used/assigned
+    uint8_t map_PWM_INT;                // 0 - available for interrupts, 1 - in use by PWM
+    pin_t map_PWM_PIN;                  // pin for this PwM1 controlled pin / port
+    volatile uint32_t* MR_register;     // address of the MR register for this PWM1 channel
+    uint32_t PCR_bit;                   // PCR register bit to enable PWM1 control of this pin
+    uint32_t PINSEL3_bits;              // PINSEL3 register bits to set pin mode to PWM1 control
+} MR_map;
+
+MR_map map_MR[NUM_PWMS];
+
+void LPC1768_PWM_update_map_MR(void) {
+  map_MR[0] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_4_PWM_channel)  ? 1 : 0),  4, &LPC_PWM1->MR1, 0, 0};
+  map_MR[1] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_11_PWM_channel) ? 1 : 0), 11, &LPC_PWM1->MR2, 0, 0};
+  map_MR[2] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_6_PWM_channel)  ? 1 : 0),  6, &LPC_PWM1->MR3, 0, 0};
+  map_MR[3] = {0, 0,  0, &LPC_PWM1->MR4, 0, 0};
+  map_MR[4] = {0, 0,  0, &LPC_PWM1->MR5, 0, 0};
+  map_MR[5] = {0, 0,  0, &LPC_PWM1->MR6, 0, 0};
+}
+
+
+uint32_t LPC1768_PWM_interrupt_mask = 1;
+
+void LPC1768_PWM_update(void) {
+  for (uint8_t i = NUM_PWMS; --i;) {  // (bubble) sort table by microseconds
+    bool didSwap = false;
+    PWM_map temp;
+    for (uint16_t j = 0; j < i; ++j) {
+      if (work_table[j].microseconds > work_table[j + 1].microseconds) {
+        temp = work_table[j + 1];
+        work_table[j + 1] = work_table[j];
+        work_table[j] = temp;
+        didSwap = true;
+      }
+    }
+    if (!didSwap) break;
+  }
+
+  LPC1768_PWM_interrupt_mask = 0;                          // set match registers to new values, build IRQ mask
+  for (uint8_t i = 0; i < NUM_PWMS; i++) {
+    if (work_table[i].active_flag == true) {
+      work_table[i].sequence = i + 1;
+
+      // first see if there is a PWM1 controlled pin for this entry
+      bool found = false;
+      for (uint8_t j = 0; (j < NUM_PWMS) && !found; j++) {
+        if ( (map_MR[j].map_PWM_PIN == work_table[i].pin) && map_MR[j].map_PWM_INT ) {
+          *map_MR[j].MR_register = work_table[i].microseconds;  // found one of the PWM pins
+          work_table[i].PWM_mask = 0;
+          work_table[i].PCR_bit = map_MR[j].PCR_bit;            // PCR register bit to enable PWM1 control of this pin
+          work_table[i].PINSEL3_bits = map_MR[j].PINSEL3_bits;  // PINSEL3 register bits to set pin mode to PWM1 control} MR_map;
+          map_MR[j].map_used = 2;
+          work_table[i].assigned_MR = j +1;                    // only used to help in debugging
+          found = true;
+        }
+      }
+
+      // didn't find a PWM1 pin so get an interrupt
+      for (uint8_t k = 0; (k < NUM_PWMS) && !found; k++) {
+        if ( !(map_MR[k].map_PWM_INT || map_MR[k].map_used)) {
+          *map_MR[k].MR_register = work_table[i].microseconds;  // found one for an interrupt pin
+          map_MR[k].map_used = 1;
+          LPC1768_PWM_interrupt_mask |= _BV(3 * (k + 1));  // set bit in the MCR to enable this MR to generate an interrupt
+          work_table[i].PWM_mask = _BV(IR_BIT(k + 1));  // bit in the IR that will go active when this MR generates an interrupt
+          work_table[i].assigned_MR = k +1;                // only used to help in debugging
+          found = true;
+        }
+      }
+    }
+    else
+      work_table[i].sequence = 0;
+  }
+  LPC1768_PWM_interrupt_mask |= (uint32_t) _BV(0);  // add in MR0 interrupt
+
+   // swap tables
+
+  PWM_MR0_wait = true;
+  while (PWM_MR0_wait) delay(5);  //wait until MR0 interrupt has happend so don't delay it.
+
+  NVIC_DisableIRQ(PWM1_IRQn);
+  LPC_PWM1->LER = 0x07E;  // Set the latch Enable Bits to load the new Match Values for MR1 - MR6
+  PWM_map *pointer_swap = active_table;
+  active_table = work_table;
+  work_table = pointer_swap;
+  PWM_table_swap = true;  // tell the ISR that the tables have been swapped
+  NVIC_EnableIRQ(PWM1_IRQn);  // re-enable PWM interrupts
+}
+
+
+bool LPC1768_PWM_write(pin_t pin, uint32_t value) {
+  while (PWM_table_swap) delay(5);  // don't do anything until the previous change has been implemented by the ISR
+  COPY_ACTIVE_TABLE;  // copy active table into work table
+  uint8_t slot = 0xFF;
+  for (uint8_t i = 0; i < NUM_PWMS; i++)         // find slot
+    if (work_table[i].pin == pin) slot = i;
+  if (slot == 0xFF) return false;    // return error if pin not found
+
+  LPC1768_PWM_update_map_MR();
+
+  switch(pin) {
+    case P1_20:                        // Servo 0, PWM1 channel 2 (Pin 11  P1.20 PWM1.2)
+      map_MR[pin_11_PWM_channel - 1].PCR_bit = _BV(8 + pin_11_PWM_channel);  // enable PWM1 module control of this pin
+      map_MR[pin_11_PWM_channel - 1].map_PWM_INT = 1;               // 0 - available for interrupts, 1 - in use by PWM
+      map_MR[pin_11_PWM_channel - 1].PINSEL3_bits = 0x2 <<  8;      // ISR must do this AFTER setting PCR
+      break;
+    case P1_21:                        // Servo 1, PWM1 channel 3 (Pin 6  P1.21 PWM1.3)
+      map_MR[pin_6_PWM_channel - 1].PCR_bit = _BV(8 + pin_6_PWM_channel);                  // enable PWM1 module control of this pin
+      map_MR[pin_6_PWM_channel - 1].map_PWM_INT = 1;                // 0 - available for interrupts, 1 - in use by PWM
+      map_MR[pin_6_PWM_channel - 1].PINSEL3_bits = 0x2 << 10;       // ISR must do this AFTER setting PCR
+      break;
+    case P1_18:                        // Servo 3, PWM1 channel 1 (Pin 4  P1.18 PWM1.1)
+      map_MR[pin_4_PWM_channel - 1].PCR_bit = _BV(8 + pin_4_PWM_channel);                  // enable PWM1 module control of this pin
+      map_MR[pin_4_PWM_channel - 1].map_PWM_INT = 1;                // 0 - available for interrupts, 1 - in use by PWM
+      map_MR[pin_4_PWM_channel - 1].PINSEL3_bits =  0x2 <<  4;       // ISR must do this AFTER setting PCR
+      break;
+    default:                                                        // ISR pins
+      pinMode(pin, OUTPUT);  // set pin to output but don't write anything in case it's already in use
+      break;
+  }
+
+  work_table[slot].microseconds = MAX(MIN(value, work_table[slot].max), work_table[slot].min);
+  work_table[slot].active_flag = true;
+
+  LPC1768_PWM_update();
+
+  return 1;
+}
+
+
+bool LPC1768_PWM_detach_pin(pin_t pin) {
+  while (PWM_table_swap) delay(5);  // don't do anything until the previous change has been implemented by the ISR
+  COPY_ACTIVE_TABLE;  // copy active table into work table
+  uint8_t slot = 0xFF;
+  for (uint8_t i = 0; i < NUM_PWMS; i++)         // find slot
+    if (work_table[i].pin == pin) slot = i;
+  if (slot == 0xFF) return false;    // return error if pin not found
+
+  LPC1768_PWM_update_map_MR();
+
+  // OK to make these changes before the MR0 interrupt
+  switch(pin) {
+    case P1_20:                        // Servo 0, PWM1 channel 2  (Pin 11  P1.20 PWM1.2)
+      LPC_PWM1->PCR &= ~(_BV(8 + pin_11_PWM_channel));                 // disable PWM1 module control of this pin
+      map_MR[pin_11_PWM_channel - 1].PCR_bit = 0;
+      LPC_PINCON->PINSEL3 &= ~(0x3 <<  8);    // return pin to general purpose I/O
+      map_MR[pin_11_PWM_channel - 1].PINSEL3_bits = 0;
+      map_MR[pin_11_PWM_channel - 1].map_PWM_INT = 0;               // 0 - available for interrupts, 1 - in use by PWM
+      break;
+    case P1_21:                        // Servo 1, PWM1 channel 3  (Pin 6  P1.21 PWM1.3)
+      LPC_PWM1->PCR &= ~(_BV(8 + pin_6_PWM_channel));                  // disable PWM1 module control of this pin
+      map_MR[pin_6_PWM_channel - 1].PCR_bit = 0;
+      LPC_PINCON->PINSEL3 &= ~(0x3 << 10);  // return pin to general purpose I/O
+      map_MR[pin_6_PWM_channel - 1].PINSEL3_bits = 0;
+      map_MR[pin_6_PWM_channel - 1].map_PWM_INT = 0;                // 0 - available for interrupts, 1 - in use by PWM
+      break;
+    case P1_18:                        // Servo 3, PWM1 channel 1 (Pin 4  P1.18 PWM1.1)
+      LPC_PWM1->PCR &= ~(_BV(8 + pin_4_PWM_channel));                  // disable PWM1 module control of this pin
+      map_MR[pin_4_PWM_channel - 1].PCR_bit =  0;
+      LPC_PINCON->PINSEL3 &= ~(0x3 <<  4);  // return pin to general purpose I/O
+      map_MR[pin_4_PWM_channel - 1].PINSEL3_bits =  0;
+      map_MR[pin_4_PWM_channel - 1].map_PWM_INT = 0;                // 0 - available for interrupts, 1 - in use by PWM
+      break;
+  }
+
+  pinMode(pin, INPUT);
+
+  work_table[slot] = PWM_MAP_INIT_ROW;
+
+  LPC1768_PWM_update();
+
+  return 1;
+}
+
+
+bool useable_hardware_PWM(pin_t pin) {
+  COPY_ACTIVE_TABLE;  // copy active table into work table
+  for (uint8_t i = 0; i < NUM_PWMS; i++)         // see if it's already setup
+    if (work_table[i].pin == pin && work_table[i].sequence) return true;
+  for (uint8_t i = 0; i < NUM_PWMS; i++)         // see if there is an empty slot
+    if (!work_table[i].sequence) return true;
+  return false;    // only get here if neither the above are true
+}
+
+////////////////////////////////////////////////////////////////////////////////
+
+#define HAL_PWM_LPC1768_ISR  extern "C" void PWM1_IRQHandler(void)
+
+
+// Both loops could be terminated when the last active channel is found but that would
+// result in variations ISR run time which results in variations in pulse width
+
+/**
+ * Changes to PINSEL3, PCR and MCR are only done during the MR0 interrupt otherwise
+ * the wrong pin may be toggled or even have the system hang.
+ */
+
+
+HAL_PWM_LPC1768_ISR {
+  if (PWM_table_swap) ISR_table = work_table;   // use old table if a swap was just done
+  else ISR_table = active_table;
+
+  if (LPC_PWM1->IR & 0x1) {                                      // MR0 interrupt
+    ISR_table = active_table;                    // MR0 means new values could have been loaded so set everything
+    if (PWM_table_swap) LPC_PWM1->MCR = LPC1768_PWM_interrupt_mask; // enable new PWM individual channel interrupts
+
+    for (uint8_t i = 0; i < NUM_PWMS; i++) {
+      if(ISR_table[i].active_flag && !((ISR_table[i].pin == P1_20) ||
+                                       (ISR_table[i].pin == P1_21) ||
+                                       (ISR_table[i].pin == P1_18)))
+        *ISR_table[i].set_register = ISR_table[i].write_mask;       // set pins for all enabled interrupt channels active
+      if (PWM_table_swap && ISR_table[i].PCR_bit) {
+        LPC_PWM1->PCR |= ISR_table[i].PCR_bit;              // enable PWM1 module control of this pin
+        LPC_PINCON->PINSEL3 |= ISR_table[i].PINSEL3_bits;   // set pin mode to PWM1 control - must be done after PCR
+      }
+    }
+    PWM_table_swap = false;
+    PWM_MR0_wait = false;
+    LPC_PWM1->IR = 0x01;                                             // clear the MR0 interrupt flag bit
+  }
+  else {
+    for (uint8_t i = 0; i < NUM_PWMS ; i++)
+      if (ISR_table[i].active_flag && (LPC_PWM1->IR & ISR_table[i].PWM_mask) ){
+        LPC_PWM1->IR = ISR_table[i].PWM_mask;       // clear the interrupt flag bits for expected interrupts
+        *ISR_table[i].clr_register = ISR_table[i].write_mask;   // set channel to inactive
+      }
+  }
+
+  LPC_PWM1->IR = 0x70F;  // guarantees all interrupt flags are cleared which, if there is an unexpected
+                           // PWM interrupt, will keep the ISR from hanging which will crash the controller
+
+return;
+}
+#endif
+
+/////////////////////////////////////////////////////////////////
+/////////////////  HARDWARE FIRMWARE INTERACTION ////////////////
+/////////////////////////////////////////////////////////////////
+
+/**
+ *  Almost all changes to the hardware registers must be coordinated with the Match Register 0 (MR0)
+ *  interrupt.  The only exception is detaching pins.  It doesn't matter when they go
+ *  tristate.
+ *
+ *  The LPC1768_PWM_init routine kicks off the MR0 interrupt.  This interrupt is never disabled or
+ *  delayed.
+ *
+ *  The PWM_table_swap flag is set when the firmware has swapped in an updated table.  It is
+ *  cleared by the ISR during the MR0 interrupt as it completes the swap and accompanying updates.
+ *  It serves two purposes:
+ *    1) Tells the ISR that the tables have been swapped
+ *    2) Keeps the firmware from starting a new update until the previous one has been completed.
+ *
+ *  The PWM_MR0_wait flag is set when the firmware is ready to swap in an updated table and cleared by
+ *  the ISR during the MR0 interrupt.  It is used to avoid delaying the MR0 interrupt when swapping in
+ *  an updated table.  This avoids glitches in pulse width and/or repetition rate.
+ *
+ *  The sequence of events during a write to a PWM channel is:
+ *    1) Waits until PWM_table_swap flag is false before starting
+ *    2) Copies the active table into the work table
+ *    3) Updates the work table
+ *         NOTES - MR1-MR6 are updated at this time.  The updates aren't put into use until the first
+ *                 MR0 after the LER register has been written.  The LER register is written during the
+ *                 table swap process.
+ *               - The MCR mask is created at this time.  It is not used until the ISR writes the MCR
+ *                 during the MR0 interrupt in the table swap process.
+ *    4) Sets the PWM_MR0_wait flag
+ *    5) ISR clears the PWM_MR0_wait flag during the next MR0 interrupt
+ *    6) Once the PWM_MR0_wait flag is cleared then the firmware:
+ *          disables the ISR interrupt
+ *          swaps the pointers to the tables
+ *          writes to the LER register
+ *          sets the PWM_table_swap flag active
+ *          re-enables the ISR
+ *     7) On the next interrupt the ISR changes its pointer to the work table which is now the old,
+ *        unmodified, active table.
+ *     8) On the next MR0 interrupt the ISR:
+ *          switches over to the active table
+ *          clears the PWM_table_swap and PWM_MR0_wait flags
+ *          updates the MCR register with the possibly new interrupt sources/assignments
+ *          writes to the PCR register to enable the direct control of the Servo 0, 1 & 3 pins by the PWM1 module
+ *          sets the PINSEL3 register to function/mode 0x2 for the Servo 0, 1 & 3 pins
+ *             NOTE - PCR must be set before PINSEL
+ *          sets the pins controlled by the ISR to their active states
+ */
+
diff --git a/Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.h b/Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.h
index 3ab47f888b..6dec0b7e96 100644
--- a/Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.h
+++ b/Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.h
@@ -60,88 +60,7 @@
  * See the end of this file for details on the hardware/firmware interaction
  */
 
-
-#ifdef TARGET_LPC1768
-#include <lpc17xx_pinsel.h>
-
-#define NUM_PWMS 6
-
-typedef struct {            // holds all data needed to control/init one of the PWM channels
-    uint8_t  sequence;       // 0: available slot, 1 - 6: PWM channel assigned to that slot
-    uint8_t  logical_pin;
-    uint16_t PWM_mask;       // MASK TO CHECK/WRITE THE IR REGISTER
-    volatile uint32_t* set_register;
-    volatile uint32_t* clr_register;
-    uint32_t write_mask;     // USED BY SET/CLEAR COMMANDS
-    uint32_t microseconds;   // value written to MR register
-    uint32_t min;            // lower value limit checked by WRITE routine before writing to the MR register
-    uint32_t max;            // upper value limit checked by WRITE routine before writing to the MR register
-    bool     PWM_flag;       // 0 - USED BY sERVO, 1 - USED BY ANALOGWRITE
-    uint8_t  servo_index;    // 0 - MAX_SERVO -1 : servo index,  0xFF : PWM channel
-    bool     active_flag;    // THIS TABLE ENTRY IS ACTIVELY TOGGLING A PIN
-    uint8_t  assigned_MR;    // Which MR (1-6) is used by this logical channel
-    uint32_t PCR_bit;        // PCR register bit to enable PWM1 control of this pin
-    uint32_t PINSEL3_bits;   // PINSEL3 register bits to set pin mode to PWM1 control
-
-} PWM_map;
-
-
-#define MICRO_MAX 0xffffffff
-
-#define PWM_MAP_INIT_ROW {0, 0xff, 0, 0, 0, 0, MICRO_MAX, 0, 0, 0, 0, 0, 0, 0, 0}
-#define PWM_MAP_INIT {PWM_MAP_INIT_ROW,\
-                      PWM_MAP_INIT_ROW,\
-                      PWM_MAP_INIT_ROW,\
-                      PWM_MAP_INIT_ROW,\
-                      PWM_MAP_INIT_ROW,\
-                      PWM_MAP_INIT_ROW,\
-                     };
-
-PWM_map PWM1_map_A[NUM_PWMS] = PWM_MAP_INIT;
-PWM_map PWM1_map_B[NUM_PWMS] = PWM_MAP_INIT;
-
-PWM_map *active_table = PWM1_map_A;
-PWM_map *work_table = PWM1_map_B;
-PWM_map *ISR_table;
-
-
-#define IR_BIT(p) (p >= 0 && p <= 3 ? p : p + 4 )
-#define COPY_ACTIVE_TABLE    for (uint8_t i = 0; i < 6 ; i++) work_table[i] = active_table[i]
-#define PIN_IS_INVERTED(p) 0  // place holder in case inverting PWM output is offered
-
-
-/**
- *  Prescale register and MR0 register values
- *
- *               100MHz PCLK          50MHz PCLK          25MHz PCLK         12.5MHz PCLK
- *             -----------------   -----------------   -----------------   -----------------
- *  desired    prescale  MR0       prescale  MR0       prescale  MR0       prescale  MR0        resolution
- *  prescale   register  register  register  register  register  register  register  register   in degrees
- *  freq       value     value     value     value     value     value     value     value
- *
- *      8        11.5    159,999      5.25   159,999       2.13  159,999    0.5625   159,999    0.023
- *      4        24       79,999     11.5     79,999       5.25   79,999    2.125     79,999    0.045
- *      2        49       39,999     24       39,999      11.5    39,999    5.25      39,999    0.090
- *      1        99       19,999     49       19,999      24      19,999   11.5       19,999    0.180
- *    0.5       199        9,999     99        9,999      49       9,999   24          9,999    0.360
- *   0.25       399        4,999    199        4,999      99       4,999   49          4,999    0.720
- *  0.125       799        2,499    399        2,499     199       2,499   99          2,499    1.440
- *
- *  The desired prescale frequency comes from an input in the range of 544 - 2400 microseconds and the
- *  desire to just shift the input left or right as needed.
- *
- *  A resolution of 0.2 degrees seems reasonable so a prescale frequency output of 1MHz is being used.
- *  It also means we don't need to scale the input.
- *
- *  The PCLK is set to 25MHz because that's the slowest one that gives whole numbers for prescale and
- *  MR0 registers.
- *
- *  Final settings:
- *   PCLKSEL0: 0x0
- *   PWM1PR:   0x018 (24)
- *   PWM1MR0:  0x04E1F (19,999)
- *
- */
+ #include "fastio.h"
 
 #define LPC_PWM1_MR0 19999  // base repetition rate minus one count - 20mS
 #define LPC_PWM1_PR 24      // prescaler value - prescaler divide by 24 + 1  -  1 MHz output
@@ -149,365 +68,10 @@ PWM_map *ISR_table;
                                  // 0: 25MHz, 1: 100MHz, 2: 50MHz, 3: 12.5MHZ to PWM1 prescaler
 #define MR0_MARGIN 200       // if channel value too close to MR0 the system locks up
 
-
-void LPC1768_PWM_init(void) {
-  #define SBIT_CNTEN     0  // PWM1 counter & pre-scaler enable/disable
-  #define SBIT_CNTRST    1  // reset counters to known state
-  #define SBIT_PWMEN     3  // 1 - PWM, 0 - timer
-  #define SBIT_PWMMR0R   1
-  #define PCPWM1         6
-  #define PCLK_PWM1      12
-
-  LPC_SC->PCONP |= (1 << PCPWM1);      // enable PWM1 controller (enabled on power up)
-  LPC_SC->PCLKSEL0 &= ~(0x3 << PCLK_PWM1);
-  LPC_SC->PCLKSEL0 |= (LPC_PWM1_PCLKSEL0 << PCLK_PWM1);
-  LPC_PWM1->MR0 = LPC_PWM1_MR0;                // TC resets every 19,999 + 1 cycles - sets PWM cycle(Ton+Toff) to 20 mS
-                                        // MR0 must be set before TCR enables the PWM
-  LPC_PWM1->TCR = _BV(SBIT_CNTEN) | _BV(SBIT_CNTRST)| _BV(SBIT_PWMEN);;  // enable counters, reset counters, set mode to PWM
-  LPC_PWM1->TCR &= ~(_BV(SBIT_CNTRST));  // take counters out of reset
-  LPC_PWM1->PR  =  LPC_PWM1_PR;
-  LPC_PWM1->MCR = (_BV(SBIT_PWMMR0R) | _BV(0));     // Reset TC if it matches MR0, disable all interrupts except for MR0
-  LPC_PWM1->CTCR = 0;                   // disable counter mode (enable PWM mode)
-
-  LPC_PWM1->LER = 0x07F;  // Set the latch Enable Bits to load the new Match Values for MR0 - MR6
-  // Set all PWMs to single edge
-  LPC_PWM1->PCR = 0;    // single edge mode for all channels, PWM1 control of outputs off
-
-  NVIC_EnableIRQ(PWM1_IRQn);     // Enable interrupt handler
-  //      NVIC_SetPriority(PWM1_IRQn, NVIC_EncodePriority(0, 10, 0));  // normal priority for PWM module
-  NVIC_SetPriority(PWM1_IRQn, NVIC_EncodePriority(0, 0, 0));  // minimizes jitter due to higher priority ISRs
-}
-
-
-bool PWM_table_swap = false;  // flag to tell the ISR that the tables have been swapped
-bool PWM_MR0_wait = false;  // flag to ensure don't delay MR0 interrupt
-
-
-bool LPC1768_PWM_attach_pin(uint8_t pin, uint32_t min = 1, uint32_t max = (LPC_PWM1_MR0 - MR0_MARGIN), uint8_t servo_index = 0xff) {
-  while (PWM_table_swap) delay(5);  // don't do anything until the previous change has been implemented by the ISR
-  COPY_ACTIVE_TABLE;  // copy active table into work table
-  uint8_t slot = 0;
-  for (uint8_t i = 0; i < NUM_PWMS ; i++)         // see if already in table
-    if (work_table[i].logical_pin == pin) return 1;
-
-  for (uint8_t i = 1; (i < NUM_PWMS + 1) && !slot; i++)         // find empty slot
-    if ( !(work_table[i - 1].set_register)) slot = i;  // any item that can't be zero when active or just attached is OK
-  if (!slot) return 0;
-  slot--;  // turn it into array index
-
-  work_table[slot].logical_pin = pin;  // init slot
-  work_table[slot].PWM_mask = 0;  // real value set by PWM_write
-  work_table[slot].set_register = PIN_IS_INVERTED(pin) ? &LPC_GPIO(pin_map[pin].port)->FIOCLR : &LPC_GPIO(pin_map[pin].port)->FIOSET;
-  work_table[slot].clr_register = PIN_IS_INVERTED(pin) ? &LPC_GPIO(pin_map[pin].port)->FIOSET : &LPC_GPIO(pin_map[pin].port)->FIOCLR;
-  work_table[slot].write_mask = LPC_PIN(pin_map[pin].pin);
-  work_table[slot].microseconds = MICRO_MAX;
-  work_table[slot].min = min;
-  work_table[slot].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
-  work_table[slot].servo_index = servo_index;
-  work_table[slot].active_flag = false;
-
-  //swap tables
-  PWM_MR0_wait = true;
-  while (PWM_MR0_wait) delay(5);  //wait until MR0 interrupt has happend so don't delay it.
-
-  NVIC_DisableIRQ(PWM1_IRQn);
-  PWM_map *pointer_swap = active_table;
-  active_table = work_table;
-  work_table = pointer_swap;
-  PWM_table_swap = true;  // tell the ISR that the tables have been swapped
-  NVIC_EnableIRQ(PWM1_IRQn);  // re-enable PWM interrupts
-
-  return 1;
-}
-
-#define pin_11_PWM_channel 2
-#define pin_6_PWM_channel  3
-#define pin_4_PWM_channel  1
-
-// used to keep track of which Match Registers have been used and if they will be used by the
-// PWM1 module to directly control the pin or will be used to generate an interrupt
-typedef struct {                        // status of PWM1 channel
-    uint8_t map_used;                   // 0 - this MR register not used/assigned
-    uint8_t map_PWM_INT;                // 0 - available for interrupts, 1 - in use by PWM
-    uint8_t map_PWM_PIN;                // logical pin number for this PwM1 controlled pin / port
-    volatile uint32_t* MR_register;     // address of the MR register for this PWM1 channel
-    uint32_t PCR_bit;                   // PCR register bit to enable PWM1 control of this pin
-    uint32_t PINSEL3_bits;              // PINSEL3 register bits to set pin mode to PWM1 control
-} MR_map;
-
-MR_map map_MR[NUM_PWMS];
-
-void LPC1768_PWM_update_map_MR(void) {
-  map_MR[0] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_4_PWM_channel)  ? 1 : 0),  4, &LPC_PWM1->MR1, 0, 0};
-  map_MR[1] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_11_PWM_channel) ? 1 : 0), 11, &LPC_PWM1->MR2, 0, 0};
-  map_MR[2] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_6_PWM_channel)  ? 1 : 0),  6, &LPC_PWM1->MR3, 0, 0};
-  map_MR[3] = {0, 0,  0, &LPC_PWM1->MR4, 0, 0};
-  map_MR[4] = {0, 0,  0, &LPC_PWM1->MR5, 0, 0};
-  map_MR[5] = {0, 0,  0, &LPC_PWM1->MR6, 0, 0};
-}
-
-
-uint32_t LPC1768_PWM_interrupt_mask = 1;
-
-void LPC1768_PWM_update(void) {
-  for (uint8_t i = NUM_PWMS; --i;) {  // (bubble) sort table by microseconds
-    bool didSwap = false;
-    PWM_map temp;
-    for (uint16_t j = 0; j < i; ++j) {
-      if (work_table[j].microseconds > work_table[j + 1].microseconds) {
-        temp = work_table[j + 1];
-        work_table[j + 1] = work_table[j];
-        work_table[j] = temp;
-        didSwap = true;
-      }
-    }
-    if (!didSwap) break;
-  }
-
-  LPC1768_PWM_interrupt_mask = 0;                          // set match registers to new values, build IRQ mask
-  for (uint8_t i = 0; i < NUM_PWMS; i++) {
-    if (work_table[i].active_flag == true) {
-      work_table[i].sequence = i + 1;
-
-      // first see if there is a PWM1 controlled pin for this entry
-      bool found = false;
-      for (uint8_t j = 0; (j < NUM_PWMS) && !found; j++) {
-        if ( (map_MR[j].map_PWM_PIN == work_table[i].logical_pin) && map_MR[j].map_PWM_INT ) {
-          *map_MR[j].MR_register = work_table[i].microseconds;  // found one of the PWM pins
-          work_table[i].PWM_mask = 0;
-          work_table[i].PCR_bit = map_MR[j].PCR_bit;            // PCR register bit to enable PWM1 control of this pin
-          work_table[i].PINSEL3_bits = map_MR[j].PINSEL3_bits;  // PINSEL3 register bits to set pin mode to PWM1 control} MR_map;
-          map_MR[j].map_used = 2;
-          work_table[i].assigned_MR = j +1;                    // only used to help in debugging
-          found = true;
-        }
-      }
-
-      // didn't find a PWM1 pin so get an interrupt
-      for (uint8_t k = 0; (k < NUM_PWMS) && !found; k++) {
-        if ( !(map_MR[k].map_PWM_INT || map_MR[k].map_used)) {
-          *map_MR[k].MR_register = work_table[i].microseconds;  // found one for an interrupt pin
-          map_MR[k].map_used = 1;
-          LPC1768_PWM_interrupt_mask |= _BV(3 * (k + 1));  // set bit in the MCR to enable this MR to generate an interrupt
-          work_table[i].PWM_mask = _BV(IR_BIT(k + 1));  // bit in the IR that will go active when this MR generates an interrupt
-          work_table[i].assigned_MR = k +1;                // only used to help in debugging
-          found = true;
-        }
-      }
-    }
-    else
-      work_table[i].sequence = 0;
-  }
-  LPC1768_PWM_interrupt_mask |= (uint32_t) _BV(0);  // add in MR0 interrupt
-
-   // swap tables
-
-  PWM_MR0_wait = true;
-  while (PWM_MR0_wait) delay(5);  //wait until MR0 interrupt has happend so don't delay it.
-
-  NVIC_DisableIRQ(PWM1_IRQn);
-  LPC_PWM1->LER = 0x07E;  // Set the latch Enable Bits to load the new Match Values for MR1 - MR6
-  PWM_map *pointer_swap = active_table;
-  active_table = work_table;
-  work_table = pointer_swap;
-  PWM_table_swap = true;  // tell the ISR that the tables have been swapped
-  NVIC_EnableIRQ(PWM1_IRQn);  // re-enable PWM interrupts
-}
-
-
-bool LPC1768_PWM_write(uint8_t pin, uint32_t value) {
-  while (PWM_table_swap) delay(5);  // don't do anything until the previous change has been implemented by the ISR
-  COPY_ACTIVE_TABLE;  // copy active table into work table
-  uint8_t slot = 0xFF;
-  for (uint8_t i = 0; i < NUM_PWMS; i++)         // find slot
-    if (work_table[i].logical_pin == pin) slot = i;
-  if (slot == 0xFF) return false;    // return error if pin not found
-
-  LPC1768_PWM_update_map_MR();
-
-  switch(pin) {
-    case 11:                        // Servo 0, PWM1 channel 2 (Pin 11  P1.20 PWM1.2)
-      map_MR[pin_11_PWM_channel - 1].PCR_bit = _BV(8 + pin_11_PWM_channel);  // enable PWM1 module control of this pin
-      map_MR[pin_11_PWM_channel - 1].map_PWM_INT = 1;               // 0 - available for interrupts, 1 - in use by PWM
-      map_MR[pin_11_PWM_channel - 1].PINSEL3_bits = 0x2 <<  8;      // ISR must do this AFTER setting PCR
-      break;
-    case  6:                        // Servo 1, PWM1 channel 3 (Pin 6  P1.21 PWM1.3)
-      map_MR[pin_6_PWM_channel - 1].PCR_bit = _BV(8 + pin_6_PWM_channel);                  // enable PWM1 module control of this pin
-      map_MR[pin_6_PWM_channel - 1].map_PWM_INT = 1;                // 0 - available for interrupts, 1 - in use by PWM
-      map_MR[pin_6_PWM_channel - 1].PINSEL3_bits = 0x2 << 10;       // ISR must do this AFTER setting PCR
-      break;
-    case  4:                        // Servo 3, PWM1 channel 1 (Pin 4  P1.18 PWM1.1)
-      map_MR[pin_4_PWM_channel - 1].PCR_bit = _BV(8 + pin_4_PWM_channel);                  // enable PWM1 module control of this pin
-      map_MR[pin_4_PWM_channel - 1].map_PWM_INT = 1;                // 0 - available for interrupts, 1 - in use by PWM
-      map_MR[pin_4_PWM_channel - 1].PINSEL3_bits =  0x2 <<  4;       // ISR must do this AFTER setting PCR
-      break;
-    default:                                                        // ISR pins
-      pinMode(pin, OUTPUT);  // set pin to output but don't write anything in case it's already in use
-      break;
-  }
-
-  work_table[slot].microseconds = MAX(MIN(value, work_table[slot].max), work_table[slot].min);
-  work_table[slot].active_flag = true;
-
-  LPC1768_PWM_update();
-
-  return 1;
-}
-
-
-bool LPC1768_PWM_detach_pin(uint8_t pin) {
-  while (PWM_table_swap) delay(5);  // don't do anything until the previous change has been implemented by the ISR
-  COPY_ACTIVE_TABLE;  // copy active table into work table
-  uint8_t slot = 0xFF;
-  for (uint8_t i = 0; i < NUM_PWMS; i++)         // find slot
-    if (work_table[i].logical_pin == pin) slot = i;
-  if (slot == 0xFF) return false;    // return error if pin not found
-
-  LPC1768_PWM_update_map_MR();
-
-  // OK to make these changes before the MR0 interrupt
-  switch(pin) {
-    case 11:                        // Servo 0, PWM1 channel 2  (Pin 11  P1.20 PWM1.2)
-      LPC_PWM1->PCR &= ~(_BV(8 + pin_11_PWM_channel));                 // disable PWM1 module control of this pin
-      map_MR[pin_11_PWM_channel - 1].PCR_bit = 0;
-      LPC_PINCON->PINSEL3 &= ~(0x3 <<  8);    // return pin to general purpose I/O
-      map_MR[pin_11_PWM_channel - 1].PINSEL3_bits = 0;
-      map_MR[pin_11_PWM_channel - 1].map_PWM_INT = 0;               // 0 - available for interrupts, 1 - in use by PWM
-      break;
-    case  6:                        // Servo 1, PWM1 channel 3  (Pin 6  P1.21 PWM1.3)
-      LPC_PWM1->PCR &= ~(_BV(8 + pin_6_PWM_channel));                  // disable PWM1 module control of this pin
-      map_MR[pin_6_PWM_channel - 1].PCR_bit = 0;
-      LPC_PINCON->PINSEL3 &= ~(0x3 << 10);  // return pin to general purpose I/O
-      map_MR[pin_6_PWM_channel - 1].PINSEL3_bits = 0;
-      map_MR[pin_6_PWM_channel - 1].map_PWM_INT = 0;                // 0 - available for interrupts, 1 - in use by PWM
-      break;
-    case  4:                        // Servo 3, PWM1 channel 1 (Pin 4  P1.18 PWM1.1)
-      LPC_PWM1->PCR &= ~(_BV(8 + pin_4_PWM_channel));                  // disable PWM1 module control of this pin
-      map_MR[pin_4_PWM_channel - 1].PCR_bit =  0;
-      LPC_PINCON->PINSEL3 &= ~(0x3 <<  4);  // return pin to general purpose I/O
-      map_MR[pin_4_PWM_channel - 1].PINSEL3_bits =  0;
-      map_MR[pin_4_PWM_channel - 1].map_PWM_INT = 0;                // 0 - available for interrupts, 1 - in use by PWM
-      break;
-  }
-
-  pinMode(pin, INPUT);
-
-  work_table[slot] = PWM_MAP_INIT_ROW;
-
-  LPC1768_PWM_update();
-
-  return 1;
-}
-
-
-bool useable_hardware_PWM(uint8_t pin) {
-  COPY_ACTIVE_TABLE;  // copy active table into work table
-  for (uint8_t i = 0; i < NUM_PWMS; i++)         // see if it's already setup
-    if (work_table[i].logical_pin == pin && work_table[i].sequence) return true;
-  for (uint8_t i = 0; i < NUM_PWMS; i++)         // see if there is an empty slot
-    if (!work_table[i].sequence) return true;
-  return false;    // only get here if neither the above are true
-}
-
-////////////////////////////////////////////////////////////////////////////////
-
-#define HAL_PWM_LPC1768_ISR  extern "C" void PWM1_IRQHandler(void)
-
-
-// Both loops could be terminated when the last active channel is found but that would
-// result in variations ISR run time which results in variations in pulse width
-
-/**
- * Changes to PINSEL3, PCR and MCR are only done during the MR0 interrupt otherwise
- * the wrong pin may be toggled or even have the system hang.
- */
-
-
-HAL_PWM_LPC1768_ISR {
-  if (PWM_table_swap) ISR_table = work_table;   // use old table if a swap was just done
-  else ISR_table = active_table;
-
-  if (LPC_PWM1->IR & 0x1) {                                      // MR0 interrupt
-    ISR_table = active_table;                    // MR0 means new values could have been loaded so set everything
-    if (PWM_table_swap) LPC_PWM1->MCR = LPC1768_PWM_interrupt_mask; // enable new PWM individual channel interrupts
-
-    for (uint8_t i = 0; i < NUM_PWMS; i++) {
-      if(ISR_table[i].active_flag && !((ISR_table[i].logical_pin ==  11) ||
-                                       (ISR_table[i].logical_pin ==  4) ||
-                                       (ISR_table[i].logical_pin ==  6)))
-        *ISR_table[i].set_register = ISR_table[i].write_mask;       // set pins for all enabled interrupt channels active
-      if (PWM_table_swap && ISR_table[i].PCR_bit) {
-        LPC_PWM1->PCR |= ISR_table[i].PCR_bit;              // enable PWM1 module control of this pin
-        LPC_PINCON->PINSEL3 |= ISR_table[i].PINSEL3_bits;   // set pin mode to PWM1 control - must be done after PCR
-      }
-    }
-    PWM_table_swap = false;
-    PWM_MR0_wait = false;
-    LPC_PWM1->IR = 0x01;                                             // clear the MR0 interrupt flag bit
-  }
-  else {
-    for (uint8_t i = 0; i < NUM_PWMS ; i++)
-      if (ISR_table[i].active_flag && (LPC_PWM1->IR & ISR_table[i].PWM_mask) ){
-        LPC_PWM1->IR = ISR_table[i].PWM_mask;       // clear the interrupt flag bits for expected interrupts
-        *ISR_table[i].clr_register = ISR_table[i].write_mask;   // set channel to inactive
-      }
-  }
-
-  LPC_PWM1->IR = 0x70F;  // guarantees all interrupt flags are cleared which, if there is an unexpected
-                           // PWM interrupt, will keep the ISR from hanging which will crash the controller
-
-return;
-}
-#endif
-
-/////////////////////////////////////////////////////////////////
-/////////////////  HARDWARE FIRMWARE INTERACTION ////////////////
-/////////////////////////////////////////////////////////////////
-
-/**
- *  Almost all changes to the hardware registers must be coordinated with the Match Register 0 (MR0)
- *  interrupt.  The only exception is detaching pins.  It doesn't matter when they go
- *  tristate.
- *
- *  The LPC1768_PWM_init routine kicks off the MR0 interrupt.  This interrupt is never disabled or
- *  delayed.
- *
- *  The PWM_table_swap flag is set when the firmware has swapped in an updated table.  It is
- *  cleared by the ISR during the MR0 interrupt as it completes the swap and accompanying updates.
- *  It serves two purposes:
- *    1) Tells the ISR that the tables have been swapped
- *    2) Keeps the firmware from starting a new update until the previous one has been completed.
- *
- *  The PWM_MR0_wait flag is set when the firmware is ready to swap in an updated table and cleared by
- *  the ISR during the MR0 interrupt.  It is used to avoid delaying the MR0 interrupt when swapping in
- *  an updated table.  This avoids glitches in pulse width and/or repetition rate.
- *
- *  The sequence of events during a write to a PWM channel is:
- *    1) Waits until PWM_table_swap flag is false before starting
- *    2) Copies the active table into the work table
- *    3) Updates the work table
- *         NOTES - MR1-MR6 are updated at this time.  The updates aren't put into use until the first
- *                 MR0 after the LER register has been written.  The LER register is written during the
- *                 table swap process.
- *               - The MCR mask is created at this time.  It is not used until the ISR writes the MCR
- *                 during the MR0 interrupt in the table swap process.
- *    4) Sets the PWM_MR0_wait flag
- *    5) ISR clears the PWM_MR0_wait flag during the next MR0 interrupt
- *    6) Once the PWM_MR0_wait flag is cleared then the firmware:
- *          disables the ISR interrupt
- *          swaps the pointers to the tables
- *          writes to the LER register
- *          sets the PWM_table_swap flag active
- *          re-enables the ISR
- *     7) On the next interrupt the ISR changes its pointer to the work table which is now the old,
- *        unmodified, active table.
- *     8) On the next MR0 interrupt the ISR:
- *          switches over to the active table
- *          clears the PWM_table_swap and PWM_MR0_wait flags
- *          updates the MCR register with the possibly new interrupt sources/assignments
- *          writes to the PCR register to enable the direct control of the Servo 0, 1 & 3 pins by the PWM1 module
- *          sets the PINSEL3 register to function/mode 0x2 for the Servo 0, 1 & 3 pins
- *             NOTE - PCR must be set before PINSEL
- *          sets the pins controlled by the ISR to their active states
- */
-
+void LPC1768_PWM_init(void);
+bool LPC1768_PWM_attach_pin(pin_t pin, uint32_t min = 1, uint32_t max = (LPC_PWM1_MR0 - MR0_MARGIN), uint8_t servo_index = 0xff);
+void LPC1768_PWM_update_map_MR(void);
+void LPC1768_PWM_update(void);
+bool LPC1768_PWM_write(pin_t pin, uint32_t value);
+bool LPC1768_PWM_detach_pin(pin_t pin);
+bool useable_hardware_PWM(pin_t pin);
diff --git a/Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.cpp b/Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.cpp
index c8120b82dd..317433191c 100644
--- a/Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.cpp
+++ b/Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.cpp
@@ -64,13 +64,10 @@
 
 #if HAS_SERVOS && defined(TARGET_LPC1768)
 
+  #include "LPC1768_PWM.h"
   #include "LPC1768_Servo.h"
   #include "servo_private.h"
 
-  extern bool LPC1768_PWM_attach_pin(uint8_t, uint32_t, uint32_t, uint8_t);
-  extern bool LPC1768_PWM_write(uint8_t, uint32_t);
-  extern bool LPC1768_PWM_detach_pin(uint8_t);
-
   ServoInfo_t servo_info[MAX_SERVOS];                  // static array of servo info structures
   uint8_t ServoCount = 0;                              // the total number of attached servos
 
diff --git a/Marlin/src/HAL/HAL_LPC1768/SoftwareSerial.cpp b/Marlin/src/HAL/HAL_LPC1768/SoftwareSerial.cpp
index bfc5fbebb3..21796bcf64 100644
--- a/Marlin/src/HAL/HAL_LPC1768/SoftwareSerial.cpp
+++ b/Marlin/src/HAL/HAL_LPC1768/SoftwareSerial.cpp
@@ -40,7 +40,6 @@ http://arduiniana.org.
 #include <stdarg.h>
 #include "arduino.h"
 #include "pinmapping.h"
-#include "pinmap_re_arm.h"
 #include "fastio.h"
 #include "SoftwareSerial.h"
 
@@ -253,8 +252,8 @@ void SoftwareSerial::setRX(uint8_t rx)
   //if (!_inverse_logic)
   // digitalWrite(rx, HIGH);
   _receivePin = rx;
-  _receivePort = pin_map[rx].port;
-  _receivePortPin = pin_map[rx].pin;
+  _receivePort = LPC1768_PIN_PORT(rx);
+  _receivePortPin = LPC1768_PIN_PIN(rx);
 /*  GPIO_T * rxPort = digitalPinToPort(rx);
   _receivePortRegister = portInputRegister(rxPort);
   _receiveBitMask = digitalPinToBitMask(rx);*/
diff --git a/Marlin/src/HAL/HAL_LPC1768/WInterrupts.cpp b/Marlin/src/HAL/HAL_LPC1768/WInterrupts.cpp
index d3e91ce553..f1cf6f9838 100644
--- a/Marlin/src/HAL/HAL_LPC1768/WInterrupts.cpp
+++ b/Marlin/src/HAL/HAL_LPC1768/WInterrupts.cpp
@@ -54,8 +54,8 @@ void attachInterrupt(const uint32_t pin, void (*callback)(void), uint32_t mode)
     __initialize();
     ++enabled;
   }
-  uint8_t myport = pin_map[pin].port,
-          mypin = pin_map[pin].pin;
+  uint8_t myport = LPC1768_PIN_PORT(pin),
+          mypin = LPC1768_PIN_PIN(pin);
 
   if (myport == 0)
     callbacksP0[mypin] = callback;
@@ -69,8 +69,8 @@ void attachInterrupt(const uint32_t pin, void (*callback)(void), uint32_t mode)
 void detachInterrupt(const uint32_t pin) {
   if (!INTERRUPT_PIN(pin)) return;
 
-  const uint8_t myport = pin_map[pin].port,
-                mypin = pin_map[pin].pin;
+  const uint8_t myport = LPC1768_PIN_PORT(pin),
+                mypin = LPC1768_PIN_PIN(pin);
 
   // Disable interrupt
   GpioDisableInt(myport, mypin);
diff --git a/Marlin/src/HAL/HAL_LPC1768/arduino.cpp b/Marlin/src/HAL/HAL_LPC1768/arduino.cpp
index 32c4341660..4832c57f27 100644
--- a/Marlin/src/HAL/HAL_LPC1768/arduino.cpp
+++ b/Marlin/src/HAL/HAL_LPC1768/arduino.cpp
@@ -23,6 +23,7 @@
 #ifdef TARGET_LPC1768
 
 #include "../../inc/MarlinConfig.h"
+#include "LPC1768_PWM.h"
 
 #include <lpc17xx_pinsel.h>
 
@@ -70,26 +71,26 @@ extern "C" void delay(const int msec) {
 
 // IO functions
 // As defined by Arduino INPUT(0x0), OUPUT(0x1), INPUT_PULLUP(0x2)
-void pinMode(uint8_t pin, uint8_t mode) {
-  if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
+void pinMode(pin_t pin, uint8_t mode) {
+  if (!VALID_PIN(pin))
     return;
 
-  PINSEL_CFG_Type config = { pin_map[pin].port,
-                             pin_map[pin].pin,
+  PINSEL_CFG_Type config = { LPC1768_PIN_PORT(pin),
+                             LPC1768_PIN_PIN(pin),
                              PINSEL_FUNC_0,
                              PINSEL_PINMODE_TRISTATE,
                              PINSEL_PINMODE_NORMAL };
   switch(mode) {
   case INPUT:
-    LPC_GPIO(pin_map[pin].port)->FIODIR &= ~LPC_PIN(pin_map[pin].pin);
+    LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
     PINSEL_ConfigPin(&config);
     break;
   case OUTPUT:
-    LPC_GPIO(pin_map[pin].port)->FIODIR |=  LPC_PIN(pin_map[pin].pin);
+    LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR |=  LPC_PIN(LPC1768_PIN_PIN(pin));
     PINSEL_ConfigPin(&config);
     break;
   case INPUT_PULLUP:
-    LPC_GPIO(pin_map[pin].port)->FIODIR &= ~LPC_PIN(pin_map[pin].pin);
+    LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
     config.Pinmode = PINSEL_PINMODE_PULLUP;
     PINSEL_ConfigPin(&config);
     break;
@@ -98,14 +99,14 @@ void pinMode(uint8_t pin, uint8_t mode) {
   }
 }
 
-void digitalWrite(uint8_t pin, uint8_t pin_status) {
-  if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
+void digitalWrite(pin_t pin, uint8_t pin_status) {
+  if (!VALID_PIN(pin))
     return;
 
   if (pin_status)
-    LPC_GPIO(pin_map[pin].port)->FIOSET = LPC_PIN(pin_map[pin].pin);
+    LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOSET = LPC_PIN(LPC1768_PIN_PIN(pin));
   else
-    LPC_GPIO(pin_map[pin].port)->FIOCLR = LPC_PIN(pin_map[pin].pin);
+    LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOCLR = LPC_PIN(LPC1768_PIN_PIN(pin));
 
   pinMode(pin, OUTPUT);  // Set pin mode on every write (Arduino version does this)
 
@@ -118,23 +119,19 @@ void digitalWrite(uint8_t pin, uint8_t pin_status) {
      */
 }
 
-bool digitalRead(uint8_t pin) {
-  if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF) {
+bool digitalRead(pin_t pin) {
+  if (!VALID_PIN(pin)) {
     return false;
   }
-  return LPC_GPIO(pin_map[pin].port)->FIOPIN & LPC_PIN(pin_map[pin].pin) ? 1 : 0;
+  return LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOPIN & LPC_PIN(LPC1768_PIN_PIN(pin)) ? 1 : 0;
 }
 
-void analogWrite(uint8_t pin, int pwm_value) {  // 1 - 254: pwm_value, 0: LOW, 255: HIGH
-
-  extern bool LPC1768_PWM_attach_pin(uint8_t, uint32_t, uint32_t, uint8_t);
-  extern bool LPC1768_PWM_write(uint8_t, uint32_t);
-  extern bool LPC1768_PWM_detach_pin(uint8_t);
+void analogWrite(pin_t pin, int pwm_value) {  // 1 - 254: pwm_value, 0: LOW, 255: HIGH
   #define MR0_MARGIN 200       // if channel value too close to MR0 the system locks up
 
   static bool out_of_PWM_slots = false;
 
-  if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
+  if (!VALID_PIN(pin))
     return;
 
   uint value = MAX(MIN(pwm_value, 255), 0);
@@ -155,7 +152,7 @@ void analogWrite(uint8_t pin, int pwm_value) {  // 1 - 254: pwm_value, 0: LOW, 2
 
 extern bool HAL_adc_finished();
 
-uint16_t analogRead(uint8_t adc_pin) {
+uint16_t analogRead(pin_t adc_pin) {
   HAL_adc_start_conversion(adc_pin);
   while (!HAL_adc_finished());  // Wait for conversion to finish
   return HAL_adc_get_result();
diff --git a/Marlin/src/HAL/HAL_LPC1768/fastio.h b/Marlin/src/HAL/HAL_LPC1768/fastio.h
index 85d5ce2ab3..6f0b361463 100644
--- a/Marlin/src/HAL/HAL_LPC1768/fastio.h
+++ b/Marlin/src/HAL/HAL_LPC1768/fastio.h
@@ -45,15 +45,15 @@ bool useable_hardware_PWM(uint8_t pin);
 #define LPC_PIN(pin)            (1UL << pin)
 #define LPC_GPIO(port)          ((volatile LPC_GPIO_TypeDef *)(LPC_GPIO0_BASE + LPC_PORT_OFFSET * port))
 
-#define SET_DIR_INPUT(IO)       (LPC_GPIO(DIO ## IO ## _PORT)->FIODIR &= ~LPC_PIN(DIO ## IO ##_PIN))
-#define SET_DIR_OUTPUT(IO)      (LPC_GPIO(DIO ## IO ## _PORT)->FIODIR |=  LPC_PIN(DIO ## IO ##_PIN))
+#define SET_DIR_INPUT(IO)       (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(IO)))
+#define SET_DIR_OUTPUT(IO)      (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIODIR |=  LPC_PIN(LPC1768_PIN_PIN(IO)))
 
-#define SET_MODE(IO, mode)      (pin_mode((DIO ## IO ## _PORT, DIO ## IO ## _PIN), mode))
+#define SET_MODE(IO, mode)      (pin_mode((LPC1768_PIN_PORT(IO), LPC1768_PIN_PIN(IO)), mode))
 
-#define WRITE_PIN_SET(IO)       (LPC_GPIO(DIO ## IO ## _PORT)->FIOSET = LPC_PIN(DIO ## IO ##_PIN))
-#define WRITE_PIN_CLR(IO)       (LPC_GPIO(DIO ## IO ## _PORT)->FIOCLR = LPC_PIN(DIO ## IO ##_PIN))
+#define WRITE_PIN_SET(IO)       (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIOSET = LPC_PIN(LPC1768_PIN_PIN(IO)))
+#define WRITE_PIN_CLR(IO)       (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIOCLR = LPC_PIN(LPC1768_PIN_PIN(IO)))
 
-#define READ_PIN(IO)            ((LPC_GPIO(DIO ## IO ## _PORT)->FIOPIN & LPC_PIN(DIO ## IO ##_PIN)) ? 1 : 0)
+#define READ_PIN(IO)            ((LPC_GPIO(LPC1768_PIN_PORT(IO))->FIOPIN & LPC_PIN(LPC1768_PIN_PIN(IO))) ? 1 : 0)
 #define WRITE_PIN(IO, v)        ((v) ? WRITE_PIN_SET(IO) : WRITE_PIN_CLR(IO))
 
 /**
diff --git a/Marlin/src/HAL/HAL_LPC1768/include/Wire.h b/Marlin/src/HAL/HAL_LPC1768/include/Wire.h
index 7e736829b5..d6da3b2311 100644
--- a/Marlin/src/HAL/HAL_LPC1768/include/Wire.h
+++ b/Marlin/src/HAL/HAL_LPC1768/include/Wire.h
@@ -21,7 +21,7 @@
 
 // Modified for use with the mcp4451 digipot routine
 
-#if defined(TARGET_LPC1768)
+#ifdef TARGET_LPC1768
 
 #ifndef TwoWire_h
 #define TwoWire_h
diff --git a/Marlin/src/HAL/HAL_LPC1768/include/arduino.h b/Marlin/src/HAL/HAL_LPC1768/include/arduino.h
index 5a310f5750..a88324fcfd 100644
--- a/Marlin/src/HAL/HAL_LPC1768/include/arduino.h
+++ b/Marlin/src/HAL/HAL_LPC1768/include/arduino.h
@@ -26,6 +26,8 @@
 #include <stdint.h>
 #include <math.h>
 
+#include "../pinmapping.h"
+
 #define LOW          0x00
 #define HIGH         0x01
 #define CHANGE       0x02
@@ -83,6 +85,7 @@ extern "C" void GpioDisableInt(uint32_t port, uint32_t pin);
 #define pgm_read_word(addr)       pgm_read_word_near(addr)
 #define pgm_read_dword(addr)      pgm_read_dword_near(addr)
 
+#define memcpy_P memcpy
 #define sprintf_P sprintf
 #define strstr_P strstr
 #define strncpy_P strncpy
@@ -99,11 +102,11 @@ void delayMicroseconds(unsigned long);
 uint32_t millis();
 
 //IO functions
-void pinMode(uint8_t, uint8_t);
-void digitalWrite(uint8_t, uint8_t);
-bool digitalRead(uint8_t);
-void analogWrite(uint8_t, int);
-uint16_t analogRead(uint8_t);
+void pinMode(pin_t, uint8_t);
+void digitalWrite(pin_t, uint8_t);
+bool digitalRead(pin_t);
+void analogWrite(pin_t, int);
+uint16_t analogRead(pin_t);
 
 // EEPROM
 void eeprom_write_byte(unsigned char *pos, unsigned char value);
diff --git a/Marlin/src/HAL/HAL_LPC1768/include/digipot_mcp4451_I2C_routines.c b/Marlin/src/HAL/HAL_LPC1768/include/digipot_mcp4451_I2C_routines.c
index 6b2372fcd6..a75b21c532 100644
--- a/Marlin/src/HAL/HAL_LPC1768/include/digipot_mcp4451_I2C_routines.c
+++ b/Marlin/src/HAL/HAL_LPC1768/include/digipot_mcp4451_I2C_routines.c
@@ -25,7 +25,7 @@
 
 
 
-#if defined(TARGET_LPC1768)
+#ifdef TARGET_LPC1768
 
   #ifdef __cplusplus
     extern "C" {
diff --git a/Marlin/src/HAL/HAL_LPC1768/lpc1768_flag_script.py b/Marlin/src/HAL/HAL_LPC1768/lpc1768_flag_script.py
index a3138dfc07..4f888aa9f3 100644
--- a/Marlin/src/HAL/HAL_LPC1768/lpc1768_flag_script.py
+++ b/Marlin/src/HAL/HAL_LPC1768/lpc1768_flag_script.py
@@ -22,8 +22,7 @@ if __name__ == "__main__":
 
                     "-MMD",
                     "-MP",
-                    "-DTARGET_LPC1768",
-                    "-DIS_REARM"
+                    "-DTARGET_LPC1768"
                   ])
 
   for i in range(1, len(sys.argv)):
diff --git a/Marlin/src/HAL/HAL_LPC1768/main.cpp b/Marlin/src/HAL/HAL_LPC1768/main.cpp
index 788193c5b1..a7f013de43 100644
--- a/Marlin/src/HAL/HAL_LPC1768/main.cpp
+++ b/Marlin/src/HAL/HAL_LPC1768/main.cpp
@@ -100,7 +100,6 @@ int main(void) {
 
   HAL_timer_init();
 
-  extern void LPC1768_PWM_init();
   LPC1768_PWM_init();
 
   setup();
diff --git a/Marlin/src/HAL/HAL_LPC1768/persistent_store_impl.cpp b/Marlin/src/HAL/HAL_LPC1768/persistent_store_impl.cpp
index 5bcd3576e3..82fd567ab9 100644
--- a/Marlin/src/HAL/HAL_LPC1768/persistent_store_impl.cpp
+++ b/Marlin/src/HAL/HAL_LPC1768/persistent_store_impl.cpp
@@ -50,7 +50,8 @@ bool access_start() {
   if (res) MSC_Release_Lock();
 
   if (res == FR_OK) {
-    uint16_t bytes_written, file_size = f_size(&eeprom_file);
+    UINT bytes_written;
+    FSIZE_t file_size = f_size(&eeprom_file);
     f_lseek(&eeprom_file, file_size);
     while (file_size <= E2END && res == FR_OK) {
       res = f_write(&eeprom_file, &eeprom_erase_value, 1, &bytes_written);
@@ -99,7 +100,7 @@ bool access_finish() {
 
 bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
   FRESULT s;
-  uint16_t bytes_written = 0;
+  UINT bytes_written = 0;
 
   s = f_lseek(&eeprom_file, pos);
   if (s) {
@@ -128,7 +129,7 @@ bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
 }
 
 bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) {
-  uint16_t bytes_read = 0;
+  UINT bytes_read = 0;
   FRESULT s;
   s = f_lseek(&eeprom_file, pos);
   if ( s ) {
diff --git a/Marlin/src/HAL/HAL_LPC1768/pinmap_re_arm.h b/Marlin/src/HAL/HAL_LPC1768/pinmap_re_arm.h
deleted file mode 100644
index c4843d7f91..0000000000
--- a/Marlin/src/HAL/HAL_LPC1768/pinmap_re_arm.h
+++ /dev/null
@@ -1,464 +0,0 @@
-/**
- * Marlin 3D Printer Firmware
- * Copyright (C) 2016 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 <http://www.gnu.org/licenses/>.
- *
- */
-
-#ifndef __PINMAP_RE_ARM_H__
-#define __PINMAP_RE_ARM_H__
-
-// ******************
-// Runtime pinmapping
-// ******************
-
-#if SERIAL_PORT == 0
-  #define NUM_ANALOG_INPUTS 6
-#else
-  #define NUM_ANALOG_INPUTS 8
-#endif
-
-const adc_pin_data adc_pin_map[] = {
-  {0, 23, 0},         //A0 (T0) - D67 - TEMP_0_PIN
-  {0, 24, 1},         //A1 (T1) - D68 - TEMP_BED_PIN
-  {0, 25, 2},         //A2 (T2) - D69 - TEMP_1_PIN
-  {0, 26, 3},         //A3 - D63
-  {1, 30, 4},         //A4 - D37 - BUZZER_PIN
-  {1, 31, 5},         //A5 - D49 - SD_DETECT_PIN
-  #if SERIAL_PORT != 0
-    {0,  3, 6},       //A6 - D0  - RXD0
-    {0,  2, 7}        //A7 - D1  - TXD0
-  #endif
-};
-
-constexpr FORCE_INLINE int8_t analogInputToDigitalPin(int8_t p) {
-  return (p == 0 ? 67:
-          p == 1 ? 68:
-          p == 2 ? 69:
-          p == 3 ? 63:
-          p == 4 ? 37:
-          p == 5 ? 49:
-          #if SERIAL_PORT != 0
-            p == 6 ?  0:
-            p == 7 ?  1:
-          #endif
-          -1);
-}
-
-constexpr FORCE_INLINE int8_t DIGITAL_PIN_TO_ANALOG_PIN(int8_t p) {
-  return (p == 67 ? 0:
-          p == 68 ? 1:
-          p == 69 ? 2:
-          p == 63 ? 3:
-          p == 37 ? 4:
-          p == 49 ? 5:
-          #if SERIAL_PORT != 0
-            p == 0  ? 6:
-            p == 1  ? 7:
-          #endif
-          -1);
-}
-
-#define NUM_DIGITAL_PINS 84
-
-#define VALID_PIN(r)  (r <   0 ? 0 :\
-                       r ==  7 ? 0 :\
-                       r == 17 ? 0 :\
-                       r == 22 ? 0 :\
-                       r == 23 ? 0 :\
-                       r == 25 ? 0 :\
-                       r == 27 ? 0 :\
-                       r == 29 ? 0 :\
-                       r == 32 ? 0 :\
-                       r == 39 ? 0 :\
-                       r == 40 ? 0 :\
-                       r == 42 ? 0 :\
-                       r == 43 ? 0 :\
-                       r == 44 ? 0 :\
-                       r == 45 ? 0 :\
-                       r == 47 ? 0 :\
-                       r == 64 ? 0 :\
-                       r == 65 ? 0 :\
-                       r == 66 ? 0 :\
-                       r >= NUM_DIGITAL_PINS ? 0 : 1)
-
-#define PWM_PIN(r)  (r <   0 ? 0 :\
-                       r ==  3 ? 1 :\
-                       r ==  4 ? 1 :\
-                       r ==  6 ? 1 :\
-                       r ==  9 ? 1 :\
-                       r == 10 ? 1 :\
-                       r == 11 ? 1 :\
-                       r == 14 ? 1 :\
-                       r == 26 ? 1 :\
-                       r == 46 ? 1 :\
-                       r == 53 ? 1 :\
-                       r == 54 ? 1 :\
-                       r == 60 ? 1 : 0)
-
-#define NUM_INTERRUPT_PINS 35
-
-#define INTERRUPT_PIN(r)  ( r< 0  ? 0 :\
-                        r == 0  ? 1 :\
-                        r == 1  ? 1 :\
-                        r == 8  ? 1 :\
-                        r == 9  ? 1 :\
-                        r == 10 ? 1 :\
-                        r == 12 ? 1 :\
-                        r == 16 ? 1 :\
-                        r == 20 ? 1 :\
-                        r == 21 ? 1 :\
-                        r == 24 ? 1 :\
-                        r == 25 ? 1 :\
-                        r == 26 ? 1 :\
-                        r == 28 ? 1 :\
-                        r == 34 ? 1 :\
-                        r == 35 ? 1 :\
-                        r == 36 ? 1 :\
-                        r == 38 ? 1 :\
-                        r == 46 ? 1 :\
-                        r == 48 ? 1 :\
-                        r == 50 ? 1 :\
-                        r == 51 ? 1 :\
-                        r == 52 ? 1 :\
-                        r == 54 ? 1 :\
-                        r == 55 ? 1 :\
-                        r == 56 ? 1 :\
-                        r == 57 ? 1 :\
-                        r == 58 ? 1 :\
-                        r == 59 ? 1 :\
-                        r == 60 ? 1 :\
-                        r == 61 ? 1 :\
-                        r == 62 ? 1 :\
-                        r == 63 ? 1 :\
-                        r == 67 ? 1 :\
-                        r == 68 ? 1 :\
-                        r == 69 ? 1 : 0)
-                        /*Internal SD Card */
-                        /*r == 80 ? 1 :\
-                        r == 81 ? 1 :\
-                        r == 82 ? 1 :\
-                        r == 83 ? 1 :\*/
-
-const pin_data pin_map[] = { // pin map for variable pin function
-  {0,3},        //  DIO0   RXD0             A6               J4-4                           AUX-1
-  {0,2},        //  DIO1   TXD0             A7               J4-5                           AUX-1
-  {1,25},       //  DIO2   X_MAX_PIN                          10K PULLUP TO 3.3v, 1K SERIES
-  {1,24},       //  DIO3   X_MIN_PIN                          10K PULLUP TO 3.3v, 1K SERIES
-  {1,18},       //  DIO4   SERVO3_PIN        FIL_RUNOUT_PIN   5V output, PWM
-  {1,19},       //  DIO5   SERVO2_PIN
-  {1,21},       //  DIO6   SERVO1_PIN       J5-1
-  {0xFF,0xFF},  //  DIO7   N/C
-  {2,7},        //  DIO8   RAMPS_D8_PIN
-  {2,4},        //  DIO9   RAMPS_D9_PIN     PWM
-  {2,5},        //  DIO10  RAMPS_D10_PIN    PWM
-  {1,20},       //  DIO11  SERVO0_PIN
-  {2,12},       //  DIO12  PS_ON_PIN
-  {4,28},       //  DIO13  LED_PIN
-  {1,26},       //  DIO14  Y_MIN_PIN                          10K PULLUP TO 3.3v, 1K SERIES
-  {1,27},       //  DIO15  Y_MAX_PIN                          10K PULLUP TO 3.3v, 1K SERIES
-  {0,16},       //  DIO16  LCD_PINS_RS      J3-7
-  {0xFF,0xFF},  //  DIO17  LCD_PINS_ENABLE   MOSI_PIN(MOSI0)  J3-10                          AUX-3
-  {1,29},       //  DIO18  Z_MIN_PIN                          10K PULLUP TO 3.3v, 1K SERIES
-  {1,28},       //  DIO19  Z_MAX_PIN                          10K PULLUP TO 3.3v, 1K SERIES
-  {0,0},        //  DIO20  SCA
-  {0,1},        //  DIO21  SCL
-  {0xFF,0xFF},  //  DIO22  N/C
-  {0xFF,0xFF},  //  DIO23  LCD_PINS_D4       SCK_PIN(SCLK0)   J3-9                           AUX-3
-  {0,4},        //  DIO24  E0_ENABLE_PIN
-  {0xFF,0xFF},  //  DIO25  N/C
-  {2,0},        //  DIO26  E0_STEP_PIN
-  {0xFF,0xFF},  //  DIO27  N/C
-  {0,5},        //  DIO28  E0_DIR_PIN
-  {0xFF,0xFF},  //  DIO29  N/C
-  {4,29},       //  DIO30  E1_ENABLE_PIN
-  {3,26},       //  DIO31  BTN_EN1
-  {0xFF,0xFF},  //  DIO32  N/C
-  {3,25},       //  DIO33  BTN_EN2          J3-4
-  {2,13},       //  DIO34  E1_DIR_PIN
-  {2,11},       //  DIO35  BTN_ENC          J3-3
-  {2,8},        //  DIO36  E1_STEP_PIN
-  {1,30},       //  DIO37  BEEPER_PIN       A4                                              not 5V tolerant
-  {0,10},       //  DIO38  X_ENABLE_PIN
-  {0xFF,0xFF},  //  DIO39  N/C
-  {0xFF,0xFF},  //  DIO40  N/C
-  {1,22},       //  DIO41  KILL_PIN         J5-4
-  {0xFF,0xFF},  //  DIO42  N/C
-  {0xFF,0xFF},  //  DIO43  N/C
-  {0xFF,0xFF},  //  DIO44  N/C
-  {0xFF,0xFF},  //  DIO45  N/C
-  {2,3},        //  DIO46  Z_STEP_PIN
-  {0xFF,0xFF},  //  DIO47  N/C
-  {0,22},       //  DIO48  Z_DIR_PIN
-  {1,31},       //  DIO49  SD_DETECT_PIN    A5               J3-1                           not 5V tolerant
-  {0,17},       //  DIO50  MISO_PIN(MISO0)                                                   AUX-3
-  {0,18},       //  DIO51  MOSI_PIN(MOSI0)   LCD_PINS_ENABLE  J3-10                          AUX-3
-  {0,15},       //  DIO52  SCK_PIN(SCLK0)    LCD_PINS_D4      J3-9                           AUX-3
-  {1,23},       //  DIO53  SDSS(SSEL0)      J3-5                                             AUX-3
-  {2,1},        //  DIO54  X_STEP_PIN
-  {0,11},       //  DIO55  X_DIR_PIN
-  {0,19},       //  DIO56  Y_ENABLE_PIN
-  {0,27},       //  DIO57                   AUX-1             open collector
-  {0,28},       //  DIO58                   AUX-1             open collector
-  {2,6},        //  DIO59  LCD_A0           J3-8                                             AUX-2
-  {2,2},        //  DIO60  Y_STEP_PIN
-  {0,20},       //  DIO61  Y_DIR_PIN
-  {0,21},       //  DIO62  Z_ENABLE_PIN
-  {0,26},       //  DIO63  AUX-2             A3               J5-3                           AUX-2
-  {0xFF,0xFF},  //  DIO64  N/C
-  {0xFF,0xFF},  //  DIO65  N/C
-  {0xFF,0xFF},  //  DIO66  N/C
-  {0,23},       //  DIO67  TEMP_0_PIN       A0
-  {0,24},       //  DIO68  TEMP_BED_PIN     A1
-  {0,25},       //  DIO69  TEMP_1_PIN       A2
-  {1,16},       //  DIO70                   J12-3             ENET_MOC
-  {1,17},       //  DIO71                   J12-4             ENET_MDIO
-  {1,15},       //  DIO72                   J12-5             REF_CLK
-  {1,14},       //  DIO73                   J12-6             ENET_RX_ER
-  {1,9},        //  DIO74                   J12-7             ENET_RXD0
-  {1,10},       //  DIO75                   J12-8             ENET_RXD1
-  {1,8},        //  DIO76                   J12-9             ENET_CRS
-  {1,4},        //  DIO77                   J12-10            ENET_TX_EN
-  {1,0},        //  DIO78                   J12-11            ENET_TXD0
-  {1,1},        //  DIO79                   J12-12            ENET_TXD1
-  {0,14},       //  DIO80                   MKS-SBASE	J7-6 & EXP1-5
-  {0,7},        //  DIO81  SD-SCK           MKS-SBASE	on board SD card and EXP2-2
-  {0,8},        //  DIO82  SD-MISO          MKS-SBASE	on board SD card and EXP2-1
-  {0,9},        //  DIO83  SD-MOSI          MKS-SBASE 	n board SD card and EXP2-6
-//  {0,6},        //  DIO84  SD-CS            on board SD card
-
-};
-
-// ***********************
-// Preprocessor pinmapping
-// ***********************
-
-//#define RXD0                      0  //              A16               J4-4                           AUX-1
-#define DIO0_PORT 0
-#define DIO0_PIN 3
-//#define TXD0                      1  //              A17               J4-5                           AUX-1
-#define DIO1_PORT 0
-#define DIO1_PIN 2
-//#define X_MAX_PIN                 2  //                           10K PULLUP TO 3.3v, 1K SERIES
-#define DIO2_PORT 1
-#define DIO2_PIN 25
-//#define X_MIN_PIN                 3  //                           10K PULLUP TO 3.3v, 1K SERIES
-#define DIO3_PORT 1
-#define DIO3_PIN 24
-//#define SERVO3_PIN                4  //         FIL_RUNOUT_PIN   5V output, PWM
-#define DIO4_PORT 1
-#define DIO4_PIN 18
-//#define SERVO2_PIN                5  //
-#define DIO5_PORT 1
-#define DIO5_PIN 19
-//#define SERVO1_PIN                6  //        J5-1
-#define DIO6_PORT 1
-#define DIO6_PIN 21
-//#define RAMPS_D8_PIN              8  //
-#define DIO8_PORT 2
-#define DIO8_PIN 7
-//#define RAMPS_D9_PIN              9  //      PWM
-#define DIO9_PORT 2
-#define DIO9_PIN 4
-//#define RAMPS_D10_PIN             10  //     PWM
-#define DIO10_PORT 2
-#define DIO10_PIN 5
-//#define SERVO0_PIN                11  //
-#define DIO11_PORT 1
-#define DIO11_PIN 20
-//#define PS_ON_PIN                 12  //
-#define DIO12_PORT 2
-#define DIO12_PIN 12
-//#define LED_PIN                   13  //
-#define DIO13_PORT 4
-#define DIO13_PIN 28
-//#define Y_MIN_PIN                 14  //                           10K PULLUP TO 3.3v, 1K SERIES
-#define DIO14_PORT 1
-#define DIO14_PIN 26
-//#define Y_MAX_PIN                 15  //                           10K PULLUP TO 3.3v, 1K SERIES
-#define DIO15_PORT 1
-#define DIO15_PIN 27
-//#define LCD_PINS_RS               16  //       J3-7
-#define DIO16_PORT 0
-#define DIO16_PIN 16
-//#define Z_MIN_PIN                 18  //                           10K PULLUP TO 3.3v, 1K SERIES
-#define DIO18_PORT 1
-#define DIO18_PIN 29
-//#define Z_MAX_PIN                 19  //                           10K PULLUP TO 3.3v, 1K SERIES
-#define DIO19_PORT 1
-#define DIO19_PIN 28
-//#define SCA                       20  //
-#define DIO20_PORT 0
-#define DIO20_PIN 0
-//#define SCL                       21  //
-#define DIO21_PORT 0
-#define DIO21_PIN 1
-//#define E0_ENABLE_PIN             24  //
-#define DIO24_PORT 0
-#define DIO24_PIN 4
-//#define E0_STEP_PIN               26  //
-#define DIO26_PORT 2
-#define DIO26_PIN 0
-//#define E0_DIR_PIN                28  //
-#define DIO28_PORT 0
-#define DIO28_PIN 5
-//#define E1_ENABLE_PIN             30  //
-#define DIO30_PORT 4
-#define DIO30_PIN 29
-//#define BTN_EN1                   31  //
-#define DIO31_PORT 3
-#define DIO31_PIN 26
-//#define BTN_EN2                   33  //           J3-4
-#define DIO33_PORT 3
-#define DIO33_PIN 25
-//#define E1_DIR_PIN                34  //
-#define DIO34_PORT 2
-#define DIO34_PIN 13
-//#define BTN_ENC                   35  //           J3-3
-#define DIO35_PORT 2
-#define DIO35_PIN 11
-//#define E1_STEP_PIN               36  //
-#define DIO36_PORT 2
-#define DIO36_PIN 8
-//#define BEEPER_PIN                37  //        A18                                              not 5V tolerant
-#define DIO37_PORT 1
-#define DIO37_PIN 30
-//#define X_ENABLE_PIN              38  //
-#define DIO38_PORT 0
-#define DIO38_PIN 10
-//#define KILL_PIN                  41  //          J5-4
-#define DIO41_PORT 1
-#define DIO41_PIN 22
-//#define Z_STEP_PIN                46  //
-#define DIO46_PORT 2
-#define DIO46_PIN 3
-//#define Z_DIR_PIN                 48  //
-#define DIO48_PORT 0
-#define DIO48_PIN 22
-//#define SD_DETECT_PIN             49  //     A19               J3-1                           not 5V tolerant
-#define DIO49_PORT 1
-#define DIO49_PIN 31
-//#define MISO_PIN(MISO0)           50  //                                                    AUX-3
-#define DIO50_PORT 0
-#define DIO50_PIN 17
-//#define MOSI_PIN(MOSI0)           51  //    LCD_PINS_ENABLE  J3-10                          AUX-3
-#define DIO51_PORT 0
-#define DIO51_PIN 18
-//#define SCK_PIN(SCLK0)            52  //     LCD_PINS_D4      J3-9                           AUX-3
-#define DIO52_PORT 0
-#define DIO52_PIN 15
-//#define SDSS(SSEL0)               53  //       J3-5                                             AUX-3
-#define DIO53_PORT 1
-#define DIO53_PIN 23
-//#define X_STEP_PIN                54  //
-#define DIO54_PORT 2
-#define DIO54_PIN 1
-//#define X_DIR_PIN                 55  //
-#define DIO55_PORT 0
-#define DIO55_PIN 11
-//#define Y_ENABLE_PIN              56  //
-#define DIO56_PORT 0
-#define DIO56_PIN 19
-//#define AUX-1                     57  //              open collector
-#define DIO57_PORT 0
-#define DIO57_PIN 27
-//#define AUX-1                     58  //              open collector
-#define DIO58_PORT 0
-#define DIO58_PIN 28
-//#define LCD_A0                    59  //            J3-8                                             AUX-2
-#define DIO59_PORT 2
-#define DIO59_PIN 6
-//#define Y_STEP_PIN                60  //
-#define DIO60_PORT 2
-#define DIO60_PIN 2
-//#define Y_DIR_PIN                 61  //
-#define DIO61_PORT 0
-#define DIO61_PIN 20
-//#define Z_ENABLE_PIN              62  //
-#define DIO62_PORT 0
-#define DIO62_PIN 21
-//#define AUX-2                     63  //              A9               J5-3                           AUX-2
-#define DIO63_PORT 0
-#define DIO63_PIN 26
-//#define TEMP_0_PIN                67  //        A13
-#define DIO67_PORT 0
-#define DIO67_PIN 23
-//#define TEMP_BED_PIN              68  //      A14
-#define DIO68_PORT 0
-#define DIO68_PIN 24
-//#define TEMP_1_PIN                69  //        A15
-#define DIO69_PORT 0
-#define DIO69_PIN 25
-//#define J12-3                     70  //              ENET_MOC
-#define DIO70_PORT 1
-#define DIO70_PIN 16
-//#define J12-4                     71  //              ENET_MDIO
-#define DIO71_PORT 1
-#define DIO71_PIN 17
-//#define J12-5                     72  //              REF_CLK
-#define DIO72_PORT 1
-#define DIO72_PIN 15
-//#define J12-6                     73  //              ENET_RX_ER
-#define DIO73_PORT 1
-#define DIO73_PIN 14
-//#define J12-7                     74  //              ENET_RXD0
-#define DIO74_PORT 1
-#define DIO74_PIN 9
-//#define J12-8                     75  //              ENET_RXD1
-#define DIO75_PORT 1
-#define DIO75_PIN 10
-//#define J12-9                     76  //              ENET_CRS
-#define DIO76_PORT 1
-#define DIO76_PIN 8
-//#define J12-10                    77  //             ENET_TX_EN
-#define DIO77_PORT 1
-#define DIO77_PIN 4
-//#define J12-11                    78  //             ENET_TXD0
-#define DIO78_PORT 1
-#define DIO78_PIN 0
-//#define J12-12                    79  //             ENET_TXD1
-#define DIO79_PORT 1
-#define DIO79_PIN 1
-//#define J7-6                      80  //             MKS-SBASE	J7-6
-#define DIO80_PORT 0
-#define DIO80_PIN 14
-//#define EXP2-2                    81  //             MKS-SBASE 	on board SD card and EXP2
-#define DIO81_PORT 0
-#define DIO81_PIN  7
-//#define EXP2-1                    82  //             MKS-SBASE 	on board SD card and EXP2
-#define DIO82_PORT 0
-#define DIO82_PIN  8
-//#define EXP2-6                    83  //             MKS-SBASE 	on board SD card and EXP2
-#define DIO83_PORT 0
-#define DIO83_PIN  9
-/**
-//#define SD-CS                     81  //             on board SD card
-#define DIO81_PORT 0
-#define DIO81_PIN 6
-//#define SD-SCK                    82  //            on board SD card
-#define DIO82_PORT 0
-#define DIO82_PIN 7
-//#define SD-MISO                   83  //           on board SD card
-#define DIO83_PORT 0
-#define DIO83_PIN 8
-//#define SD-MOSI                   84  //           on board SD card
-#define DIO84_PORT 0
-#define DIO84_PIN 9
-*/
-
-#endif //__PINMAP_RE_ARM_H__
diff --git a/Marlin/src/HAL/HAL_LPC1768/pinmapping.cpp b/Marlin/src/HAL/HAL_LPC1768/pinmapping.cpp
new file mode 100644
index 0000000000..174ce8616f
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/pinmapping.cpp
@@ -0,0 +1,50 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (C) 2016 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 <http://www.gnu.org/licenses/>.
+ *
+ */
+
+#ifdef TARGET_LPC1768
+
+#include "../../inc/MarlinConfig.h"
+#include "../../gcode/parser.h"
+
+int16_t GET_PIN_MAP_INDEX(pin_t pin) {
+  const uint8_t pin_port = LPC1768_PIN_PORT(pin),
+                pin_pin = LPC1768_PIN_PIN(pin);
+  for (size_t i = 0; i < NUM_DIGITAL_PINS; ++i)
+    if (LPC1768_PIN_PORT(pin_map[i]) == pin_port && LPC1768_PIN_PIN(pin_map[i]) == pin_pin)
+      return i;
+
+  return -1;
+}
+
+int16_t PARSED_PIN_INDEX(char code, int16_t dval) {
+  if (parser.seenval(code)) {
+    int port, pin;
+    if (sscanf(parser.strval(code), "%d.%d", &port, &pin) == 2)
+      for (size_t i = 0; i < NUM_DIGITAL_PINS; ++i)
+        if (LPC1768_PIN_PORT(pin_map[i]) == port && LPC1768_PIN_PIN(pin_map[i]) == pin)
+          return i;
+  }
+
+  return dval;
+}
+
+#endif // TARGET_LPC1768
\ No newline at end of file
diff --git a/Marlin/src/HAL/HAL_LPC1768/pinmapping.h b/Marlin/src/HAL/HAL_LPC1768/pinmapping.h
index adff789b88..a514b83363 100644
--- a/Marlin/src/HAL/HAL_LPC1768/pinmapping.h
+++ b/Marlin/src/HAL/HAL_LPC1768/pinmapping.h
@@ -24,13 +24,195 @@
 #define __HAL_PINMAPPING_H__
 #include "../../core/macros.h"
 
-struct pin_data { uint8_t port, pin; };
-struct adc_pin_data { uint8_t port, pin, adc; };
+typedef int16_t pin_t;
 
-#if ENABLED(IS_REARM)
-  #include "pinmap_re_arm.h"
+const uint8_t PIN_FEATURE_INTERRUPT = 1 << 0;
+const uint8_t PIN_FEATURE_PWM = 1 << 1;
+constexpr uint8_t PIN_FEATURE_ADC(const int8_t chan) { return (((chan + 1) & 0b1111) << 2); }
+
+constexpr pin_t LPC1768_PIN(const uint8_t port, const uint8_t pin, const uint8_t feat = 0) {
+  return (((pin_t)feat << 8) | (((pin_t)port & 0x7) << 5) | ((pin_t)pin & 0x1F));
+}
+
+constexpr uint8_t LPC1768_PIN_PORT(const pin_t pin) { return ((uint8_t)((pin >> 5) & 0b111)); }
+constexpr uint8_t LPC1768_PIN_PIN(const pin_t pin) { return ((uint8_t)(pin & 0b11111)); }
+constexpr bool LPC1768_PIN_INTERRUPT(const pin_t pin) { return (((pin >> 8) & PIN_FEATURE_INTERRUPT) != 0); }
+constexpr bool LPC1768_PIN_PWM(const pin_t pin) { return (((pin >> 8) & PIN_FEATURE_PWM) != 0); }
+constexpr int8_t LPC1768_PIN_ADC(const pin_t pin) { return (int8_t)((pin >> 8) & 0b1111) - 1; }
+
+// ******************
+// Runtime pinmapping
+// ******************
+#if SERIAL_PORT != 3
+  const pin_t P0_0  = LPC1768_PIN(0,  0, PIN_FEATURE_INTERRUPT);
+  const pin_t P0_1  = LPC1768_PIN(0,  1, PIN_FEATURE_INTERRUPT);
+#endif
+#if SERIAL_PORT != 0
+  const pin_t P0_2  = LPC1768_PIN(0,  2, PIN_FEATURE_INTERRUPT | PIN_FEATURE_ADC(7));
+  const pin_t P0_3  = LPC1768_PIN(0,  3, PIN_FEATURE_INTERRUPT | PIN_FEATURE_ADC(6));
+#endif
+const pin_t P0_4  = LPC1768_PIN(0,  4, PIN_FEATURE_INTERRUPT);
+const pin_t P0_5  = LPC1768_PIN(0,  5, PIN_FEATURE_INTERRUPT);
+const pin_t P0_6  = LPC1768_PIN(0,  6, PIN_FEATURE_INTERRUPT);
+const pin_t P0_7  = LPC1768_PIN(0,  7, PIN_FEATURE_INTERRUPT);
+const pin_t P0_8  = LPC1768_PIN(0,  8, PIN_FEATURE_INTERRUPT);
+const pin_t P0_9  = LPC1768_PIN(0,  9, PIN_FEATURE_INTERRUPT);
+#if SERIAL_PORT != 2
+  const pin_t P0_10 = LPC1768_PIN(0, 10, PIN_FEATURE_INTERRUPT);
+  const pin_t P0_11 = LPC1768_PIN(0, 11, PIN_FEATURE_INTERRUPT);
+#endif
+#if SERIAL_PORT != 1
+  const pin_t P0_15 = LPC1768_PIN(0, 15, PIN_FEATURE_INTERRUPT);
+  const pin_t P0_16 = LPC1768_PIN(0, 16, PIN_FEATURE_INTERRUPT);
+#endif
+const pin_t P0_17 = LPC1768_PIN(0, 17, PIN_FEATURE_INTERRUPT);
+const pin_t P0_18 = LPC1768_PIN(0, 18, PIN_FEATURE_INTERRUPT);
+const pin_t P0_19 = LPC1768_PIN(0, 19, PIN_FEATURE_INTERRUPT);
+const pin_t P0_20 = LPC1768_PIN(0, 20, PIN_FEATURE_INTERRUPT);
+const pin_t P0_21 = LPC1768_PIN(0, 21, PIN_FEATURE_INTERRUPT);
+const pin_t P0_22 = LPC1768_PIN(0, 22, PIN_FEATURE_INTERRUPT);
+const pin_t P0_23 = LPC1768_PIN(0, 23, PIN_FEATURE_INTERRUPT | PIN_FEATURE_ADC(0));
+const pin_t P0_24 = LPC1768_PIN(0, 24, PIN_FEATURE_INTERRUPT | PIN_FEATURE_ADC(1));
+const pin_t P0_25 = LPC1768_PIN(0, 25, PIN_FEATURE_INTERRUPT | PIN_FEATURE_ADC(2));
+const pin_t P0_26 = LPC1768_PIN(0, 26, PIN_FEATURE_INTERRUPT | PIN_FEATURE_ADC(3));
+const pin_t P0_27 = LPC1768_PIN(0, 27, PIN_FEATURE_INTERRUPT);
+const pin_t P0_28 = LPC1768_PIN(0, 28, PIN_FEATURE_INTERRUPT);
+const pin_t P0_29 = LPC1768_PIN(0, 29, PIN_FEATURE_INTERRUPT);
+const pin_t P0_30 = LPC1768_PIN(0, 30, PIN_FEATURE_INTERRUPT);
+const pin_t P1_0  = LPC1768_PIN(1,  0);
+const pin_t P1_1  = LPC1768_PIN(1,  1);
+const pin_t P1_4  = LPC1768_PIN(1,  4);
+const pin_t P1_8  = LPC1768_PIN(1,  8);
+const pin_t P1_9  = LPC1768_PIN(1,  9);
+const pin_t P1_10 = LPC1768_PIN(1, 10);
+const pin_t P1_14 = LPC1768_PIN(1, 14);
+const pin_t P1_15 = LPC1768_PIN(1, 15);
+const pin_t P1_16 = LPC1768_PIN(1, 16);
+const pin_t P1_17 = LPC1768_PIN(1, 17);
+const pin_t P1_18 = LPC1768_PIN(1, 18, PIN_FEATURE_PWM);
+const pin_t P1_19 = LPC1768_PIN(1, 19);
+const pin_t P1_20 = LPC1768_PIN(1, 20, PIN_FEATURE_PWM);
+const pin_t P1_21 = LPC1768_PIN(1, 21, PIN_FEATURE_PWM);
+const pin_t P1_22 = LPC1768_PIN(1, 22);
+const pin_t P1_23 = LPC1768_PIN(1, 23, PIN_FEATURE_PWM);
+const pin_t P1_24 = LPC1768_PIN(1, 24, PIN_FEATURE_PWM);
+const pin_t P1_25 = LPC1768_PIN(1, 25);
+const pin_t P1_26 = LPC1768_PIN(1, 26, PIN_FEATURE_PWM);
+const pin_t P1_27 = LPC1768_PIN(1, 27);
+const pin_t P1_28 = LPC1768_PIN(1, 28);
+const pin_t P1_29 = LPC1768_PIN(1, 29);
+const pin_t P1_30 = LPC1768_PIN(1, 30, PIN_FEATURE_ADC(4));
+const pin_t P1_31 = LPC1768_PIN(1, 31, PIN_FEATURE_ADC(5));
+const pin_t P2_0  = LPC1768_PIN(2,  0, PIN_FEATURE_INTERRUPT | PIN_FEATURE_PWM);
+const pin_t P2_1  = LPC1768_PIN(2,  1, PIN_FEATURE_INTERRUPT | PIN_FEATURE_PWM);
+const pin_t P2_2  = LPC1768_PIN(2,  2, PIN_FEATURE_INTERRUPT | PIN_FEATURE_PWM);
+const pin_t P2_3  = LPC1768_PIN(2,  3, PIN_FEATURE_INTERRUPT | PIN_FEATURE_PWM);
+const pin_t P2_4  = LPC1768_PIN(2,  4, PIN_FEATURE_INTERRUPT | PIN_FEATURE_PWM);
+const pin_t P2_5  = LPC1768_PIN(2,  5, PIN_FEATURE_INTERRUPT | PIN_FEATURE_PWM);
+const pin_t P2_6  = LPC1768_PIN(2,  6, PIN_FEATURE_INTERRUPT);
+const pin_t P2_7  = LPC1768_PIN(2,  7, PIN_FEATURE_INTERRUPT);
+const pin_t P2_8  = LPC1768_PIN(2,  8, PIN_FEATURE_INTERRUPT);
+const pin_t P2_9  = LPC1768_PIN(2,  9, PIN_FEATURE_INTERRUPT);
+const pin_t P2_10 = LPC1768_PIN(2, 10, PIN_FEATURE_INTERRUPT);
+const pin_t P2_11 = LPC1768_PIN(2, 11, PIN_FEATURE_INTERRUPT);
+const pin_t P2_12 = LPC1768_PIN(2, 12, PIN_FEATURE_INTERRUPT);
+const pin_t P2_13 = LPC1768_PIN(2, 13, PIN_FEATURE_INTERRUPT);
+const pin_t P3_25 = LPC1768_PIN(3, 25, PIN_FEATURE_PWM);
+const pin_t P3_26 = LPC1768_PIN(3, 26, PIN_FEATURE_PWM);
+const pin_t P4_28 = LPC1768_PIN(4, 28);
+const pin_t P4_29 = LPC1768_PIN(4, 29);
+
+constexpr bool VALID_PIN(const pin_t p) {
+  return (
+    #if SERIAL_PORT == 0
+      (LPC1768_PIN_PORT(p) == 0 && LPC1768_PIN_PIN(p) <= 1)             ||
+      (LPC1768_PIN_PORT(p) == 0 && WITHIN(LPC1768_PIN_PIN(p), 4, 11))   ||
+    #elif SERIAL_PORT == 2
+      (LPC1768_PIN_PORT(p) == 0 && LPC1768_PIN_PIN(p) <= 9)             ||
+    #elif SERIAL_PORT == 3
+      (LPC1768_PIN_PORT(p) == 0 && WITHIN(LPC1768_PIN_PIN(p), 2, 11))   ||
+    #else
+      (LPC1768_PIN_PORT(p) == 0 && LPC1768_PIN_PIN(p) <= 11)            ||
+    #endif
+    #if SERIAL_PORT == 1
+      (LPC1768_PIN_PORT(p) == 0 && WITHIN(LPC1768_PIN_PIN(p), 17, 30))  ||
+    #else
+      (LPC1768_PIN_PORT(p) == 0 && WITHIN(LPC1768_PIN_PIN(p), 15, 30))  ||
+    #endif
+    (LPC1768_PIN_PORT(p) == 1 && LPC1768_PIN_PIN(p) == 1)             ||
+    (LPC1768_PIN_PORT(p) == 1 && LPC1768_PIN_PIN(p) == 4)             ||
+    (LPC1768_PIN_PORT(p) == 1 && WITHIN(LPC1768_PIN_PIN(p), 8, 10))   ||
+    (LPC1768_PIN_PORT(p) == 1 && WITHIN(LPC1768_PIN_PIN(p), 14, 31))  ||
+    (LPC1768_PIN_PORT(p) == 2 && LPC1768_PIN_PIN(p) <= 13)            ||
+    (LPC1768_PIN_PORT(p) == 3 && WITHIN(LPC1768_PIN_PIN(p), 25, 26))  ||
+    (LPC1768_PIN_PORT(p) == 4 && WITHIN(LPC1768_PIN_PIN(p), 28, 29))
+  );
+}
+
+constexpr bool PWM_PIN(const pin_t p) {
+  return (VALID_PIN(p) && LPC1768_PIN_PWM(p));
+}
+
+constexpr bool INTERRUPT_PIN(const pin_t p) {
+  return (VALID_PIN(p) && LPC1768_PIN_INTERRUPT(p));
+}
+
+#if SERIAL_PORT == 0
+  #define NUM_ANALOG_INPUTS 6
 #else
-  #error "HAL: LPC1768: No defined pin-mapping"
+  #define NUM_ANALOG_INPUTS 8
 #endif
 
+constexpr pin_t adc_pin_table[] = { 
+  P0_23, P0_24, P0_25, P0_26, P1_30, P1_31,
+  #if SERIAL_PORT != 0
+    P0_3, P0_2
+  #endif
+};
+
+constexpr pin_t analogInputToDigitalPin(const uint8_t p) {
+  return (p < COUNT(adc_pin_table) ? adc_pin_table[p] : -1);
+}
+
+constexpr int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p) {
+  return (VALID_PIN(p) ? LPC1768_PIN_ADC(p) : -1);
+}
+
+// P0.6 thru P0.9 are for the onboard SD card
+// P0.29 and P0.30 are for the USB port
+#define HAL_SENSITIVE_PINS P0_6, P0_7, P0_8, P0_9, P0_29, P0_30
+
+// Pin map for M43 and M226
+const pin_t pin_map[] = {
+  #if SERIAL_PORT != 3
+    P0_0,  P0_1,
+  #endif
+  #if SERIAL_PORT != 0
+    P0_2,  P0_3,
+  #endif
+  P0_4,  P0_5,  P0_6,  P0_7,  P0_8,  P0_9,
+  #if SERIAL_PORT != 2
+    P0_10, P0_11,
+  #endif
+  #if SERIAL_PORT != 1
+    P0_15, P0_16,
+  #endif
+  P0_17, P0_18, P0_19, P0_20, P0_21, P0_22, P0_23, P0_24,
+  P0_25, P0_26, P0_27, P0_28, P0_29, P0_30,
+  P1_0,  P1_1,  P1_4,  P1_8,  P1_9,  P1_10, P1_14, P1_15,
+  P1_16, P1_17, P1_18, P1_19, P1_20, P1_21, P1_22, P1_23,
+  P1_24, P1_25, P1_26, P1_27, P1_28, P1_29, P1_30, P1_31,
+  P2_0,  P2_1,  P2_2,  P2_3,  P2_4,  P2_5,  P2_6,  P2_7,
+  P2_8,  P2_9,  P2_10, P2_11, P2_12, P2_13,
+  P3_25, P3_26,
+  P4_28, P4_29
+};
+
+#define NUM_DIGITAL_PINS COUNT(pin_map)
+
+#define GET_PIN_MAP_PIN(i) (WITHIN(i, 0, (int)NUM_DIGITAL_PINS - 1) ? pin_map[i] : -1)
+
+int16_t GET_PIN_MAP_INDEX(pin_t pin);
+int16_t PARSED_PIN_INDEX(char code, int16_t dval = 0);
+                           
 #endif // __HAL_PINMAPPING_H__
diff --git a/Marlin/src/HAL/HAL_LPC1768/pinsDebug_Re_ARM.h b/Marlin/src/HAL/HAL_LPC1768/pinsDebug_LPC1768.h
similarity index 63%
rename from Marlin/src/HAL/HAL_LPC1768/pinsDebug_Re_ARM.h
rename to Marlin/src/HAL/HAL_LPC1768/pinsDebug_LPC1768.h
index a93f7c0767..e8d4af265c 100644
--- a/Marlin/src/HAL/HAL_LPC1768/pinsDebug_Re_ARM.h
+++ b/Marlin/src/HAL/HAL_LPC1768/pinsDebug_LPC1768.h
@@ -21,29 +21,27 @@
  */
 
 /**
- * Support routines for Re-ARM board
+ * Support routines for LPC1768
 */
 
-bool pin_Re_ARM_output;
-bool pin_Re_ARM_analog;
-int8_t pin_Re_ARM_pin;
-
-void get_pin_info(int8_t pin) {
+// active ADC function/mode/code values for PINSEL registers
+int8_t ADC_pin_mode(pin_t pin) {
+  uint8_t pin_port = LPC1768_PIN_PORT(pin);
+  uint8_t pin_port_pin = LPC1768_PIN_PIN(pin);
+  return (pin_port == 0 && pin_port_pin == 2  ? 2 :
+          pin_port == 0 && pin_port_pin == 3  ? 2 :
+          pin_port == 0 && pin_port_pin == 23 ? 1 :
+          pin_port == 0 && pin_port_pin == 24 ? 1 :
+          pin_port == 0 && pin_port_pin == 25 ? 1 :
+          pin_port == 0 && pin_port_pin == 26 ? 1 :
+          pin_port == 1 && pin_port_pin == 30 ? 3 :
+          pin_port == 1 && pin_port_pin == 31 ? 3 : -1);
+}
 
-if (pin == 7) return;
-  pin_Re_ARM_analog = 0;
-  pin_Re_ARM_pin = pin;
-  int8_t pin_port = pin_map[pin].port;
-  int8_t pin_port_pin = pin_map[pin].pin;
-  // active ADC function/mode/code values for PINSEL registers
-  int8_t ADC_pin_mode = pin_port == 0 && pin_port_pin == 2  ? 2 :
-                        pin_port == 0 && pin_port_pin == 3  ? 2 :
-                        pin_port == 0 && pin_port_pin == 23 ? 1 :
-                        pin_port == 0 && pin_port_pin == 24 ? 1 :
-                        pin_port == 0 && pin_port_pin == 25 ? 1 :
-                        pin_port == 0 && pin_port_pin == 26 ? 1 :
-                        pin_port == 1 && pin_port_pin == 30 ? 3 :
-                        pin_port == 1 && pin_port_pin == 31 ? 3 : -1;
+int8_t get_pin_mode(pin_t pin) {
+  if (!VALID_PIN(pin)) return -1;
+  uint8_t pin_port = LPC1768_PIN_PORT(pin);
+  uint8_t pin_port_pin = LPC1768_PIN_PIN(pin);
   //get appropriate PINSEL register
   volatile uint32_t * pinsel_reg = (pin_port == 0 && pin_port_pin <= 15) ? &LPC_PINCON->PINSEL0 :
                                    (pin_port == 0)                       ? &LPC_PINCON->PINSEL1 :
@@ -52,16 +50,22 @@ if (pin == 7) return;
                                     pin_port == 2                        ? &LPC_PINCON->PINSEL4 :
                                     pin_port == 3                        ? &LPC_PINCON->PINSEL7 : &LPC_PINCON->PINSEL9;
   uint8_t pinsel_start_bit = pin_port_pin > 15 ? 2 * (pin_port_pin - 16) : 2 * pin_port_pin;
-  uint8_t pin_mode = (uint8_t) ((*pinsel_reg >> pinsel_start_bit) & 0x3);
+  int8_t pin_mode = (int8_t) ((*pinsel_reg >> pinsel_start_bit) & 0x3);
+  return pin_mode;
+}
+
+bool GET_PINMODE(pin_t pin) {
+  int8_t pin_mode = get_pin_mode(pin);
+  if (pin_mode == -1 || (pin_mode && pin_mode == ADC_pin_mode(pin))) // found an invalid pin or active analog pin
+    return false;
+
   uint32_t * FIO_reg[5] PROGMEM = {(uint32_t*) 0x2009C000,(uint32_t*)  0x2009C020,(uint32_t*)  0x2009C040,(uint32_t*)  0x2009C060,(uint32_t*)  0x2009C080};
-  pin_Re_ARM_output = (*FIO_reg[pin_map[pin].port] >> pin_map[pin].pin) & 1; //input/output state except if active ADC
+  return ((*FIO_reg[LPC1768_PIN_PORT(pin)] >> LPC1768_PIN_PIN(pin) & 1) != 0); //input/output state
+}
 
-  if (pin_mode) {  // if function/mode/code value not 0 then could be an active analog channel
-    if (ADC_pin_mode == pin_mode) {  // found an active analog pin
-      pin_Re_ARM_output = 0;
-      pin_Re_ARM_analog = 1;
-    }
-  }
+bool GET_ARRAY_IS_DIGITAL(pin_t pin) {
+  int8_t pin_mode = get_pin_mode(pin);
+  return (pin_mode != -1 && (!get_pin_mode(pin) || pin_mode != ADC_pin_mode(pin)));
 }
 
 /**
@@ -70,9 +74,7 @@ if (pin == 7) return;
 
 #define pwm_details(pin) pin = pin    // do nothing  // print PWM details
 #define pwm_status(pin) false //Print a pin's PWM status. Return true if it's currently a PWM pin.
-#define GET_PIN_INFO(pin) get_pin_info(pin)
 #define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P) >= 0 ? 1 : 0)
-#define GET_PINMODE(pin) pin_Re_ARM_output
 #define digitalRead_mod(p)  digitalRead(p)
 #define digitalPinToPort_DEBUG(p)  0
 #define digitalPinToBitMask_DEBUG(pin) 0
@@ -81,4 +83,4 @@ if (pin == 7) return;
 #define NAME_FORMAT(p) PSTR("%-##p##s")
 //  #define PRINT_ARRAY_NAME(x)  do {sprintf_P(buffer, NAME_FORMAT(MAX_NAME_LENGTH) , pin_array[x].name); SERIAL_ECHO(buffer);} while (0)
 #define PRINT_ARRAY_NAME(x)  do {sprintf_P(buffer, PSTR("%-35s") , pin_array[x].name); SERIAL_ECHO(buffer);} while (0)
-#define GET_ARRAY_IS_DIGITAL(x)  !pin_Re_ARM_analog
+#define PRINT_PIN(p) do {sprintf_P(buffer, PSTR("%d.%02d "), LPC1768_PIN_PORT(p), LPC1768_PIN_PIN(p)); SERIAL_ECHO(buffer);} while (0)
diff --git a/Marlin/src/HAL/HAL_LPC1768/spi_pins.h b/Marlin/src/HAL/HAL_LPC1768/spi_pins.h
index 6312f1ff60..1e8ff21617 100644
--- a/Marlin/src/HAL/HAL_LPC1768/spi_pins.h
+++ b/Marlin/src/HAL/HAL_LPC1768/spi_pins.h
@@ -31,13 +31,13 @@
 //#define MOSI_PIN          P0_9
 //#define SS_PIN            P0_6
 /** external */
-#define SCK_PIN           52 //P0_15
-#define MISO_PIN          50 //P0_17
-#define MOSI_PIN          51 //P0_18
-#define SS_PIN            53 //P1_23
+#define SCK_PIN           P0_15
+#define MISO_PIN          P0_17
+#define MOSI_PIN          P0_18
+#define SS_PIN            P1_23
 #define SDSS              SS_PIN
 
-#if (defined(IS_REARM) && !(defined(LPC_SOFTWARE_SPI)))   // signal LCDs that they need to use the hardware SPI
+#if (defined(TARGET_LPC1768) && !(defined(LPC_SOFTWARE_SPI)))   // signal LCDs that they need to use the hardware SPI
   #define SHARED_SPI
 #endif
 
diff --git a/Marlin/src/HAL/HAL_STM32F1/HAL_Stm32f1.h b/Marlin/src/HAL/HAL_STM32F1/HAL_Stm32f1.h
index 590b32856f..24b8801da3 100644
--- a/Marlin/src/HAL/HAL_STM32F1/HAL_Stm32f1.h
+++ b/Marlin/src/HAL/HAL_STM32F1/HAL_Stm32f1.h
@@ -98,6 +98,8 @@
 // Types
 // --------------------------------------------------------------------------
 
+typedef int8_t pin_t;
+
 // --------------------------------------------------------------------------
 // Public Variables
 // --------------------------------------------------------------------------
@@ -192,4 +194,8 @@ void HAL_enable_AdcFreerun(void);
 
 */
 
+#define GET_PIN_MAP_PIN(index) index
+#define GET_PIN_MAP_INDEX(pin) pin
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
+
 #endif // _HAL_STM32F1_H
diff --git a/Marlin/src/HAL/HAL_STM32F1/HAL_timers_Stm32f1.h b/Marlin/src/HAL/HAL_STM32F1/HAL_timers_Stm32f1.h
index 7065ebdb23..df155047ae 100644
--- a/Marlin/src/HAL/HAL_STM32F1/HAL_timers_Stm32f1.h
+++ b/Marlin/src/HAL/HAL_STM32F1/HAL_timers_Stm32f1.h
@@ -43,7 +43,7 @@
  */
 #define FORCE_INLINE __attribute__((always_inline)) inline
 
-#define HAL_TIMER_TYPE uint16_t
+typedef uint16_t timer_t;
 #define HAL_TIMER_TYPE_MAX 0xFFFF
 
 #define STEP_TIMER_NUM 5  // index of timer to use for stepper
@@ -126,8 +126,8 @@ static FORCE_INLINE void HAL_timer_set_count (uint8_t timer_num, uint32_t count)
   }
 }
 
-static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count (uint8_t timer_num) {
-  HAL_TIMER_TYPE temp;
+static FORCE_INLINE timer_t HAL_timer_get_count (uint8_t timer_num) {
+  timer_t temp;
   switch (timer_num) {
   case STEP_TIMER_NUM:
     temp = StepperTimer.getCompare(STEP_TIMER_CHAN);
@@ -142,8 +142,8 @@ static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count (uint8_t timer_num) {
   return temp;
 }
 
-static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_current_count(uint8_t timer_num) {
-  HAL_TIMER_TYPE temp;
+static FORCE_INLINE timer_t HAL_timer_get_current_count(uint8_t timer_num) {
+  timer_t temp;
   switch (timer_num) {
   case STEP_TIMER_NUM:
     temp = StepperTimer.getCount();
diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/HAL_Teensy.h b/Marlin/src/HAL/HAL_TEENSY35_36/HAL_Teensy.h
index 13526f10f8..0ac8244e04 100644
--- a/Marlin/src/HAL/HAL_TEENSY35_36/HAL_Teensy.h
+++ b/Marlin/src/HAL/HAL_TEENSY35_36/HAL_Teensy.h
@@ -64,6 +64,8 @@
 
 #define HAL_SERVO_LIB libServo
 
+typedef int8_t pin_t;
+
 #ifndef analogInputToDigitalPin
   #define analogInputToDigitalPin(p) ((p < 12u) ? (p) + 54u : -1)
 #endif
@@ -139,6 +141,10 @@ uint16_t HAL_adc_get_result(void);
   //void HAL_disable_AdcFreerun(uint8_t chan);
 */
 
+#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/HAL_TEENSY35_36/HAL_timers_Teensy.h b/Marlin/src/HAL/HAL_TEENSY35_36/HAL_timers_Teensy.h
index e48ea54604..8139a33ad8 100644
--- a/Marlin/src/HAL/HAL_TEENSY35_36/HAL_timers_Teensy.h
+++ b/Marlin/src/HAL/HAL_TEENSY35_36/HAL_timers_Teensy.h
@@ -40,7 +40,7 @@
 
 #define FORCE_INLINE __attribute__((always_inline)) inline
 
-#define HAL_TIMER_TYPE uint32_t
+typedef uint32_t timer_t;
 #define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
 
 #define STEP_TIMER_NUM 0
@@ -82,7 +82,7 @@ static FORCE_INLINE void HAL_timer_set_count(const uint8_t timer_num, const uint
   }
 }
 
-static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count(const uint8_t timer_num) {
+static FORCE_INLINE timer_t HAL_timer_get_count(const uint8_t timer_num) {
   switch(timer_num) {
     case 0: return FTM0_C0V;
     case 1: return FTM1_C0V;
diff --git a/Marlin/src/HAL/HAL_pinsDebug.h b/Marlin/src/HAL/HAL_pinsDebug.h
index 53d718f6f1..17c2c8eeb3 100644
--- a/Marlin/src/HAL/HAL_pinsDebug.h
+++ b/Marlin/src/HAL/HAL_pinsDebug.h
@@ -30,7 +30,7 @@
 #elif IS_32BIT_TEENSY
   #include "HAL_TEENSY35_36/HAL_pinsDebug_Teensy.h"
 #elif defined(TARGET_LPC1768)
-  #include "HAL_LPC1768/pinsDebug_Re_ARM.h"
+  #include "HAL_LPC1768/pinsDebug_LPC1768.h"
 #else
   #error Unsupported Platform!
 #endif
diff --git a/Marlin/src/Marlin.cpp b/Marlin/src/Marlin.cpp
index 75f10d0b83..dc0fb6c7be 100644
--- a/Marlin/src/Marlin.cpp
+++ b/Marlin/src/Marlin.cpp
@@ -297,10 +297,13 @@ void setup_powerhold() {
 /**
  * Sensitive pin test for M42, M226
  */
-bool pin_is_protected(const int8_t pin) {
-  static const int8_t sensitive_pins[] PROGMEM = SENSITIVE_PINS;
-  for (uint8_t i = 0; i < COUNT(sensitive_pins); i++)
-    if (pin == (int8_t)pgm_read_byte(&sensitive_pins[i])) return true;
+bool pin_is_protected(const pin_t pin) {
+  static const pin_t sensitive_pins[] PROGMEM = SENSITIVE_PINS;
+  for (uint8_t i = 0; i < COUNT(sensitive_pins); i++) {
+    pin_t sensitive_pin;
+    memcpy_P(&sensitive_pin, &sensitive_pins[i], sizeof(pin_t));
+    if (pin == sensitive_pin) return true;
+  }
   return false;
 }
 
diff --git a/Marlin/src/Marlin.h b/Marlin/src/Marlin.h
index a1b79208a4..6930996024 100644
--- a/Marlin/src/Marlin.h
+++ b/Marlin/src/Marlin.h
@@ -216,7 +216,7 @@ extern millis_t max_inactive_time, stepper_inactive_time;
   extern int lpq_len;
 #endif
 
-bool pin_is_protected(const int8_t pin);
+bool pin_is_protected(const pin_t pin);
 
 #if HAS_SUICIDE
   inline void suicide() { OUT_WRITE(SUICIDE_PIN, LOW); }
diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp
index b46f398d71..a02d943bd6 100644
--- a/Marlin/src/core/serial.cpp
+++ b/Marlin/src/core/serial.cpp
@@ -42,6 +42,7 @@ void serial_echopair_P(const char* s_P, int v)           { serialprintPGM(s_P);
 void serial_echopair_P(const char* s_P, long v)          { serialprintPGM(s_P); SERIAL_ECHO(v); }
 void serial_echopair_P(const char* s_P, float v)         { serialprintPGM(s_P); SERIAL_ECHO(v); }
 void serial_echopair_P(const char* s_P, double v)        { serialprintPGM(s_P); SERIAL_ECHO(v); }
+void serial_echopair_P(const char* s_P, unsigned int v)  { serialprintPGM(s_P); SERIAL_ECHO(v); }
 void serial_echopair_P(const char* s_P, unsigned long v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
 
 void serial_spaces(uint8_t count) { count *= (PROPORTIONAL_FONT_RATIO); while (count--) MYSERIAL.write(' '); }
diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h
index 6642a3ce64..07d3ac1734 100644
--- a/Marlin/src/core/serial.h
+++ b/Marlin/src/core/serial.h
@@ -106,7 +106,6 @@ void serial_echopair_P(const char* s_P, double v);
 void serial_echopair_P(const char* s_P, unsigned int v);
 void serial_echopair_P(const char* s_P, unsigned long v);
 FORCE_INLINE void serial_echopair_P(const char* s_P, uint8_t v) { serial_echopair_P(s_P, (int)v); }
-FORCE_INLINE void serial_echopair_P(const char* s_P, uint16_t v) { serial_echopair_P(s_P, (int)v); }
 FORCE_INLINE void serial_echopair_P(const char* s_P, bool v) { serial_echopair_P(s_P, (int)v); }
 FORCE_INLINE void serial_echopair_P(const char* s_P, void *v) { serial_echopair_P(s_P, (unsigned long)v); }
 
diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp
index e3f2021f55..9b7fc47538 100644
--- a/Marlin/src/gcode/config/M43.cpp
+++ b/Marlin/src/gcode/config/M43.cpp
@@ -36,11 +36,12 @@
 inline void toggle_pins() {
   const bool I_flag = parser.boolval('I');
   const int repeat = parser.intval('R', 1),
-            start = parser.intval('S'),
-            end = parser.intval('E', NUM_DIGITAL_PINS - 1),
+            start = PARSED_PIN_INDEX('S', 0),
+            end = PARSED_PIN_INDEX('E', NUM_DIGITAL_PINS - 1),
             wait = parser.intval('W', 500);
 
-  for (uint8_t pin = start; pin <= end; pin++) {
+  for (uint8_t i = start; i <= end; i++) {
+    pin_t pin = GET_PIN_MAP_PIN(i);
     //report_pin_state_extended(pin, I_flag, false);
     if (!VALID_PIN(pin)) continue;
     if (!I_flag && pin_is_protected(pin)) {
@@ -258,7 +259,7 @@ void GcodeSuite::M43() {
   }
 
   // Get the range of pins to test or watch
-  const uint8_t first_pin = parser.byteval('P'),
+  const uint8_t first_pin = PARSED_PIN_INDEX('P', 0),
                 last_pin = parser.seenval('P') ? first_pin : NUM_DIGITAL_PINS - 1;
 
   if (first_pin > last_pin) return;
@@ -269,7 +270,8 @@ void GcodeSuite::M43() {
   if (parser.boolval('W')) {
     SERIAL_PROTOCOLLNPGM("Watching pins");
     uint8_t pin_state[last_pin - first_pin + 1];
-    for (int8_t pin = first_pin; pin <= last_pin; pin++) {
+    for (uint8_t i = first_pin; i <= last_pin; i++) {
+      pin_t pin = GET_PIN_MAP_PIN(i);
       if (!VALID_PIN(pin)) continue;
       if (pin_is_protected(pin) && !ignore_protection) continue;
       pinMode(pin, INPUT_PULLUP);
@@ -279,7 +281,7 @@ void GcodeSuite::M43() {
           pin_state[pin - first_pin] = analogRead(DIGITAL_PIN_TO_ANALOG_PIN(pin)); // int16_t pin_state[...]
         else
       //*/
-          pin_state[pin - first_pin] = digitalRead(pin);
+          pin_state[i - first_pin] = digitalRead(pin);
     }
 
     #if HAS_RESUME_CONTINUE
@@ -288,7 +290,8 @@ void GcodeSuite::M43() {
     #endif
 
     for (;;) {
-      for (int8_t pin = first_pin; pin <= last_pin; pin++) {
+      for (uint8_t i = first_pin; i <= last_pin; i++) {
+        pin_t pin = GET_PIN_MAP_PIN(i);
         if (!VALID_PIN(pin)) continue;
         if (pin_is_protected(pin) && !ignore_protection) continue;
         const byte val =
@@ -298,9 +301,9 @@ void GcodeSuite::M43() {
               :
           //*/
             digitalRead(pin);
-        if (val != pin_state[pin - first_pin]) {
+        if (val != pin_state[i - first_pin]) {
           report_pin_state_extended(pin, ignore_protection, false);
-          pin_state[pin - first_pin] = val;
+          pin_state[i - first_pin] = val;
         }
       }
 
@@ -317,8 +320,10 @@ void GcodeSuite::M43() {
   }
 
   // Report current state of selected pin(s)
-  for (uint8_t pin = first_pin; pin <= last_pin; pin++)
+  for (uint8_t i = first_pin; i <= last_pin; i++) {
+    pin_t pin = GET_PIN_MAP_PIN(i);
     if (VALID_PIN(pin)) report_pin_state_extended(pin, ignore_protection, true);
+  }
 }
 
 #endif // PINS_DEBUGGING
diff --git a/Marlin/src/gcode/control/M226.cpp b/Marlin/src/gcode/control/M226.cpp
index c0f5111e90..889bac118c 100644
--- a/Marlin/src/gcode/control/M226.cpp
+++ b/Marlin/src/gcode/control/M226.cpp
@@ -29,16 +29,17 @@
  */
 void GcodeSuite::M226() {
   if (parser.seen('P')) {
-    const int pin_number = parser.value_int(),
+    const int pin_number = PARSED_PIN_INDEX('P', 0),
               pin_state = parser.intval('S', -1); // required pin state - default is inverted
+    const pin_t pin = GET_PIN_MAP_PIN(pin_number);
 
-    if (WITHIN(pin_state, -1, 1) && pin_number > -1 && !pin_is_protected(pin_number)) {
+    if (WITHIN(pin_state, -1, 1) && pin > -1 && !pin_is_protected(pin)) {
 
       int target = LOW;
 
       stepper.synchronize();
 
-      pinMode(pin_number, INPUT);
+      pinMode(pin, INPUT);
       switch (pin_state) {
         case 1:
           target = HIGH;
@@ -47,12 +48,12 @@ void GcodeSuite::M226() {
           target = LOW;
           break;
         case -1:
-          target = !digitalRead(pin_number);
+          target = !digitalRead(pin);
           break;
       }
 
-      while (digitalRead(pin_number) != target) idle();
+      while (digitalRead(pin) != target) idle();
 
-    } // pin_state -1 0 1 && pin_number > -1
+    } // pin_state -1 0 1 && pin > -1
   } // parser.seen('P')
 }
diff --git a/Marlin/src/gcode/control/M42.cpp b/Marlin/src/gcode/control/M42.cpp
index 44a1892ec3..af5886b011 100644
--- a/Marlin/src/gcode/control/M42.cpp
+++ b/Marlin/src/gcode/control/M42.cpp
@@ -34,21 +34,22 @@ void GcodeSuite::M42() {
   if (!parser.seenval('S')) return;
   const byte pin_status = parser.value_byte();
 
-  const int pin_number = parser.intval('P', LED_PIN);
+  int pin_number = PARSED_PIN_INDEX('P', GET_PIN_MAP_INDEX(LED_PIN));
   if (pin_number < 0) return;
 
-  if (pin_is_protected(pin_number)) {
+  const pin_t pin = GET_PIN_MAP_PIN(pin_number);
+  if (pin_is_protected(pin)) {
     SERIAL_ERROR_START();
     SERIAL_ERRORLNPGM(MSG_ERR_PROTECTED_PIN);
     return;
   }
 
-  pinMode(pin_number, OUTPUT);
-  digitalWrite(pin_number, pin_status);
-  analogWrite(pin_number, pin_status);
+  pinMode(pin, OUTPUT);
+  digitalWrite(pin, pin_status);
+  analogWrite(pin, pin_status);
 
   #if FAN_COUNT > 0
-    switch (pin_number) {
+    switch (pin) {
       #if HAS_FAN0
         case FAN_PIN: fanSpeeds[0] = pin_status; break;
       #endif
diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h
index dcd019a99c..d872b21d8e 100644
--- a/Marlin/src/gcode/parser.h
+++ b/Marlin/src/gcode/parser.h
@@ -293,15 +293,16 @@ public:
   void unknown_command_error();
 
   // Provide simple value accessors with default option
-  FORCE_INLINE static float    floatval(const char c, const float dval=0.0)   { return seenval(c) ? value_float()        : dval; }
-  FORCE_INLINE static bool     boolval(const char c)                          { return seenval(c) ? value_bool()         : seen(c); }
-  FORCE_INLINE static uint8_t  byteval(const char c, const uint8_t dval=0)    { return seenval(c) ? value_byte()         : dval; }
-  FORCE_INLINE static int16_t  intval(const char c, const int16_t dval=0)     { return seenval(c) ? value_int()          : dval; }
-  FORCE_INLINE static uint16_t ushortval(const char c, const uint16_t dval=0) { return seenval(c) ? value_ushort()       : dval; }
-  FORCE_INLINE static int32_t  longval(const char c, const int32_t dval=0)    { return seenval(c) ? value_long()         : dval; }
-  FORCE_INLINE static uint32_t ulongval(const char c, const uint32_t dval=0)  { return seenval(c) ? value_ulong()        : dval; }
-  FORCE_INLINE static float    linearval(const char c, const float dval=0.0)  { return seenval(c) ? value_linear_units() : dval; }
-  FORCE_INLINE static float    celsiusval(const char c, const float dval=0.0) { return seenval(c) ? value_celsius()      : dval; }
+  FORCE_INLINE static float       floatval(const char c, const float dval=0.0)   { return seenval(c) ? value_float()        : dval; }
+  FORCE_INLINE static bool        boolval(const char c)                          { return seenval(c) ? value_bool()         : seen(c); }
+  FORCE_INLINE static uint8_t     byteval(const char c, const uint8_t dval=0)    { return seenval(c) ? value_byte()         : dval; }
+  FORCE_INLINE static int16_t     intval(const char c, const int16_t dval=0)     { return seenval(c) ? value_int()          : dval; }
+  FORCE_INLINE static uint16_t    ushortval(const char c, const uint16_t dval=0) { return seenval(c) ? value_ushort()       : dval; }
+  FORCE_INLINE static int32_t     longval(const char c, const int32_t dval=0)    { return seenval(c) ? value_long()         : dval; }
+  FORCE_INLINE static uint32_t    ulongval(const char c, const uint32_t dval=0)  { return seenval(c) ? value_ulong()        : dval; }
+  FORCE_INLINE static float       linearval(const char c, const float dval=0.0)  { return seenval(c) ? value_linear_units() : dval; }
+  FORCE_INLINE static float       celsiusval(const char c, const float dval=0.0) { return seenval(c) ? value_celsius()      : dval; }
+  FORCE_INLINE static const char* strval(const char c)                           { return seenval(c) ? value_ptr            : NULL; }
 
 };
 
diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp
index eb856af2a7..22c9ad3d92 100644
--- a/Marlin/src/module/stepper.cpp
+++ b/Marlin/src/module/stepper.cpp
@@ -110,9 +110,9 @@ volatile uint32_t Stepper::step_events_completed = 0; // The number of step even
 
 #if ENABLED(LIN_ADVANCE)
 
-  constexpr HAL_TIMER_TYPE ADV_NEVER = HAL_TIMER_TYPE_MAX;
+  constexpr timer_t ADV_NEVER = HAL_TIMER_TYPE_MAX;
 
-  HAL_TIMER_TYPE Stepper::nextMainISR = 0,
+  timer_t Stepper::nextMainISR = 0,
          Stepper::nextAdvanceISR = ADV_NEVER,
          Stepper::eISR_Rate = ADV_NEVER;
 
@@ -127,9 +127,9 @@ volatile uint32_t Stepper::step_events_completed = 0; // The number of step even
    * This fix isn't perfect and may lose steps - but better than locking up completely
    * in future the planner should slow down if advance stepping rate would be too high
    */
-  FORCE_INLINE HAL_TIMER_TYPE adv_rate(const int steps, const HAL_TIMER_TYPE timer, const uint8_t loops) {
+  FORCE_INLINE timer_t adv_rate(const int steps, const timer_t timer, const uint8_t loops) {
     if (steps) {
-      const HAL_TIMER_TYPE rate = (timer * loops) / abs(steps);
+      const timer_t rate = (timer * loops) / abs(steps);
       //return constrain(rate, 1, ADV_NEVER - 1)
       return rate ? rate : 1;
     }
@@ -147,9 +147,9 @@ volatile signed char Stepper::count_direction[NUM_AXIS] = { 1, 1, 1, 1 };
   long Stepper::counter_m[MIXING_STEPPERS];
 #endif
 
-HAL_TIMER_TYPE Stepper::acc_step_rate; // needed for deceleration start point
+timer_t Stepper::acc_step_rate; // needed for deceleration start point
 uint8_t Stepper::step_loops, Stepper::step_loops_nominal;
-HAL_TIMER_TYPE Stepper::OCR1A_nominal;
+timer_t Stepper::OCR1A_nominal;
 
 volatile long Stepper::endstops_trigsteps[XYZ];
 
@@ -313,7 +313,7 @@ HAL_STEP_TIMER_ISR {
 
 void Stepper::isr() {
 
-  HAL_TIMER_TYPE ocr_val;
+  timer_t ocr_val;
 
   #define ENDSTOP_NOMINAL_OCR_VAL 1500 * HAL_TICKS_PER_US    // check endstops every 1.5ms to guarantee two stepper ISRs within 5ms for BLTouch
   #define OCR_VAL_TOLERANCE 500 * HAL_TICKS_PER_US           // First max delay is 2.0ms, last min delay is 0.5ms, all others 1.5ms
@@ -649,7 +649,7 @@ void Stepper::isr() {
     NOMORE(acc_step_rate, current_block->nominal_rate);
 
     // step_rate to timer interval
-    const HAL_TIMER_TYPE timer = calc_timer(acc_step_rate);
+    const timer_t timer = calc_timer(acc_step_rate);
 
     SPLIT(timer);  // split step into multiple ISRs if larger than  ENDSTOP_NOMINAL_OCR_VAL
     _NEXT_ISR(ocr_val);
@@ -671,7 +671,7 @@ void Stepper::isr() {
     #endif // LIN_ADVANCE
   }
   else if (step_events_completed > (uint32_t)current_block->decelerate_after) {
-    HAL_TIMER_TYPE step_rate;
+    timer_t step_rate;
     #ifdef CPU_32_BIT
       MultiU32X24toH32(step_rate, deceleration_time, current_block->acceleration_rate);
     #else
@@ -686,7 +686,7 @@ void Stepper::isr() {
       step_rate = current_block->final_rate;
 
     // step_rate to timer interval
-    const HAL_TIMER_TYPE timer = calc_timer(step_rate);
+    const timer_t timer = calc_timer(step_rate);
 
     SPLIT(timer);  // split step into multiple ISRs if larger than  ENDSTOP_NOMINAL_OCR_VAL
     _NEXT_ISR(ocr_val);
@@ -726,7 +726,7 @@ void Stepper::isr() {
   #if DISABLED(LIN_ADVANCE)
     #ifdef CPU_32_BIT
       // Make sure stepper interrupt does not monopolise CPU by adjusting count to give about 8 us room
-      HAL_TIMER_TYPE stepper_timer_count = HAL_timer_get_count(STEP_TIMER_NUM),
+      timer_t stepper_timer_count = HAL_timer_get_count(STEP_TIMER_NUM),
                      stepper_timer_current_count = HAL_timer_get_current_count(STEP_TIMER_NUM) + 8 * HAL_TICKS_PER_US;
       HAL_timer_set_count(STEP_TIMER_NUM, max(stepper_timer_count, stepper_timer_current_count));
     #else
diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h
index 6ea5517364..aa11ef929b 100644
--- a/Marlin/src/module/stepper.h
+++ b/Marlin/src/module/stepper.h
@@ -91,7 +91,7 @@ class Stepper {
     static volatile uint32_t step_events_completed; // The number of step events executed in the current block
 
     #if ENABLED(LIN_ADVANCE)
-      static HAL_TIMER_TYPE nextMainISR, nextAdvanceISR, eISR_Rate;
+      static timer_t nextMainISR, nextAdvanceISR, eISR_Rate;
       #define _NEXT_ISR(T) nextMainISR = T
 
       static volatile int e_steps[E_STEPPERS];
@@ -106,9 +106,9 @@ class Stepper {
 
     static long acceleration_time, deceleration_time;
     //unsigned long accelerate_until, decelerate_after, acceleration_rate, initial_rate, final_rate, nominal_rate;
-    static HAL_TIMER_TYPE acc_step_rate; // needed for deceleration start point
+    static timer_t acc_step_rate; // needed for deceleration start point
     static uint8_t step_loops, step_loops_nominal;
-    static HAL_TIMER_TYPE OCR1A_nominal;
+    static timer_t OCR1A_nominal;
 
     static volatile long endstops_trigsteps[XYZ];
     static volatile long endstops_stepsTotal, endstops_stepsDone;
@@ -259,8 +259,8 @@ class Stepper {
 
   private:
 
-    static FORCE_INLINE HAL_TIMER_TYPE calc_timer(HAL_TIMER_TYPE step_rate) {
-      HAL_TIMER_TYPE timer;
+    static FORCE_INLINE timer_t calc_timer(timer_t step_rate) {
+      timer_t timer;
 
       NOMORE(step_rate, MAX_STEP_FREQUENCY);
 
diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h
index 09a0d4e817..fd7285ca9e 100644
--- a/Marlin/src/pins/pins.h
+++ b/Marlin/src/pins/pins.h
@@ -665,7 +665,11 @@
   #define _Z2_PINS Z2_STEP_PIN, Z2_DIR_PIN, Z2_ENABLE_PIN,
 #endif
 
-#define SENSITIVE_PINS { 0, 1, \
+#ifndef HAL_SENSITIVE_PINS
+#define HAL_SENSITIVE_PINS
+#endif
+
+#define SENSITIVE_PINS { \
     X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_MIN_PIN, X_MAX_PIN, \
     Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_MIN_PIN, Y_MAX_PIN, \
     Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, Z_MIN_PIN, Z_MAX_PIN, Z_MIN_PROBE_PIN, \
@@ -673,7 +677,8 @@
     _E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS BED_PINS \
     _H0_PINS _H1_PINS _H2_PINS _H3_PINS _H4_PINS \
     _X2_PINS _Y2_PINS _Z2_PINS \
-    X_MS1_PIN, X_MS2_PIN, Y_MS1_PIN, Y_MS2_PIN, Z_MS1_PIN, Z_MS2_PIN \
+    X_MS1_PIN, X_MS2_PIN, Y_MS1_PIN, Y_MS2_PIN, Z_MS1_PIN, Z_MS2_PIN, \
+    HAL_SENSITIVE_PINS \
   }
 
 #define HAS_DIGIPOTSS (PIN_EXISTS(DIGIPOTSS))
diff --git a/Marlin/src/pins/pinsDebug.h b/Marlin/src/pins/pinsDebug.h
index 8957077903..037e79ddfb 100644
--- a/Marlin/src/pins/pinsDebug.h
+++ b/Marlin/src/pins/pinsDebug.h
@@ -68,7 +68,7 @@
 
 typedef struct {
   const char * const name;
-  uint8_t pin;
+  pin_t pin;
   bool is_digital;
 } PinInfo;
 
@@ -109,18 +109,18 @@ static void print_input_or_output(const bool isout) {
 
 
 // pretty report with PWM info
-inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = false, const char *start_string = "") {
+inline void report_pin_state_extended(pin_t pin, bool ignore, bool extended = false, const char *start_string = "") {
   char buffer[30];   // for the sprintf statements
   bool found = false, multi_name_pin = false;
 
   for (uint8_t x = 0; x < COUNT(pin_array); x++)  {    // scan entire array and report all instances of this pin
     if (GET_ARRAY_PIN(x) == pin) {
-      GET_PIN_INFO(pin);
       if (found) multi_name_pin = true;
       found = true;
       if (!multi_name_pin) {    // report digitial and analog pin number only on the first time through
-        sprintf_P(buffer, PSTR("%sPIN: %3d "), start_string, pin);     // digital pin number
+        sprintf_P(buffer, PSTR("%sPIN: "), start_string);     // digital pin number
         SERIAL_ECHO(buffer);
+        PRINT_PIN(pin);
         PRINT_PORT(pin);
         if (IS_ANALOG(pin)) {
           sprintf_P(buffer, PSTR(" (A%2d)  "), DIGITAL_PIN_TO_ANALOG_PIN(pin));    // analog pin number
@@ -180,8 +180,9 @@ inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = f
   } // end of for loop
 
   if (!found) {
-    sprintf_P(buffer, PSTR("%sPIN: %3d "), start_string, pin);
+    sprintf_P(buffer, PSTR("%sPIN: "), start_string);
     SERIAL_ECHO(buffer);
+    PRINT_PIN(pin);
     PRINT_PORT(pin);
     if (IS_ANALOG(pin)) {
       sprintf_P(buffer, PSTR(" (A%2d)  "), DIGITAL_PIN_TO_ANALOG_PIN(pin));    // analog pin number
diff --git a/Marlin/src/pins/pins_MKS_SBASE.h b/Marlin/src/pins/pins_MKS_SBASE.h
index 1d576f4acc..5da1bf2ac0 100644
--- a/Marlin/src/pins/pins_MKS_SBASE.h
+++ b/Marlin/src/pins/pins_MKS_SBASE.h
@@ -25,9 +25,8 @@
  * MKS SBASE pin assignments
  */
 
-//#if !defined(TARGET_LPC1768)
-#if DISABLED(IS_REARM)
-  #error "Oops!  Make sure you have Re-Arm selected."
+#ifndef TARGET_LPC1768
+  #error "Oops!  Make sure you have LPC1768 selected."
 #endif
 
 #ifndef BOARD_NAME
@@ -39,46 +38,42 @@
 
 // unused
 /*
-#define D57               57
-#define D58               58
+#define PIN_P0_27         P0_27
+#define PIN_P0_28         P0_28
 */
 
 //
 // Limit Switches
 //
-#define X_MIN_PIN           3  //10k pullup to 3.3V, 1K series
-#define X_MAX_PIN           2  //10k pullup to 3.3V, 1K series
-#define Y_MIN_PIN          14  //10k pullup to 3.3V, 1K series
-#define Y_MAX_PIN          15  //10k pullup to 3.3V, 1K series
-#define Z_MIN_PIN          19  //The original Mks Sbase DIO19 has a 10k pullup to 3.3V or 5V, 1K series, so when using a Zprobe we must use DIO41 (J8 P1.22)
-#define Z_MAX_PIN          18  //10k pullup to 3.3V, 1K series
+#define X_MIN_PIN          P1_24  //10k pullup to 3.3V, 1K series
+#define X_MAX_PIN          P1_25  //10k pullup to 3.3V, 1K series
+#define Y_MIN_PIN          P1_26  //10k pullup to 3.3V, 1K series
+#define Y_MAX_PIN          P1_27  //10k pullup to 3.3V, 1K series
+#define Z_MIN_PIN          P1_28  //The original Mks Sbase DIO19 has a 10k pullup to 3.3V or 5V, 1K series, so when using a Zprobe we must use DIO41 (J8 P1.22)
+#define Z_MAX_PIN          P1_29  //10k pullup to 3.3V, 1K series
 
 //
 // Steppers
 //
-#define X_STEP_PIN         26
-#define X_DIR_PIN          28
-#define X_ENABLE_PIN       24
+#define X_STEP_PIN         P2_0
+#define X_DIR_PIN          P0_5
+#define X_ENABLE_PIN       P0_4
 
-#define Y_STEP_PIN         54
-#define Y_DIR_PIN          55
-#define Y_ENABLE_PIN       38
+#define Y_STEP_PIN         P2_1
+#define Y_DIR_PIN          P0_11
+#define Y_ENABLE_PIN       P0_10
 
-#define Z_STEP_PIN         60
-#define Z_DIR_PIN          61
-#define Z_ENABLE_PIN       56
+#define Z_STEP_PIN         P2_2
+#define Z_DIR_PIN          P0_20
+#define Z_ENABLE_PIN       P0_19
 
-#define E0_STEP_PIN        46
-#define E0_DIR_PIN         48
-#define E0_ENABLE_PIN      62
+#define E0_STEP_PIN        P2_3
+#define E0_DIR_PIN         P0_22
+#define E0_ENABLE_PIN      P0_21
 
-#define E1_STEP_PIN        36
-#define E1_DIR_PIN         34
-#define E1_ENABLE_PIN      30
-
-#define X2_STEP_PIN        36
-#define X2_DIR_PIN         34
-#define X2_ENABLE_PIN      30
+#define E1_STEP_PIN        P2_8
+#define E1_DIR_PIN         P2_13
+#define E1_ENABLE_PIN      P4_29
 
 //
 // Temperature Sensors
@@ -95,13 +90,13 @@
 // Heaters / Fans
 //
 
-#define HEATER_BED_PIN     10
-#define HEATER_0_PIN        8
-#define HEATER_1_PIN       59
-#define FAN_PIN             9
+#define HEATER_BED_PIN     P2_5
+#define HEATER_0_PIN       P2_7
+#define HEATER_1_PIN       P2_6
+#define FAN_PIN            P2_4
 
 
-#define PS_ON_PIN          69
+#define PS_ON_PIN          P0_25
 
 
 //
@@ -111,9 +106,9 @@
 // 5V
 // NC
 // GND
-#define PIN_P0_17          50
-#define PIN_P0_16          16
-#define PIN_P0_14          80
+#define PIN_P0_17          P0_17
+#define PIN_P0_16          P0_16
+#define PIN_P0_14          P0_14
 
 
 //
@@ -121,19 +116,21 @@
 //
 
 // GND
-#define PIN_P1_22          41
-#define PIN_P1_23          53
-#define PIN_P2_12          12
-#define PIN_P2_11          35
-#define PIN_P4_28          13
+#define PIN_P1_22          P1_22
+#define PIN_P1_23          P1_23
+#define PIN_P2_12          P2_12
+#define PIN_P2_11          P2_11
+#define PIN_P4_28          P4_28
 
 //
 // Prusa i3 MK2 Multi Material Multiplexer Support
 //
 
-#define E_MUX0_PIN         50   // J7-4
-#define E_MUX1_PIN         16   // J7-5
-#define E_MUX2_PIN         80   // J7-6
+#if ENABLED(MK2_MULTIPLEXER)
+  #define E_MUX0_PIN         P0_17   // J7-4
+  #define E_MUX1_PIN         P0_16   // J7-5
+  #define E_MUX2_PIN         P0_15   // J7-6
+#endif
 
 
 /**
@@ -150,32 +147,32 @@
  */
 
 #if ENABLED(ULTRA_LCD)
-  #define BEEPER_PIN       49  // EXP1.1
-  #define BTN_ENC          37  // EXP1.2
-  #define BTN_EN1          31  // EXP2.5
-  #define BTN_EN2          33  // EXP2.3
-  #define SD_DETECT_PIN    57  // EXP2.7
-  #define LCD_PINS_RS      16  // EXP1.4
-  #define LCD_SDSS         58  // EXP2.4
-  #define LCD_PINS_ENABLE  51  // EXP1.3
-  #define LCD_PINS_D4      80  // EXP1.5
+  #define BEEPER_PIN       P1_31  // EXP1.1
+  #define BTN_ENC          P1_30  // EXP1.2
+  #define BTN_EN1          P3_26  // EXP2.5
+  #define BTN_EN2          P3_25  // EXP2.3
+  #define SD_DETECT_PIN    P0_27  // EXP2.7
+  #define LCD_PINS_RS      P0_16  // EXP1.4
+  #define LCD_SDSS         P0_28  // EXP2.4
+  #define LCD_PINS_ENABLE  P0_18  // EXP1.3
+  #define LCD_PINS_D4      P0_14  // EXP1.5
 #endif // ULTRA_LCD
 
 //
 // Ethernet pins
 //
 #ifndef ULTIPANEL
-  #define ENET_MDIO        71  // J12-4
-  #define ENET_RX_ER       73  // J12-6
-  #define ENET_RXD1        75  // J12-8
+  #define ENET_MDIO        P1_17  // J12-4
+  #define ENET_RX_ER       P1_14  // J12-6
+  #define ENET_RXD1        P1_10  // J12-8
 #endif
-#define ENET_MOC           70  // J12-3
-#define REF_CLK            72  // J12-5
-#define ENET_RXD0          74  // J12-7
-#define ENET_CRS           76  // J12-9
-#define ENET_TX_EN         77  // J12-10
-#define ENET_TXD0          78  // J12-11
-#define ENET_TXD1          79  // J12-12
+#define ENET_MOC           P1_16  // J12-3
+#define REF_CLK            P1_15  // J12-5
+#define ENET_RXD0          P1_9   // J12-7
+#define ENET_CRS           P1_8   // J12-9
+#define ENET_TX_EN         P1_4   // J12-10
+#define ENET_TXD0          P1_0   // J12-11
+#define ENET_TXD1          P1_1   // J12-12
 
 /**
  *  PWMs
@@ -184,25 +181,25 @@
  *
  *  SERVO2 does NOT have a PWM assigned to it.
  *
- *  PWM1.1   DIO4    SERVO3_PIN       FIL_RUNOUT_PIN   5V output, PWM
- *  PWM1.1   DIO26   E0_STEP_PIN
- *  PWM1.2   DIO11   SERVO0_PIN
- *  PWM1.2   DIO54   X_STEP_PIN
- *  PWM1.3   DIO6    SERVO1_PIN       J5-1
- *  PWM1.3   DIO60   Y_STEP_PIN
- *  PWM1.4   DIO53   SDSS(SSEL0)      J3-5  AUX-3
- *  PWM1.4   DIO46   Z_STEP_PIN
- *  PWM1.5   DIO3    X_MIN_PIN        10K PULLUP TO 3.3v, 1K SERIES
- *  PWM1.5   DIO9    RAMPS_D9_PIN
- *  PWM1.6   DIO14   Y_MIN_PIN        10K PULLUP TO 3.3v, 1K SERIES
- *  PWM1.6   DIO10   RAMPS_D10_PIN
+ *  PWM1.1   P1_18   SERVO3_PIN       FIL_RUNOUT_PIN   5V output, PWM
+ *  PWM1.1   P2_0    E0_STEP_PIN
+ *  PWM1.2   P1_20   SERVO0_PIN
+ *  PWM1.2   P2_1    X_STEP_PIN
+ *  PWM1.3   P1_21   SERVO1_PIN       J5-1
+ *  PWM1.3   P2_2    Y_STEP_PIN
+ *  PWM1.4   P1_23   SDSS(SSEL0)      J3-5  AUX-3
+ *  PWM1.4   P2_3    Z_STEP_PIN
+ *  PWM1.5   P1_24   X_MIN_PIN        10K PULLUP TO 3.3v, 1K SERIES
+ *  PWM1.5   P2_4    RAMPS_D9_PIN
+ *  PWM1.6   P1_26   Y_MIN_PIN        10K PULLUP TO 3.3v, 1K SERIES
+ *  PWM1.6   P2_5    RAMPS_D10_PIN
  */
 
  /**
   * Special pins
-  *   D37 - not 5V tolerant
-  *   D49 - not 5V tolerant
-  *   D57 - open collector
-  *   D58 - open collector
+  *   P1_30 - not 5V tolerant
+  *   P1_31 - not 5V tolerant
+  *   P0_27 - open collector
+  *   P0_28 - open collector
   *
   */
diff --git a/Marlin/src/pins/pins_RAMPS.h b/Marlin/src/pins/pins_RAMPS.h
index 5b83176f4b..168dcbd8cb 100644
--- a/Marlin/src/pins/pins_RAMPS.h
+++ b/Marlin/src/pins/pins_RAMPS.h
@@ -44,7 +44,7 @@
  *         7 | 11
  */
 
-#if ENABLED(IS_REARM)
+#if ENABLED(TARGET_LPC1768)
   #error "Oops!  Use 'BOARD_RAMPS_RE_ARM' to build for Re-ARM."
 #endif
 
diff --git a/Marlin/src/pins/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/pins_RAMPS_RE_ARM.h
index 80cb0abaf0..992f9b3879 100644
--- a/Marlin/src/pins/pins_RAMPS_RE_ARM.h
+++ b/Marlin/src/pins/pins_RAMPS_RE_ARM.h
@@ -34,9 +34,8 @@
  *
  */
 
-//#if !defined(TARGET_LPC1768)
-#if DISABLED(IS_REARM)
-  #error "Oops!  Make sure you have Re-Arm selected."
+#ifndef TARGET_LPC1768
+  #error "Oops!  Make sure you have LPC1768 selected."
 #endif
 
 #ifndef BOARD_NAME
@@ -45,56 +44,50 @@
 
 #define LARGE_FLASH true
 
-// unused
-#define D57               57
-#define D58               58
-
 //
 // Servos
 //
-#define SERVO0_PIN         11
-#define SERVO1_PIN          6  // also on J5-1
-#define SERVO2_PIN          5
-#define SERVO3_PIN          4  // 5V output - PWM capable
+#define SERVO0_PIN         P1_20
+#define SERVO1_PIN         P1_21  // also on J5-1
+#define SERVO2_PIN         P1_19
+#define SERVO3_PIN         P1_18  // 5V output - PWM capable
 
 //
 // Limit Switches
 //
-#define X_MIN_PIN           3  //10k pullup to 3.3V, 1K series
-#define X_MAX_PIN           2  //10k pullup to 3.3V, 1K series
-#define Y_MIN_PIN          14  //10k pullup to 3.3V, 1K series
-#define Y_MAX_PIN          15  //10k pullup to 3.3V, 1K series
-#define Z_MIN_PIN          18  //10k pullup to 3.3V, 1K series
-#define Z_MAX_PIN          19  //10k pullup to 3.3V, 1K series
-//#define Z_PROBE_PIN         1  // AUX-1
-
+#define X_MIN_PIN          P1_24  //10k pullup to 3.3V, 1K series
+#define X_MAX_PIN          P1_25  //10k pullup to 3.3V, 1K series
+#define Y_MIN_PIN          P1_26  //10k pullup to 3.3V, 1K series
+#define Y_MAX_PIN          P1_27  //10k pullup to 3.3V, 1K series
+#define Z_MIN_PIN          P1_29  //10k pullup to 3.3V, 1K series
+#define Z_MAX_PIN          P1_28  //10k pullup to 3.3V, 1K series
 
 //
 // Steppers
 //
-#define X_STEP_PIN         54
-#define X_DIR_PIN          55
-#define X_ENABLE_PIN       38
+#define X_STEP_PIN         P2_1
+#define X_DIR_PIN          P0_11
+#define X_ENABLE_PIN       P0_10
 
-#define Y_STEP_PIN         60
-#define Y_DIR_PIN          61
-#define Y_ENABLE_PIN       56
+#define Y_STEP_PIN         P2_2
+#define Y_DIR_PIN          P0_20
+#define Y_ENABLE_PIN       P0_19
 
-#define Z_STEP_PIN         46
-#define Z_DIR_PIN          48
-#define Z_ENABLE_PIN       62
+#define Z_STEP_PIN         P2_3
+#define Z_DIR_PIN          P0_22
+#define Z_ENABLE_PIN       P0_21
 
-#define E0_STEP_PIN        26
-#define E0_DIR_PIN         28
-#define E0_ENABLE_PIN      24
+#define E0_STEP_PIN        P2_0
+#define E0_DIR_PIN         P0_5
+#define E0_ENABLE_PIN      P0_4
 
-#define E1_STEP_PIN        36
-#define E1_DIR_PIN         34
-#define E1_ENABLE_PIN      30
+#define E1_STEP_PIN        P2_8
+#define E1_DIR_PIN         P2_13
+#define E1_ENABLE_PIN      P4_29
 
-#define E2_STEP_PIN        36
-#define E2_DIR_PIN         34
-#define E2_ENABLE_PIN      30
+#define E2_STEP_PIN        P2_8
+#define E2_DIR_PIN         P2_13
+#define E2_ENABLE_PIN      P4_29
 
 //
 // Temperature Sensors
@@ -131,16 +124,16 @@
 // Heaters / Fans
 //
 #ifndef MOSFET_D_PIN
-  #define MOSFET_D_PIN  -1
+  #define MOSFET_D_PIN   -1
 #endif
 #ifndef RAMPS_D8_PIN
-  #define RAMPS_D8_PIN   8
+  #define RAMPS_D8_PIN   P2_8
 #endif
 #ifndef RAMPS_D9_PIN
-  #define RAMPS_D9_PIN   9
+  #define RAMPS_D9_PIN   P2_4
 #endif
 #ifndef RAMPS_D10_PIN
-  #define RAMPS_D10_PIN 10
+  #define RAMPS_D10_PIN  P2_5
 #endif
 
 #define HEATER_0_PIN     RAMPS_D10_PIN
@@ -170,22 +163,22 @@
 #endif
 
 #ifndef FAN_PIN
-  #define FAN_PIN 4      // IO pin. Buffer needed
+  #define FAN_PIN         P1_18 // IO pin. Buffer needed
 #endif
 
 //
 // Misc. Functions
 //
-#define LED_PIN            13
+#define LED_PIN           P4_28
 
 // define digital pin 4 for the filament runout sensor. Use the RAMPS 1.4 digital input 4 on the servos connector
-#define FIL_RUNOUT_PIN      4
+#define FIL_RUNOUT_PIN    P1_18
 
-#define PS_ON_PIN          12
+#define PS_ON_PIN         P2_12
 
 #if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) && !defined(SPINDLE_LASER_ENABLE_PIN)
   #if !defined(NUM_SERVOS) || NUM_SERVOS < 4 // try to use servo connector
-    #define CASE_LIGHT_PIN    4      // MUST BE HARDWARE PWM
+    #define CASE_LIGHT_PIN    P1_18 // MUST BE HARDWARE PWM
   #endif
 #endif
 
@@ -197,17 +190,17 @@
     #undef  SERVO1
     #undef  SERVO2
     #undef  SERVO3
-    #define SPINDLE_LASER_ENABLE_PIN  6  // Pin should have a pullup/pulldown!
-    #define SPINDLE_LASER_PWM_PIN     4  // MUST BE HARDWARE PWM
-    #define SPINDLE_DIR_PIN           5
+    #define SPINDLE_LASER_ENABLE_PIN  P1_21  // Pin should have a pullup/pulldown!
+    #define SPINDLE_LASER_PWM_PIN     P1_18  // MUST BE HARDWARE PWM
+    #define SPINDLE_DIR_PIN           P1_19
   #endif
 #endif
 //
 // Průša i3 MK2 Multiplexer Support
 //
-#define E_MUX0_PIN          0   // Z_CS_PIN
-#define E_MUX1_PIN          1   // E0_CS_PIN
-#define E_MUX2_PIN         63   // E1_CS_PIN
+#define E_MUX0_PIN         P0_3    // Z_CS_PIN
+#define E_MUX1_PIN         P0_2    // E0_CS_PIN
+#define E_MUX2_PIN         P0_26   // E1_CS_PIN
 
 /**
  * LCD / Controller
@@ -230,89 +223,76 @@
 
 #if ENABLED(ULTRA_LCD)
 
-  #define BEEPER_PIN          37  // not 5V tolerant
+  #define BEEPER_PIN          P1_30  // not 5V tolerant
 
-  #define BTN_EN1             31  // J3-2 & AUX-4
-  #define BTN_EN2             33  // J3-4 & AUX-4
-  #define BTN_ENC             35  // J3-3 & AUX-4
+  #define BTN_EN1             P3_26  // J3-2 & AUX-4
+  #define BTN_EN2             P3_25  // J3-4 & AUX-4
+  #define BTN_ENC             P2_11  // J3-3 & AUX-4
 
-  #define SD_DETECT_PIN       49  // not 5V tolerant   J3-1 & AUX-3
-  #define KILL_PIN            41  // J5-4 & AUX-4
-  #define LCD_PINS_RS         16  // J3-7 & AUX-4
-  #define LCD_SDSS            16  // J3-7 & AUX-4
-  #define LCD_BACKLIGHT_PIN   16  // J3-7 & AUX-4 - only used on DOGLCD controllers
-  #define LCD_PINS_ENABLE     51  // (MOSI) J3-10 & AUX-3
-  #define LCD_PINS_D4         52  // (SCK)  J3-9 & AUX-3
+  #define SD_DETECT_PIN       P1_31  // not 5V tolerant   J3-1 & AUX-3
+  #define KILL_PIN            P1_22  // J5-4 & AUX-4
+  #define LCD_PINS_RS         P0_16  // J3-7 & AUX-4
+  #define LCD_SDSS            P0_16  // J3-7 & AUX-4
+  #define LCD_BACKLIGHT_PIN   P0_16  // J3-7 & AUX-4 - only used on DOGLCD controllers
+  #define LCD_PINS_ENABLE     P0_18  // (MOSI) J3-10 & AUX-3
+  #define LCD_PINS_D4         P0_15  // (SCK)  J3-9 & AUX-3
 
-  #define DOGLCD_A0           59  // J3-8 & AUX-2
-  #define DOGLCD_CS           63  // J5-3 & AUX-2
+  #define DOGLCD_A0           P2_6   // J3-8 & AUX-2
+  #define DOGLCD_CS           P0_26  // J5-3 & AUX-2
 
   #ifdef ULTIPANEL
-    #define LCD_PINS_D5       71  // ENET_MDIO
-    #define LCD_PINS_D6       73  // ENET_RX_ER
-    #define LCD_PINS_D7       75  // ENET_RXD1
+    #define LCD_PINS_D5       P1_17  // ENET_MDIO
+    #define LCD_PINS_D6       P1_14  // ENET_RX_ER
+    #define LCD_PINS_D7       P1_10  // ENET_RXD1
   #endif
 
   #if ENABLED(NEWPANEL)
     #if ENABLED(REPRAPWORLD_KEYPAD)
-      #define SHIFT_OUT         51  // (MOSI) J3-10 & AUX-3
-      #define SHIFT_CLK         52  // (SCK)  J3-9 & AUX-3
-      #define SHIFT_LD          49  // not 5V tolerant   J3-1 & AUX-3
+      #define SHIFT_OUT         P0_18  // (MOSI) J3-10 & AUX-3
+      #define SHIFT_CLK         P0_15  // (SCK)  J3-9 & AUX-3
+      #define SHIFT_LD          P1_31  // not 5V tolerant   J3-1 & AUX-3
     #endif
   #else
-    //#define SHIFT_CLK           31  // J3-2 & AUX-4
-    //#define SHIFT_LD            33  // J3-4 & AUX-4
-    //#define SHIFT_OUT           35  // J3-3 & AUX-4
-    //#define SHIFT_EN            41  // J5-4 & AUX-4
+    //#define SHIFT_CLK           P3_26  // J3-2 & AUX-4
+    //#define SHIFT_LD            P3_25  // J3-4 & AUX-4
+    //#define SHIFT_OUT           P2_11  // J3-3 & AUX-4
+    //#define SHIFT_EN            P1_22  // J5-4 & AUX-4
   #endif
 
-  #define SDCARD_SORT_ALPHA         // Using SORT feature to keep one directory level in RAM
-                                    // When going up/down directory levels the SD card is
-                                    // accessed but the garbage/lines are removed when the
-                                    // LCD updates
-
-  #define SDSORT_LIMIT       256    // Maximum number of sorted items (10-256). Costs 27 bytes each.
-  #define FOLDER_SORTING     -1     // -1=above  0=none  1=below
-  #define SDSORT_GCODE       false  // Allow turning sorting on/off with LCD and M34 g-code.
-  #define SDSORT_USES_RAM    true   // Pre-allocate a static array for faster pre-sorting.
-  #define SDSORT_USES_STACK  false  // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
-  #define SDSORT_CACHE_NAMES true   // Keep sorted items in RAM longer for speedy performance. Most expensive option.
-  #define SDSORT_DYNAMIC_RAM false  // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
-
   #if ENABLED(VIKI2) || ENABLED(miniVIKI)
     // #define LCD_SCREEN_ROT_180
 
     #undef  BEEPER_PIN
-    #define BEEPER_PIN          37  // may change if cable changes
+    #define BEEPER_PIN          P1_30  // may change if cable changes
 
-    #define BTN_EN1             31  // J3-2 & AUX-4
-    #define BTN_EN2             33  // J3-4 & AUX-4
-    #define BTN_ENC             35  // J3-3 & AUX-4
+    #define BTN_EN1             P3_26  // J3-2 & AUX-4
+    #define BTN_EN2             P3_25  // J3-4 & AUX-4
+    #define BTN_ENC             P2_11  // J3-3 & AUX-4
 
-    #define SD_DETECT_PIN       49  // not 5V tolerant   J3-1 & AUX-3
-    #define KILL_PIN            41  // J5-4 & AUX-4
+    #define SD_DETECT_PIN       P1_31  // not 5V tolerant   J3-1 & AUX-3
+    #define KILL_PIN            P1_22  // J5-4 & AUX-4
 
     #undef  DOGLCD_CS
-    #define DOGLCD_CS           16
-    #undef  LCD_BACKLIGHT_PIN   //16  // J3-7 & AUX-4 - only used on DOGLCD controllers
-    #undef  LCD_PINS_ENABLE     //51  // (MOSI) J3-10 & AUX-3
-    #undef  LCD_PINS_D4         //52  // (SCK)  J3-9 & AUX-3
-
-    #undef  LCD_PINS_D5         //59  // J3-8 & AUX-2
-    #define DOGLCD_A0           59  // J3-8 & AUX-2
-    #undef  LCD_PINS_D6         //63  // J5-3 & AUX-2
-    #undef  LCD_PINS_D7         // 6  // (SERVO1) J5-1 & SERVO connector
-    #define DOGLCD_SCK SCK_PIN
-    #define DOGLCD_MOSI MOSI_PIN
-
-    #define STAT_LED_BLUE_PIN   63  // may change if cable changes
-    #define STAT_LED_RED_PIN     6  // may change if cable changes
+    #define DOGLCD_CS           P0_16
+    #undef  LCD_BACKLIGHT_PIN   //P0_16  // J3-7 & AUX-4 - only used on DOGLCD controllers
+    #undef  LCD_PINS_ENABLE     //P0_18  // (MOSI) J3-10 & AUX-3
+    #undef  LCD_PINS_D4         //P0_15  // (SCK)  J3-9 & AUX-3
+
+    #undef  LCD_PINS_D5         //P2_6   // J3-8 & AUX-2
+    #define DOGLCD_A0           P2_6   // J3-8 & AUX-2
+    #undef  LCD_PINS_D6         //P0_26  // J5-3 & AUX-2
+    #undef  LCD_PINS_D7         //P1_21  // (SERVO1) J5-1 & SERVO connector
+    #define DOGLCD_SCK          SCK_PIN
+    #define DOGLCD_MOSI         MOSI_PIN
+
+    #define STAT_LED_BLUE_PIN   P0_26  // may change if cable changes
+    #define STAT_LED_RED_PIN    P1_21  // may change if cable changes
   #endif
 
-  //#define MISO_PIN            50  // system defined J3-10 & AUX-3
-  //#define MOSI_PIN            51  // system defined J3-10 & AUX-3
-  //#define SCK_PIN             52  // system defined J3-9 & AUX-3
-  //#define SS_PIN              53  // system defined J3-5 & AUX-3 - sometimes called SDSS
+  //#define MISO_PIN            P0_17  // system defined J3-10 & AUX-3
+  //#define MOSI_PIN            P0_18  // system defined J3-10 & AUX-3
+  //#define SCK_PIN             P0_15  // system defined J3-9 & AUX-3
+  //#define SS_PIN              P1_23  // system defined J3-5 & AUX-3 - sometimes called SDSS
 
   #if ENABLED(MINIPANEL)
     // GLCD features
@@ -329,17 +309,17 @@
 // Ethernet pins
 //
 #ifndef ULTIPANEL
-  #define ENET_MDIO   71  // J12-4
-  #define ENET_RX_ER  73  // J12-6
-  #define ENET_RXD1   75  // J12-8
+  #define ENET_MDIO   P1_17  // J12-4
+  #define ENET_RX_ER  P1_14  // J12-6
+  #define ENET_RXD1   P1_10  // J12-8
 #endif
-#define ENET_MOC      70  // J12-3
-#define REF_CLK       72  // J12-5
-#define ENET_RXD0     74  // J12-7
-#define ENET_CRS      76  // J12-9
-#define ENET_TX_EN    77  // J12-10
-#define ENET_TXD0     78  // J12-11
-#define ENET_TXD1     79  // J12-12
+#define ENET_MOC      P1_16  // J12-3
+#define REF_CLK       P1_15  // J12-5
+#define ENET_RXD0     P1_9   // J12-7
+#define ENET_CRS      P1_8   // J12-9
+#define ENET_TX_EN    P1_4   // J12-10
+#define ENET_TXD0     P1_0   // J12-11
+#define ENET_TXD1     P1_1   // J12-12
 
 /**
  *  PWMS
@@ -348,47 +328,25 @@
  *
  *  SERVO2 does NOT have a PWM assigned to it.
  *
- *  PWM1.1   DIO4    SERVO3_PIN       FIL_RUNOUT_PIN   5V output, PWM
- *  PWM1.1   DIO26   E0_STEP_PIN
- *  PWM1.2   DIO11   SERVO0_PIN
- *  PWM1.2   DIO54   X_STEP_PIN
- *  PWM1.3   DIO6    SERVO1_PIN       J5-1
- *  PWM1.3   DIO60   Y_STEP_PIN
- *  PWM1.4   DIO53   SDSS(SSEL0)      J3-5  AUX-3
- *  PWM1.4   DIO46   Z_STEP_PIN
- *  PWM1.5   DIO3    X_MIN_PIN        10K PULLUP TO 3.3v, 1K SERIES
- *  PWM1.5   DIO9    RAMPS_D9_PIN
- *  PWM1.6   DIO14   Y_MIN_PIN        10K PULLUP TO 3.3v, 1K SERIES
- *  PWM1.6   DIO10   RAMPS_D10_PIN
- */
-
-/**
- *  The following pins are NOT available in a Re-ARM system
- *  7
- *  17
- *  22
- *  23
- *  25
- *  27
- *  29
- *  32
- *  39
- *  40
- *  42
- *  43
- *  44
- *  45
- *  47
- *  64
- *  65
- *  66
+ *  PWM1.1   P0_18   SERVO3_PIN       FIL_RUNOUT_PIN   5V output, PWM
+ *  PWM1.1   P2_0    E0_STEP_PIN
+ *  PWM1.2   P1_20   SERVO0_PIN
+ *  PWM1.2   P2_1    X_STEP_PIN
+ *  PWM1.3   P1_21   SERVO1_PIN       J5-1
+ *  PWM1.3   P2_2    Y_STEP_PIN
+ *  PWM1.4   P1_23   SDSS(SSEL0)      J3-5  AUX-3
+ *  PWM1.4   P2_3    Z_STEP_PIN
+ *  PWM1.5   P1_24   X_MIN_PIN        10K PULLUP TO 3.3v, 1K SERIES
+ *  PWM1.5   P2_4    RAMPS_D9_PIN
+ *  PWM1.6   P1_26   Y_MIN_PIN        10K PULLUP TO 3.3v, 1K SERIES
+ *  PWM1.6   P2_5    RAMPS_D10_PIN
  */
 
  /**
   * special pins
-  *   D37 - not 5V tolerant
-  *   D49 - not 5V tolerant
-  *   D57 - open collector
-  *   D58 - open collector
+  *   P1_30 - not 5V tolerant
+  *   P1_31 - not 5V tolerant
+  *   P0_27 - open collector
+  *   P0_28 - open collector
   *
  */
diff --git a/Marlin/src/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp
index 4107eaf2bc..d0e807f82f 100644
--- a/Marlin/src/sd/Sd2Card.cpp
+++ b/Marlin/src/sd/Sd2Card.cpp
@@ -170,7 +170,7 @@ bool Sd2Card::eraseSingleBlockEnable() {
  * the value zero, false, is returned for failure.  The reason for failure
  * can be determined by calling errorCode() and errorData().
  */
-bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
+bool Sd2Card::init(uint8_t sckRateID, pin_t chipSelectPin) {
   errorCode_ = type_ = 0;
   chipSelectPin_ = chipSelectPin;
   // 16-bit init start time allows over a minute
diff --git a/Marlin/src/sd/Sd2Card.h b/Marlin/src/sd/Sd2Card.h
index a038f99a6d..5aaffe72f4 100644
--- a/Marlin/src/sd/Sd2Card.h
+++ b/Marlin/src/sd/Sd2Card.h
@@ -181,7 +181,7 @@ class Sd2Card {
    * \return true for success or false for failure.
    */
   bool init(uint8_t sckRateID = SPI_FULL_SPEED,
-            uint8_t chipSelectPin = SD_CHIP_SELECT_PIN);
+            pin_t chipSelectPin = SD_CHIP_SELECT_PIN);
   bool readBlock(uint32_t block, uint8_t* dst);
   /**
    * Read a card's CID register. The CID contains card identification
@@ -220,7 +220,7 @@ class Sd2Card {
   bool writeStop();
  private:
   //----------------------------------------------------------------------------
-  uint8_t chipSelectPin_;
+  pin_t chipSelectPin_;
   uint8_t errorCode_;
   uint8_t spiRate_;
   uint8_t status_;
diff --git a/platformio.ini b/platformio.ini
index 06e783433f..94f893edfa 100644
--- a/platformio.ini
+++ b/platformio.ini
@@ -139,9 +139,9 @@ lib_ignore  = Adafruit NeoPixel
 src_filter  = ${common.default_src_filter}
 
 #
-# Re-ARM (NXP LPC1768 ARM Cortex-M3)
+# NXP LPC1768 ARM Cortex-M3
 #
-[env:Re-ARM]
+[env:LPC1768]
 platform        = nxplpc
 board_f_cpu     = 100000000L
 build_flags     = !python Marlin/src/HAL/HAL_LPC1768/lpc1768_flag_script.py
@@ -154,9 +154,9 @@ extra_scripts   = Marlin/src/HAL/HAL_LPC1768/lpc1768_flag_script.py
 src_filter      = ${common.default_src_filter}
 
 #
-# Re-ARM (for debugging and development)
+# LPC1768 (for debugging and development)
 #
-[env:Re-ARM_debug_and_upload]
+[env:LPC1768_debug_and_upload]
 # Segger JLink
 platform       = nxplpc
 #framework     = mbed
-- 
GitLab