diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/HAL.cpp b/Marlin/src/HAL/HAL_TEENSY31_32/HAL.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..fa5cdd8d1a8a488219fe4f0f71f6de952c8d51f7
--- /dev/null
+++ b/Marlin/src/HAL/HAL_TEENSY31_32/HAL.cpp
@@ -0,0 +1,90 @@
+/* **************************************************************************
+
+ Marlin 3D Printer Firmware
+ Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
+
+ This program is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ This program is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with this program.  If not, see <http://www.gnu.org/licenses/>.
+****************************************************************************/
+
+
+/**
+ * Description: HAL for Teensy32 (MK20DX256)
+ */
+
+#ifdef __MK20DX256__
+
+#include "HAL.h"
+#include "../Delay.h"
+
+#include <Wire.h>
+
+uint16_t HAL_adc_result;
+
+static const uint8_t pin2sc1a[] = {
+    5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 0, 19, 3, 31, // 0-13, we treat them as A0-A13
+    5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 (A0-A9)
+    31, 31, 31, 31, 31, 31, 31, 31, 31, 31, // 24-33
+    0+64, 19+64, 3+64, 31+64, // 34-37 (A10-A13)
+    26, 22, 23, 27, 29, 30 // 38-43: temp. sensor, VREF_OUT, A14, bandgap, VREFH, VREFL. A14 isn't connected to anything in Teensy 3.0.
+};
+
+/*
+  // disable interrupts
+  void cli(void) { noInterrupts(); }
+
+  // enable interrupts
+  void sei(void) { interrupts(); }
+*/
+
+void HAL_adc_init() {
+  analog_init();
+  while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish
+  NVIC_ENABLE_IRQ(IRQ_FTM1);
+}
+
+void HAL_clear_reset_source(void) { }
+
+uint8_t HAL_get_reset_source(void) {
+  switch (RCM_SRS0) {
+    case 128: return RST_POWER_ON; break;
+    case 64: return RST_EXTERNAL; break;
+    case 32: return RST_WATCHDOG; break;
+    // case 8: return RST_LOSS_OF_LOCK; break;
+    // case 4: return RST_LOSS_OF_CLOCK; break;
+    // case 2: return RST_LOW_VOLTAGE; break;
+  }
+  return 0;
+}
+
+extern "C" {
+  extern char __bss_end;
+  extern char __heap_start;
+  extern void* __brkval;
+
+  int freeMemory() {
+    int free_memory;
+    if ((int)__brkval == 0)
+      free_memory = ((int)&free_memory) - ((int)&__bss_end);
+    else
+      free_memory = ((int)&free_memory) - ((int)__brkval);
+    return free_memory;
+  }
+}
+
+void HAL_adc_start_conversion(const uint8_t adc_pin) { ADC0_SC1A = pin2sc1a[adc_pin]; }
+
+uint16_t HAL_adc_get_result(void) { return ADC0_RA; }
+
+#endif // __MK20DX256__
diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/HAL.h b/Marlin/src/HAL/HAL_TEENSY31_32/HAL.h
new file mode 100644
index 0000000000000000000000000000000000000000..ce40eb24e0ac74f1bad763d5ab5808148e51bee2
--- /dev/null
+++ b/Marlin/src/HAL/HAL_TEENSY31_32/HAL.h
@@ -0,0 +1,159 @@
+/**
+ * Marlin 3D Printer Firmware
+ *
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
+ * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
+ *
+ */
+
+/**
+ * Description: HAL for Teensy 3.5 and Teensy 3.6
+ */
+
+#pragma once
+
+#define CPU_32_BIT
+
+// _BV is re-defined in Arduino.h
+#undef _BV
+
+#include <Arduino.h>
+
+// Redefine sq macro defined by teensy3/wiring.h
+#undef sq
+#define sq(x) ((x)*(x))
+
+#include "../math_32bit.h"
+#include "../HAL_SPI.h"
+
+#include "fastio_Teensy.h"
+#include "watchdog_Teensy.h"
+
+#include "HAL_timers_Teensy.h"
+
+#include <stdint.h>
+
+#define ST7920_DELAY_1 DELAY_NS(600)
+#define ST7920_DELAY_2 DELAY_NS(750)
+#define ST7920_DELAY_3 DELAY_NS(750)
+
+//#undef MOTHERBOARD
+//#define MOTHERBOARD BOARD_TEENSY31_32
+
+#define IS_32BIT_TEENSY defined(__MK20DX256__)
+#define IS_TEENSY32 defined(__MK20DX256__)
+
+#define NUM_SERIAL 1
+
+#if SERIAL_PORT == -1
+  #define MYSERIAL0 SerialUSB
+#elif SERIAL_PORT == 0
+  #define MYSERIAL0 Serial
+#elif SERIAL_PORT == 1
+  #define MYSERIAL0 Serial1
+#elif SERIAL_PORT == 2
+  #define MYSERIAL0 Serial2
+#elif SERIAL_PORT == 3
+  #define MYSERIAL0 Serial3
+#endif
+
+#define HAL_SERVO_LIB libServo
+
+typedef int8_t pin_t;
+
+#ifndef analogInputToDigitalPin
+  #define analogInputToDigitalPin(p) ((p < 12u) ? (p) + 54u : -1)
+#endif
+
+#define CRITICAL_SECTION_START  uint32_t primask = __get_PRIMASK(); __disable_irq()
+#define CRITICAL_SECTION_END    if (!primask) __enable_irq()
+#define ISRS_ENABLED() (!__get_PRIMASK())
+#define ENABLE_ISRS()  __enable_irq()
+#define DISABLE_ISRS() __disable_irq()
+
+#ifndef strncpy_P
+  #define strncpy_P(dest, src, num) strncpy((dest), (src), (num))
+#endif
+
+// Fix bug in pgm_read_ptr
+#undef pgm_read_ptr
+#define pgm_read_ptr(addr) (*((void**)(addr)))
+// Add type-checking to pgm_read_word
+#undef pgm_read_word
+#define pgm_read_word(addr) (*((uint16_t*)(addr)))
+
+#define RST_POWER_ON   1
+#define RST_EXTERNAL   2
+#define RST_BROWN_OUT  4
+#define RST_WATCHDOG   8
+#define RST_JTAG       16
+#define RST_SOFTWARE   32
+#define RST_BACKUP     64
+
+// Clear the reset reason
+void HAL_clear_reset_source(void);
+
+// Get the reason for the reset
+uint8_t HAL_get_reset_source(void);
+
+FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
+
+extern "C" {
+  int freeMemory(void);
+}
+
+// SPI: Extended functions which take a channel number (hardware SPI only)
+
+// Write single byte to specified SPI channel
+void spiSend(uint32_t chan, byte b);
+
+// Write buffer to specified SPI channel
+void spiSend(uint32_t chan, const uint8_t* buf, size_t n);
+
+// Read single byte from specified SPI channel
+uint8_t spiRec(uint32_t chan);
+
+// ADC
+
+void HAL_adc_init();
+
+#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
+#define HAL_READ_ADC()      HAL_adc_get_result()
+#define HAL_ADC_READY()     true
+
+#define HAL_ANALOG_SELECT(pin) NOOP;
+
+void HAL_adc_start_conversion(const uint8_t adc_pin);
+
+uint16_t HAL_adc_get_result(void);
+
+/*
+uint16_t HAL_getAdcReading(uint8_t chan);
+
+void HAL_startAdcConversion(uint8_t chan);
+uint8_t HAL_pinToAdcChannel(int pin);
+
+uint16_t HAL_getAdcFreerun(uint8_t chan, bool wait_for_conversion = false);
+//uint16_t HAL_getAdcSuperSample(uint8_t chan);
+
+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_TEENSY31_32/HAL_Servo_Teensy.cpp b/Marlin/src/HAL/HAL_TEENSY31_32/HAL_Servo_Teensy.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..7864ee715f03737f8c8f299a83efe57a451060bf
--- /dev/null
+++ b/Marlin/src/HAL/HAL_TEENSY31_32/HAL_Servo_Teensy.cpp
@@ -0,0 +1,36 @@
+#ifdef __MK20DX256__
+
+#include "../../inc/MarlinConfig.h"
+
+#if HAS_SERVOS
+
+#include "HAL_Servo_Teensy.h"
+
+uint8_t servoPin[MAX_SERVOS] = { 0 };
+
+int8_t libServo::attach(const int pin) {
+  if (this->servoIndex >= MAX_SERVOS) return -1;
+  if (pin > 0) servoPin[this->servoIndex] = pin;
+  return Servo::attach(servoPin[this->servoIndex]);
+}
+
+int8_t libServo::attach(const int pin, const int min, const int max) {
+  if (pin > 0) servoPin[this->servoIndex] = pin;
+  return Servo::attach(servoPin[this->servoIndex], min, max);
+}
+
+void libServo::move(const int value) {
+  constexpr uint16_t servo_delay[] = SERVO_DELAY;
+  static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
+  if (this->attach(0) >= 0) {
+    this->write(value);
+    safe_delay(servo_delay[this->servoIndex]);
+    #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
+      this->detach();
+    #endif
+  }
+}
+
+#endif // HAS_SERVOS
+
+#endif // __MK20DX256__
diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/HAL_Servo_Teensy.h b/Marlin/src/HAL/HAL_TEENSY31_32/HAL_Servo_Teensy.h
new file mode 100644
index 0000000000000000000000000000000000000000..c18d96ae12b7ae22cb2a72264fbe76b74323709b
--- /dev/null
+++ b/Marlin/src/HAL/HAL_TEENSY31_32/HAL_Servo_Teensy.h
@@ -0,0 +1,37 @@
+/**
+ * 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/>.
+ *
+ */
+
+#pragma once
+
+#include <Servo.h>
+
+// Inherit and expand on the official library
+class libServo : public Servo {
+  public:
+    int8_t attach(const int pin);
+    int8_t attach(const int pin, const int min, const int max);
+    void move(const int value);
+  private:
+     uint16_t min_ticks;
+     uint16_t max_ticks;
+     uint8_t servoIndex;               // index into the channel data for this servo
+};
diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/HAL_spi_Teensy.cpp b/Marlin/src/HAL/HAL_TEENSY31_32/HAL_spi_Teensy.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..4c57f02436a16219895d99ff0717fa1efdec0129
--- /dev/null
+++ b/Marlin/src/HAL/HAL_TEENSY31_32/HAL_spi_Teensy.cpp
@@ -0,0 +1,132 @@
+/**
+ * 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 __MK20DX256__
+
+#include "HAL.h"
+#include <SPI.h>
+#include <pins_arduino.h>
+#include "spi_pins.h"
+#include "../../core/macros.h"
+
+static SPISettings spiConfig;
+
+/**
+ * Standard SPI functions
+ */
+
+// Initialise SPI bus
+void spiBegin(void) {
+  #if !PIN_EXISTS(SS)
+    #error "SS_PIN not defined!"
+  #endif
+  SET_OUTPUT(SS_PIN);
+  WRITE(SS_PIN, HIGH);
+  SET_OUTPUT(SCK_PIN);
+  SET_INPUT(MISO_PIN);
+  SET_OUTPUT(MOSI_PIN);
+
+  //#if DISABLED(SOFTWARE_SPI)
+  #if 0
+    // set SS high - may be chip select for another SPI device
+    #if SET_SPI_SS_HIGH
+      WRITE(SS_PIN, HIGH);
+    #endif
+    // set a default rate
+    spiInit(SPI_HALF_SPEED); // 1
+  #endif
+}
+
+// Configure SPI for specified SPI speed
+void spiInit(uint8_t spiRate) {
+  // Use data rates Marlin uses
+  uint32_t clock;
+  switch (spiRate) {
+    case SPI_FULL_SPEED:    clock = 10000000; break;
+    case SPI_HALF_SPEED:    clock =  5000000; break;
+    case SPI_QUARTER_SPEED: clock =  2500000; break;
+    case SPI_EIGHTH_SPEED:  clock =  1250000; break;
+    case SPI_SPEED_5:       clock =   625000; break;
+    case SPI_SPEED_6:       clock =   312500; break;
+    default:                clock = 4000000; // Default from the SPI libarary
+  }
+  spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0);
+  SPI.begin();
+}
+
+// SPI receive a byte
+uint8_t spiRec(void) {
+  SPI.beginTransaction(spiConfig);
+  const uint8_t returnByte = SPI.transfer(0xFF);
+  SPI.endTransaction();
+  return returnByte;
+  //SPDR = 0xFF;
+  //while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
+  //return SPDR;
+}
+
+// SPI read data
+void spiRead(uint8_t* buf, uint16_t nbyte) {
+  SPI.beginTransaction(spiConfig);
+  SPI.transfer(buf, nbyte);
+  SPI.endTransaction();
+  //if (nbyte-- == 0) return;
+  //  SPDR = 0xFF;
+  //for (uint16_t i = 0; i < nbyte; i++) {
+  //  while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
+  //  buf[i] = SPDR;
+  //  SPDR = 0xFF;
+  //}
+  //while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
+  //buf[nbyte] = SPDR;
+}
+
+// SPI send a byte
+void spiSend(uint8_t b) {
+  SPI.beginTransaction(spiConfig);
+  SPI.transfer(b);
+  SPI.endTransaction();
+  //SPDR = b;
+  //while (!TEST(SPSR, SPIF)) { /* nada */ }
+}
+
+// SPI send block
+void spiSendBlock(uint8_t token, const uint8_t* buf) {
+  SPI.beginTransaction(spiConfig);
+  SPDR = token;
+  for (uint16_t i = 0; i < 512; i += 2) {
+    while (!TEST(SPSR, SPIF)) { /* nada */ };
+    SPDR = buf[i];
+    while (!TEST(SPSR, SPIF)) { /* nada */ };
+    SPDR = buf[i + 1];
+  }
+  while (!TEST(SPSR, SPIF)) { /* nada */ };
+  SPI.endTransaction();
+}
+
+
+// Begin SPI transaction, set clock, bit order, data mode
+void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) {
+  spiConfig = SPISettings(spiClock, bitOrder, dataMode);
+  SPI.beginTransaction(spiConfig);
+}
+
+#endif // __MK20DX256__
diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/HAL_timers_Teensy.cpp b/Marlin/src/HAL/HAL_TEENSY31_32/HAL_timers_Teensy.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..aff44d4486150c16bcbc139b9262f7006448916c
--- /dev/null
+++ b/Marlin/src/HAL/HAL_TEENSY31_32/HAL_timers_Teensy.cpp
@@ -0,0 +1,113 @@
+/* **************************************************************************
+
+ Marlin 3D Printer Firmware
+ Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
+
+ This program is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ This program is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with this program.  If not, see <http://www.gnu.org/licenses/>.
+****************************************************************************/
+
+
+/**
+ * Teensy3.2 __MK20DX256__
+ */
+
+#ifdef __MK20DX256__
+
+#include "HAL.h"
+#include "HAL_timers_Teensy.h"
+
+/** \brief Instruction Synchronization Barrier
+  Instruction Synchronization Barrier flushes the pipeline in the processor,
+  so that all instructions following the ISB are fetched from cache or
+  memory, after the instruction has been completed.
+*/
+FORCE_INLINE static void __ISB(void) {
+  __asm__ __volatile__("isb 0xF":::"memory");
+}
+
+/** \brief Data Synchronization Barrier
+  This function acts as a special kind of Data Memory Barrier.
+  It completes when all explicit memory accesses before this instruction complete.
+*/
+FORCE_INLINE static void __DSB(void) {
+  __asm__ __volatile__("dsb 0xF":::"memory");
+}
+
+void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
+  switch (timer_num) {
+    case 0:
+      FTM0_MODE = FTM_MODE_WPDIS | FTM_MODE_FTMEN;
+      FTM0_SC = 0x00; // Set this to zero before changing the modulus
+      FTM0_CNT = 0x0000; // Reset the count to zero
+      FTM0_MOD = 0xFFFF; // max modulus = 65535
+      FTM0_C0V = FTM0_TIMER_RATE / frequency; // Initial FTM Channel 0 compare value
+      FTM0_SC = (FTM_SC_CLKS(0b1) & FTM_SC_CLKS_MASK) | (FTM_SC_PS(FTM0_TIMER_PRESCALE_BITS) & FTM_SC_PS_MASK); // Bus clock 60MHz divided by prescaler 8
+      FTM0_C0SC = FTM_CSC_CHIE | FTM_CSC_MSA | FTM_CSC_ELSA;
+      break;
+    case 1:
+      FTM1_MODE = FTM_MODE_WPDIS | FTM_MODE_FTMEN; // Disable write protection, Enable FTM1
+      FTM1_SC = 0x00; // Set this to zero before changing the modulus
+      FTM1_CNT = 0x0000; // Reset the count to zero
+      FTM1_MOD = 0xFFFF; // max modulus = 65535
+      FTM1_C0V = FTM1_TIMER_RATE / frequency; // Initial FTM Channel 0 compare value 65535
+      FTM1_SC = (FTM_SC_CLKS(0b1) & FTM_SC_CLKS_MASK) | (FTM_SC_PS(FTM1_TIMER_PRESCALE_BITS) & FTM_SC_PS_MASK); // Bus clock 60MHz divided by prescaler 4
+      FTM1_C0SC = FTM_CSC_CHIE | FTM_CSC_MSA | FTM_CSC_ELSA;
+      break;
+  }
+}
+
+void HAL_timer_enable_interrupt(const uint8_t timer_num) {
+  switch(timer_num) {
+    case 0: NVIC_ENABLE_IRQ(IRQ_FTM0); break;
+    case 1: NVIC_ENABLE_IRQ(IRQ_FTM1); break;
+  }
+}
+
+void HAL_timer_disable_interrupt(const uint8_t timer_num) {
+  switch (timer_num) {
+    case 0: NVIC_DISABLE_IRQ(IRQ_FTM0); break;
+    case 1: NVIC_DISABLE_IRQ(IRQ_FTM1); break;
+  }
+
+  // We NEED memory barriers to ensure Interrupts are actually disabled!
+  // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
+  __DSB();
+  __ISB();
+}
+
+bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
+  switch (timer_num) {
+    case 0: return NVIC_IS_ENABLED(IRQ_FTM0);
+    case 1: return NVIC_IS_ENABLED(IRQ_FTM1);
+  }
+  return false;
+}
+
+void HAL_timer_isr_prologue(const uint8_t timer_num) {
+  switch(timer_num) {
+    case 0:
+      FTM0_CNT = 0x0000;
+      FTM0_SC &= ~FTM_SC_TOF; // Clear FTM Overflow flag
+      FTM0_C0SC &= ~FTM_CSC_CHF; // Clear FTM Channel Compare flag
+      break;
+    case 1:
+      FTM1_CNT = 0x0000;
+      FTM1_SC &= ~FTM_SC_TOF; // Clear FTM Overflow flag
+      FTM1_C0SC &= ~FTM_CSC_CHF; // Clear FTM Channel Compare flag
+      break;
+  }
+}
+
+#endif // __MK20DX256__
diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/HAL_timers_Teensy.h b/Marlin/src/HAL/HAL_TEENSY31_32/HAL_timers_Teensy.h
new file mode 100644
index 0000000000000000000000000000000000000000..bef5e5a91410836a26484666ad618a47be579244
--- /dev/null
+++ b/Marlin/src/HAL/HAL_TEENSY31_32/HAL_timers_Teensy.h
@@ -0,0 +1,113 @@
+/* **************************************************************************
+
+ Marlin 3D Printer Firmware
+ Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
+ Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
+
+ This program is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ This program is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with this program.  If not, see <http://www.gnu.org/licenses/>.
+****************************************************************************/
+
+/**
+ * Description: HAL for
+ * Teensy3.2 (__MK20DX256__)
+ */
+
+#pragma once
+
+// --------------------------------------------------------------------------
+// Includes
+// --------------------------------------------------------------------------
+
+#include <stdint.h>
+
+// --------------------------------------------------------------------------
+// Defines
+// --------------------------------------------------------------------------
+
+#define FORCE_INLINE __attribute__((always_inline)) inline
+
+typedef uint32_t hal_timer_t;
+#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
+
+#define FTM0_TIMER_PRESCALE 8
+#define FTM1_TIMER_PRESCALE 4
+#define FTM0_TIMER_PRESCALE_BITS 0b011
+#define FTM1_TIMER_PRESCALE_BITS 0b010
+
+#define FTM0_TIMER_RATE (F_BUS / FTM0_TIMER_PRESCALE) // 60MHz / 8 = 7500kHz
+#define FTM1_TIMER_RATE (F_BUS / FTM1_TIMER_PRESCALE) // 60MHz / 4 = 15MHz
+
+#define HAL_TIMER_RATE         (FTM0_TIMER_RATE)
+
+#define STEP_TIMER_NUM 0
+#define TEMP_TIMER_NUM 1
+#define PULSE_TIMER_NUM STEP_TIMER_NUM
+
+#define TEMP_TIMER_FREQUENCY    1000
+
+#define STEPPER_TIMER_RATE     HAL_TIMER_RATE
+#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000)
+#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
+
+#define PULSE_TIMER_RATE       STEPPER_TIMER_RATE   // frequency of pulse timer
+#define PULSE_TIMER_PRESCALE   STEPPER_TIMER_PRESCALE
+#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
+
+#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
+#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM)
+#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
+
+#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
+#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
+
+#define HAL_STEP_TIMER_ISR  extern "C" void ftm0_isr(void) //void TC3_Handler()
+#define HAL_TEMP_TIMER_ISR  extern "C" void ftm1_isr(void) //void TC4_Handler()
+
+void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
+
+FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
+  switch (timer_num) {
+    case 0: FTM0_C0V = compare; break;
+    case 1: FTM1_C0V = compare; break;
+  }
+}
+
+FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
+  switch (timer_num) {
+    case 0: return FTM0_C0V;
+    case 1: return FTM1_C0V;
+  }
+  return 0;
+}
+
+FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
+  switch (timer_num) {
+    case 0: return FTM0_CNT;
+    case 1: return FTM1_CNT;
+  }
+  return 0;
+}
+
+FORCE_INLINE static void HAL_timer_restrain(const uint8_t timer_num, const uint16_t interval_ticks) {
+  const hal_timer_t mincmp = HAL_timer_get_count(timer_num) + interval_ticks;
+  if (HAL_timer_get_compare(timer_num) < mincmp) HAL_timer_set_compare(timer_num, mincmp);
+}
+
+void HAL_timer_enable_interrupt(const uint8_t timer_num);
+void HAL_timer_disable_interrupt(const uint8_t timer_num);
+bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
+
+void HAL_timer_isr_prologue(const uint8_t timer_num);
+#define HAL_timer_isr_epilogue(TIMER_NUM)
diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/SanityCheck.h b/Marlin/src/HAL/HAL_TEENSY31_32/SanityCheck.h
new file mode 100644
index 0000000000000000000000000000000000000000..777f3834a60d8a22bc8a9ced5a53eb2b9a91063e
--- /dev/null
+++ b/Marlin/src/HAL/HAL_TEENSY31_32/SanityCheck.h
@@ -0,0 +1,29 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (C) 2016, 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/>.
+ *
+ */
+
+/**
+ * Test TEENSY35_36 specific configuration values for errors at compile-time.
+ */
+
+#if ENABLED(EMERGENCY_PARSER)
+  #error "EMERGENCY_PARSER is not yet implemented for Teensy 3.1/3.2. Disable EMERGENCY_PARSER to continue."
+#endif
diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/endstop_interrupts.h b/Marlin/src/HAL/HAL_TEENSY31_32/endstop_interrupts.h
new file mode 100644
index 0000000000000000000000000000000000000000..353fd853f30db2a8a5e3dfba108aa705e854a1ec
--- /dev/null
+++ b/Marlin/src/HAL/HAL_TEENSY31_32/endstop_interrupts.h
@@ -0,0 +1,86 @@
+/**
+ * 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/>.
+ *
+ */
+
+/**
+ * Endstop Interrupts
+ *
+ * Without endstop interrupts the endstop pins must be polled continually in
+ * the temperature-ISR via endstops.update(), most of the time finding no change.
+ * With this feature endstops.update() is called only when we know that at
+ * least one endstop has changed state, saving valuable CPU cycles.
+ *
+ * This feature only works when all used endstop pins can generate an 'external interrupt'.
+ *
+ * Test whether pins issue interrupts on your board by flashing 'pin_interrupt_test.ino'.
+ * (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino)
+ */
+
+#pragma once
+
+#include "../../module/endstops.h"
+
+// One ISR for all EXT-Interrupts
+void endstop_ISR(void) { endstops.update(); }
+
+/**
+ *  Endstop interrupts for Due based targets.
+ *  On Due, all pins support external interrupt capability.
+ */
+
+void setup_endstop_interrupts( void ) {
+
+  #if HAS_X_MAX
+    attachInterrupt(digitalPinToInterrupt(X_MAX_PIN), endstop_ISR, CHANGE); // assign it
+  #endif
+
+  #if HAS_X_MIN
+    attachInterrupt(digitalPinToInterrupt(X_MIN_PIN), endstop_ISR, CHANGE);
+  #endif
+
+  #if HAS_Y_MAX
+    attachInterrupt(digitalPinToInterrupt(Y_MAX_PIN), endstop_ISR, CHANGE);
+  #endif
+
+  #if HAS_Y_MIN
+    attachInterrupt(digitalPinToInterrupt(Y_MIN_PIN), endstop_ISR, CHANGE);
+  #endif
+
+  #if HAS_Z_MAX
+    attachInterrupt(digitalPinToInterrupt(Z_MAX_PIN), endstop_ISR, CHANGE);
+  #endif
+
+  #if HAS_Z_MIN
+     attachInterrupt(digitalPinToInterrupt(Z_MIN_PIN), endstop_ISR, CHANGE);
+  #endif
+
+  #if HAS_Z2_MAX
+    attachInterrupt(digitalPinToInterrupt(Z2_MAX_PIN), endstop_ISR, CHANGE);
+  #endif
+
+  #if HAS_Z2_MIN
+    attachInterrupt(digitalPinToInterrupt(Z2_MIN_PIN), endstop_ISR, CHANGE);
+  #endif
+
+  #if HAS_Z_MIN_PROBE_PIN
+    attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_PIN), endstop_ISR, CHANGE);
+  #endif
+}
diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/fastio_Teensy.h b/Marlin/src/HAL/HAL_TEENSY31_32/fastio_Teensy.h
new file mode 100644
index 0000000000000000000000000000000000000000..6dc5c14a987e6bb8242914885ba0c522ec0170f1
--- /dev/null
+++ b/Marlin/src/HAL/HAL_TEENSY31_32/fastio_Teensy.h
@@ -0,0 +1,92 @@
+/**
+ * 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/>.
+ *
+ */
+
+/**
+ * Fast I/O Routines for Teensy 3.5 and Teensy 3.6
+ * Use direct port manipulation to save scads of processor time.
+ * Contributed by Triffid_Hunter and modified by Kliment, thinkyhead, Bob-the-Kuhn, et.al.
+ */
+
+#pragma once
+
+#ifndef MASK
+  #define MASK(PIN) (1 << PIN)
+#endif
+
+#define GPIO_BITBAND_ADDR(reg, bit) (((uint32_t)&(reg) - 0x40000000) * 32 + (bit) * 4 + 0x42000000)
+#define GPIO_BITBAND(reg, bit) (*(uint32_t *)GPIO_BITBAND_ADDR((reg), (bit)))
+
+/**
+ * Magic I/O routines
+ *
+ * Now you can simply SET_OUTPUT(PIN); WRITE(PIN, HIGH); WRITE(PIN, LOW);
+ *
+ * Why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
+ */
+
+#define _READ(p) bool(CORE_PIN ## p ## _PINREG & CORE_PIN ## p ## _BITMASK)
+
+#define _WRITE(P,V) do{ \
+  if (V) CORE_PIN ## P ## _PORTSET = CORE_PIN ## P ## _BITMASK; \
+  else CORE_PIN ## P ## _PORTCLEAR = CORE_PIN ## P ## _BITMASK; \
+}while(0)
+
+#define _TOGGLE(P) (*(&(CORE_PIN ## P ## _PORTCLEAR)+1) = CORE_PIN ## P ## _BITMASK)
+
+#define _SET_INPUT(P) do{ \
+  CORE_PIN ## P ## _CONFIG = PORT_PCR_MUX(1); \
+  GPIO_BITBAND(CORE_PIN ## P ## _DDRREG , CORE_PIN ## P ## _BIT) = 0; \
+}while(0)
+
+#define _SET_OUTPUT(P) do{ \
+  CORE_PIN ## P ## _CONFIG = PORT_PCR_MUX(1)|PORT_PCR_SRE|PORT_PCR_DSE; \
+  GPIO_BITBAND(CORE_PIN ## P ## _DDRREG , CORE_PIN ## P ## _BIT) = 1; \
+}while(0)
+
+#define _SET_INPUT_PULLUP(P) do{ \
+  CORE_PIN ## P ## _CONFIG = PORT_PCR_MUX(1) | PORT_PCR_PE | PORT_PCR_PS; \
+  GPIO_BITBAND(CORE_PIN ## P ## _DDRREG , CORE_PIN ## P ## _BIT) = 0; \
+}while(0)
+
+#define _GET_INPUT(P)   ((CORE_PIN ## P ## _DDRREG & CORE_PIN ## P ## _BITMASK) == 0)
+#define _GET_OUTPUT(P)  ((CORE_PIN ## P ## _DDRREG & CORE_PIN ## P ## _BITMASK) == 0)
+
+#define READ(IO)              _READ(IO)
+
+#define WRITE_VAR(IO,V)       _WRITE_VAR(IO,V)
+#define WRITE(IO,V)           _WRITE(IO,V)
+#define TOGGLE(IO)            _TOGGLE(IO)
+
+#define SET_INPUT(IO)         _SET_INPUT(IO)
+#define SET_INPUT_PULLUP(IO)  _SET_INPUT_PULLUP(IO)
+#define SET_OUTPUT(IO)        _SET_OUTPUT(IO)
+
+#define GET_INPUT(IO)         _GET_INPUT(IO)
+#define GET_OUTPUT(IO)        _GET_OUTPUT(IO)
+
+#define OUT_WRITE(IO,V)       do{ SET_OUTPUT(IO); WRITE(IO,V); }while(0)
+
+/**
+ * Ports, functions, and pins
+ */
+
+#define DIO0_PIN 8
diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/persistent_store_impl.cpp b/Marlin/src/HAL/HAL_TEENSY31_32/persistent_store_impl.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..ac59212300cebd8ece2509665a611cd672f23770
--- /dev/null
+++ b/Marlin/src/HAL/HAL_TEENSY31_32/persistent_store_impl.cpp
@@ -0,0 +1,51 @@
+#ifdef __MK20DX256__
+
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(EEPROM_SETTINGS)
+
+#include "../persistent_store_api.h"
+
+namespace HAL {
+namespace PersistentStore {
+
+bool access_start() { return true; }
+bool access_finish() { return true; }
+
+bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
+  while (size--) {
+    uint8_t * const p = (uint8_t * const)pos;
+    uint8_t v = *value;
+    // EEPROM has only ~100,000 write cycles,
+    // so only write bytes that have changed!
+    if (v != eeprom_read_byte(p)) {
+      eeprom_write_byte(p, v);
+      if (eeprom_read_byte(p) != v) {
+        SERIAL_ECHO_START();
+        SERIAL_ECHOLNPGM(MSG_ERR_EEPROM_WRITE);
+        return true;
+      }
+    }
+    crc16(crc, &v, 1);
+    pos++;
+    value++;
+  };
+  return false;
+}
+
+bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const bool writing/*=true*/) {
+  do {
+    uint8_t c = eeprom_read_byte((unsigned char*)pos);
+    if (writing) *value = c;
+    crc16(crc, &c, 1);
+    pos++;
+    value++;
+  } while (--size);
+  return false;
+}
+
+} // PersistentStore
+} // HAL
+
+#endif // EEPROM_SETTINGS
+#endif // __MK20DX256__
diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/pinsDebug.h b/Marlin/src/HAL/HAL_TEENSY31_32/pinsDebug.h
new file mode 100644
index 0000000000000000000000000000000000000000..47b99ae317bf2a1aa2025404987293b5d1150cfe
--- /dev/null
+++ b/Marlin/src/HAL/HAL_TEENSY31_32/pinsDebug.h
@@ -0,0 +1 @@
+#error "Debug pins is not supported on the Teensy 3.1 / 3.2 Platform!"
diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/spi_pins.h b/Marlin/src/HAL/HAL_TEENSY31_32/spi_pins.h
new file mode 100644
index 0000000000000000000000000000000000000000..6a468682e8456f41588e53dfb7411585dddf8a56
--- /dev/null
+++ b/Marlin/src/HAL/HAL_TEENSY31_32/spi_pins.h
@@ -0,0 +1,28 @@
+/**
+ * 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/>.
+ *
+ */
+
+#pragma once
+
+#define SCK_PIN   13
+#define MISO_PIN  12
+#define MOSI_PIN  11
+#define SS_PIN    20 //SDSS // A.28, A.29, B.21, C.26, C.29
diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/watchdog_Teensy.cpp b/Marlin/src/HAL/HAL_TEENSY31_32/watchdog_Teensy.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..47774b3ac2fe9a5bc00faa590d537819d407db11
--- /dev/null
+++ b/Marlin/src/HAL/HAL_TEENSY31_32/watchdog_Teensy.cpp
@@ -0,0 +1,39 @@
+/**
+ * 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 __MK20DX256__
+
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(USE_WATCHDOG)
+
+#include "watchdog_Teensy.h"
+
+void watchdog_init() {
+  WDOG_TOVALH = 0;
+  WDOG_TOVALL = 4000;
+  WDOG_STCTRLH = WDOG_STCTRLH_WDOGEN;
+}
+
+#endif // USE_WATCHDOG
+
+#endif // __MK20DX256__
diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/watchdog_Teensy.h b/Marlin/src/HAL/HAL_TEENSY31_32/watchdog_Teensy.h
new file mode 100644
index 0000000000000000000000000000000000000000..2b8ec00a1d4ebb594a3c8ae489f91bc3ea7ecd04
--- /dev/null
+++ b/Marlin/src/HAL/HAL_TEENSY31_32/watchdog_Teensy.h
@@ -0,0 +1,35 @@
+/**
+ * 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/>.
+ *
+ */
+
+#pragma once
+
+#include "HAL.h"
+
+// Arduino Due core now has watchdog support
+
+void watchdog_init();
+
+inline void watchdog_reset() {
+  // Watchdog refresh sequence
+  WDOG_REFRESH = 0xA602;
+  WDOG_REFRESH = 0xB480;
+}
diff --git a/Marlin/src/HAL/platforms.h b/Marlin/src/HAL/platforms.h
index 1410b21f9c6d73184c30c736e8fb80338b94964b..49efe490d7f42a2a696f752eaa3cdf59520250fe 100644
--- a/Marlin/src/HAL/platforms.h
+++ b/Marlin/src/HAL/platforms.h
@@ -7,6 +7,8 @@
   #define HAL_PLATFORM HAL_AVR
 #elif defined(ARDUINO_ARCH_SAM)
   #define HAL_PLATFORM HAL_DUE
+#elif defined(__MK20DX256__)
+  #define HAL_PLATFORM HAL_TEENSY31_32
 #elif defined(__MK64FX512__) || defined(__MK66FX1M0__)
   #define HAL_PLATFORM HAL_TEENSY35_36
 #elif defined(TARGET_LPC1768)
diff --git a/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp b/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp
index b939be8803facb9188d9ffc2564357c33f486421..784987172ef67aa7caf147f7483863bc1e89d484 100644
--- a/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp
+++ b/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp
@@ -84,6 +84,17 @@
 #define END_FLASH_ADDR    0x08100000
 #endif
 
+#ifdef __MK20DX256__
+// For MK20DX256 in TEENSY 3.1 or TEENSY 3.2
+//  SRAM  (0x1FFF8000 - 0x20008000) (64kb)
+//  FLASH (0x00000000 - 0x00040000) (256kb)
+//
+#define START_SRAM_ADDR   0x1FFF8000
+#define END_SRAM_ADDR     0x20008000
+#define START_FLASH_ADDR  0x00000000
+#define END_FLASH_ADDR    0x00040000
+#endif
+
 #ifdef __MK64FX512__
 // For MK64FX512 in TEENSY 3.5
 //  SRAM  (0x1FFF0000 - 0x20020000) (192kb)
diff --git a/Marlin/src/HAL/shared/servo.h b/Marlin/src/HAL/shared/servo.h
index 16eefa5190edb0cd6d98e74e2a9cc4c64f3da067..b838a990569c5233fab1a6800eb9b7031a977e8f 100644
--- a/Marlin/src/HAL/shared/servo.h
+++ b/Marlin/src/HAL/shared/servo.h
@@ -66,12 +66,12 @@
  *                   With DEACTIVATE_SERVOS_AFTER_MOVE wait SERVO_DELAY and detach.
  */
 
-#ifndef SERVO_H
-#define SERVO_H
-
-#if IS_32BIT_TEENSY
-  #include "../HAL_TEENSY35_36/HAL_Servo_Teensy.h" // Teensy HAL uses an inherited library
+#pragma once
 
+#if IS_TEENSY32
+  #include "../HAL_TEENSY31_32/HAL_Servo_Teensy.h"
+#elif IS_TEENSY35 || IS_TEENSY36
+  #include "../HAL_TEENSY35_36/HAL_Servo_Teensy.h"
 #elif defined(TARGET_LPC1768)
   #include "../HAL_LPC1768/LPC1768_Servo.h"
 #elif defined(STM32F1) || defined(STM32F1xx)
@@ -111,5 +111,3 @@
   };
 
 #endif
-
-#endif // SERVO_H
diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h
index ba3b3aa7fa42461dcc439a803b7aefbad6d9a619..af75c749863a950efd0cd8f7509338c9cb76e00a 100644
--- a/Marlin/src/core/boards.h
+++ b/Marlin/src/core/boards.h
@@ -222,6 +222,7 @@
 // STM32 ARM Cortex-M4F
 //
 
+#define BOARD_TEENSY31_32      1552   // Teensy3.1 and Teensy3.2
 #define BOARD_TEENSY35_36       841   // Teensy3.5 and Teensy3.6
 #define BOARD_BEAST            1802   // STM32FxxxVxT6 Libmaple based stm32f4 controller
 #define BOARD_STM32F4          1804   // STM32 STM32GENERIC based STM32F4 controller
diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h
index 06f1526626b3b74da3f0b41ed92740c8a0a0c90e..19f34d58971a3a75fcfda9386e082208152138d8 100644
--- a/Marlin/src/pins/pins.h
+++ b/Marlin/src/pins/pins.h
@@ -381,6 +381,8 @@
 // STM32 ARM Cortex-M4F
 //
 
+#elif MB(TEENSY31_32)
+  #include "pins_TEENSY31_32.h"       // TEENSY31_32                                env:teensy31
 #elif MB(TEENSY35_36)
   #include "pins_TEENSY35_36.h"       // TEENSY35_36                                env:teensy35
 #elif MB(BEAST)
diff --git a/Marlin/src/pins/pins_TEENSY31_32.h b/Marlin/src/pins/pins_TEENSY31_32.h
new file mode 100644
index 0000000000000000000000000000000000000000..a37a2407d8f24b6a5f84294ae2163221526cb298
--- /dev/null
+++ b/Marlin/src/pins/pins_TEENSY31_32.h
@@ -0,0 +1,111 @@
+/**
+ * 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/>.
+ *
+ */
+
+/****************************************************************************************
+* Teensy 3.1 (MK20DX256) and Teensy 3.2 (MK20DX256) Breadboard pin assignments
+* Requires the Teensyduino software with Teensy 3.1 or Teensy 3.2 selected in Arduino IDE!
+* http://www.pjrc.com/teensy/teensyduino.html
+****************************************************************************************/
+
+#if !IS_32BIT_TEENSY
+  #error "Oops!  Make sure you have 'Teensy 3.1' or 'Teensy 3.2' selected from the 'Tools -> Boards' menu."
+#endif
+
+#if IS_TEENSY32
+  #define BOARD_NAME "Teensy3.2"
+#endif
+
+#define AT90USB 1286   // Disable MarlinSerial etc.
+#define USBCON //1286  // Disable MarlinSerial etc.
+
+//
+// Limit Switches
+//
+#define X_STOP_PIN         3
+#define Y_STOP_PIN         4
+#define Z_STOP_PIN         5
+
+//
+// Steppers
+//
+#define X_STEP_PIN         5
+#define X_DIR_PIN          6
+#define X_ENABLE_PIN       2
+
+#define Y_STEP_PIN         7
+#define Y_DIR_PIN          8
+#define Y_ENABLE_PIN       2
+
+#define Z_STEP_PIN         9
+#define Z_DIR_PIN          10
+#define Z_ENABLE_PIN       2
+
+#define E0_STEP_PIN        11
+#define E0_DIR_PIN         12
+#define E0_ENABLE_PIN      2
+
+// #define E1_STEP_PIN        33
+// #define E1_DIR_PIN         34
+// #define E1_ENABLE_PIN      35
+
+#define HEATER_0_PIN       20
+// #define HEATER_1_PIN       36
+#define HEATER_BED_PIN     21
+#ifndef FAN_PIN
+  #define FAN_PIN          22
+#endif
+
+#define TEMP_0_PIN         14   // Extruder / Analog pin numbering: 2 => A2
+// #define TEMP_1_PIN          0
+#define TEMP_BED_PIN       15   // Bed / Analog pin numbering
+
+// #define SDSS               16   // 8
+#define LED_PIN            13
+#define PS_ON_PIN          -1
+#define ALARM_PIN          -1
+
+// #define FILWIDTH_PIN        6
+// #define SOL1_PIN           28
+
+#if 0
+// Pretty sure this is obsolete!
+// Please use Marlin 1.1.x pins files as reference for new pins files.
+#ifndef SDSUPPORT
+  // these are defined in the SD library if building with SD support
+  #define SCK_PIN          13
+  #define MISO_PIN         12
+  #define MOSI_PIN         11
+#endif
+#endif
+/*
+#ifdef ULTRA_LCD
+  #define LCD_PINS_RS      40
+  #define LCD_PINS_ENABLE  41
+  #define LCD_PINS_D4      42
+  #define LCD_PINS_D5      43
+  #define LCD_PINS_D6      44
+  #define LCD_PINS_D7      45
+  #define BTN_EN1          46
+  #define BTN_EN2          47
+  #define BTN_ENC          48
+#endif
+*/