Browse Source

Support for Teensy 4 (#19311)

bilsef 4 years ago
parent
commit
049fbc92a9

+ 167 - 0
Marlin/src/HAL/TEENSY40_41/HAL.cpp

@@ -0,0 +1,167 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program.  If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+
+/**
+ * Description: HAL for Teensy40 (IMXRT1062)
+ */
+
+#ifdef __IMXRT1062__
+
+#include "HAL.h"
+#include "../shared/Delay.h"
+#include "timers.h"
+
+#include <Wire.h>
+
+uint16_t HAL_adc_result, HAL_adc_select;
+
+static const uint8_t pin2sc1a[] = {
+  0x07,  // 0/A0  AD_B1_02
+  0x08,  // 1/A1  AD_B1_03
+  0x0C,  // 2/A2  AD_B1_07
+  0x0B,  // 3/A3  AD_B1_06
+  0x06,  // 4/A4  AD_B1_01
+  0x05,  // 5/A5  AD_B1_00
+  0x0F,  // 6/A6  AD_B1_10
+  0x00,  // 7/A7  AD_B1_11
+  0x0D,  // 8/A8  AD_B1_08
+  0x0E,  // 9/A9  AD_B1_09
+  0x01,  // 24/A10 AD_B0_12
+  0x02,  // 25/A11 AD_B0_13
+  0x83,  // 26/A12 AD_B1_14 - only on ADC2, 3
+  0x84,  // 27/A13 AD_B1_15 - only on ADC2, 4
+  0x07,  // 14/A0  AD_B1_02
+  0x08,  // 15/A1  AD_B1_03
+  0x0C,  // 16/A2  AD_B1_07
+  0x0B,  // 17/A3  AD_B1_06
+  0x06,  // 18/A4  AD_B1_01
+  0x05,  // 19/A5  AD_B1_00
+  0x0F,  // 20/A6  AD_B1_10
+  0x00,  // 21/A7  AD_B1_11
+  0x0D,  // 22/A8  AD_B1_08
+  0x0E,  // 23/A9  AD_B1_09
+  0x01,  // 24/A10 AD_B0_12
+  0x02,  // 25/A11 AD_B0_13
+  0x83,  // 26/A12 AD_B1_14 - only on ADC2, 3
+  0x84,  // 27/A13 AD_B1_15 - only on ADC2, 4
+  #ifdef ARDUINO_TEENSY41
+    0xFF,  // 28
+    0xFF,  // 29
+    0xFF,  // 30
+    0xFF,  // 31
+    0xFF,  // 32
+    0xFF,  // 33
+    0xFF,  // 34
+    0xFF,  // 35
+    0xFF,  // 36
+    0xFF,  // 37
+    0x81,  // 38/A14 AD_B1_12 - only on ADC2, 1
+    0x82,  // 39/A15 AD_B1_13 - only on ADC2, 2
+    0x09,  // 40/A16 AD_B1_04
+    0x0A,  // 41/A17 AD_B1_05
+  #endif
+};
+
+/*
+// disable interrupts
+void cli() { noInterrupts(); }
+
+// enable interrupts
+void sei() { interrupts(); }
+*/
+
+void HAL_adc_init() {
+  analog_init();
+  while (ADC1_GC & ADC_GC_CAL) ;
+  while (ADC2_GC & ADC_GC_CAL) ;
+}
+
+void HAL_clear_reset_source() {
+  uint32_t reset_source = SRC_SRSR;
+  SRC_SRSR = reset_source;
+ }
+
+uint8_t HAL_get_reset_source() {
+  switch (SRC_SRSR & 0xFF) {
+    case 1: return RST_POWER_ON; break;
+    case 2: return RST_SOFTWARE; break;
+    case 4: return RST_EXTERNAL; break;
+    // case 8: return RST_BROWN_OUT; break;
+    case 16: return RST_WATCHDOG; break;
+     case 64: return RST_JTAG; break;
+    // case 128: return RST_OVERTEMP; break;
+  }
+  return 0;
+}
+
+#define __bss_end _ebss
+
+extern "C" {
+  extern char __bss_end;
+  extern char __heap_start;
+  extern void* __brkval;
+
+  // Doesn't work on Teensy 4.x
+  uint32_t freeMemory() {
+    uint32_t free_memory;
+    if ((uint32_t)__brkval == 0)
+      free_memory = ((uint32_t)&free_memory) - ((uint32_t)&__bss_end);
+    else
+      free_memory = ((uint32_t)&free_memory) - ((uint32_t)__brkval);
+    return free_memory;
+  }
+}
+
+void HAL_adc_start_conversion(const uint8_t adc_pin) {
+  const uint16_t pin = pin2sc1a[adc_pin];
+  if (pin == 0xFF) {
+    HAL_adc_select = -1; // Digital only
+  }
+  else if (pin & 0x80) {
+    HAL_adc_select = 1;
+    ADC2_HC0 = pin & 0x7F;
+  }
+  else {
+    HAL_adc_select = 0;
+    ADC1_HC0 = pin;
+  }
+}
+
+uint16_t HAL_adc_get_result() {
+  switch (HAL_adc_select) {
+    case 0:
+      while (!(ADC1_HS & ADC_HS_COCO0)) ; // wait
+      return ADC1_R0;
+    case 1:
+      while (!(ADC2_HS & ADC_HS_COCO0)) ; // wait
+      return ADC2_R0;
+  }
+  return 0;
+}
+
+bool is_output(uint8_t pin) {
+  const struct digital_pin_bitband_and_config_table_struct *p;
+  p = digital_pin_to_info_PGM + pin;
+  return (*(p->reg + 1) & p->mask);
+}
+
+#endif // __IMXRT1062__

+ 180 - 0
Marlin/src/HAL/TEENSY40_41/HAL.h

@@ -0,0 +1,180 @@
+/**
+ * Marlin 3D Printer Firmware
+ *
+ * Copyright (c) 2020 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 <https://www.gnu.org/licenses/>.
+ *
+ */
+#pragma once
+
+/**
+ * Description: HAL for Teensy 4.0 and Teensy 4.1
+ */
+
+#define CPU_32_BIT
+
+#include "../shared/Marduino.h"
+#include "../shared/math_32bit.h"
+#include "../shared/HAL_SPI.h"
+
+#include "fastio.h"
+#include "watchdog.h"
+
+#include <stdint.h>
+#include <util/atomic.h>
+
+//#define ST7920_DELAY_1 DELAY_NS(600)
+//#define ST7920_DELAY_2 DELAY_NS(750)
+//#define ST7920_DELAY_3 DELAY_NS(750)
+
+// ------------------------
+// Defines
+// ------------------------
+
+#ifdef __IMXRT1062__
+  #define IS_32BIT_TEENSY 1
+  #define IS_TEENSY41 1
+#endif
+
+#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
+#elif SERIAL_PORT == 4
+  #define MYSERIAL0 Serial4
+#elif SERIAL_PORT == 5
+  #define MYSERIAL0 Serial5
+#elif SERIAL_PORT == 6
+  #define MYSERIAL0 Serial6
+#elif SERIAL_PORT == 7
+  #define MYSERIAL0 Serial7
+#elif SERIAL_PORT == 8
+  #define MYSERIAL0 Serial8
+#else
+  #error "The required SERIAL_PORT must be from -1 to 8. Please update your configuration."
+#endif
+
+#ifdef SERIAL_PORT_2
+  #if SERIAL_PORT_2 == SERIAL_PORT
+    #error "SERIAL_PORT_2 must be different from SERIAL_PORT. Please update your configuration."
+  #elif SERIAL_PORT_2 == -1
+    #define MYSERIAL1 usbSerial
+  #elif SERIAL_PORT_2 == 0
+    #define MYSERIAL1 Serial
+  #elif SERIAL_PORT_2 == 1
+    #define MYSERIAL1 Serial1
+  #elif SERIAL_PORT_2 == 2
+    #define MYSERIAL1 Serial2
+  #elif SERIAL_PORT_2 == 3
+    #define MYSERIAL1 Serial3
+  #elif SERIAL_PORT_2 == 4
+    #define MYSERIAL1 Serial4
+  #elif SERIAL_PORT_2 == 5
+    #define MYSERIAL1 Serial5
+  #elif SERIAL_PORT_2 == 6
+    #define MYSERIAL1 Serial6
+  #elif SERIAL_PORT_2 == 7
+    #define MYSERIAL1 Serial7
+  #elif SERIAL_PORT_2 == 8
+    #define MYSERIAL1 Serial8
+  #else
+      #error "SERIAL_PORT_2 must be from -1 to 8. Please update your configuration."
+  #endif
+  #define NUM_SERIAL 2
+#else
+  #define NUM_SERIAL 1
+#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()
+
+#undef sq
+#define sq(x) ((x)*(x))
+
+#ifndef strncpy_P
+  #define strncpy_P(dest, src, num) strncpy((dest), (src), (num))
+#endif
+
+// Don't place string constants in PROGMEM
+#undef PSTR
+#define PSTR(str) ({static const char *data = (str); &data[0];})
+
+// Fix bug in pgm_read_ptr
+#undef pgm_read_ptr
+#define pgm_read_ptr(addr) (*((void**)(addr)))
+// Add type-checking to pgm_read_word
+#undef pgm_read_word
+#define pgm_read_word(addr) (*((uint16_t*)(addr)))
+
+// Enable hooks into idle and setup for HAL
+#define HAL_IDLETASK 1
+FORCE_INLINE void HAL_idletask() {}
+FORCE_INLINE void HAL_init() {}
+
+// Clear reset reason
+void HAL_clear_reset_source();
+
+// Reset reason
+uint8_t HAL_get_reset_source();
+
+FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
+
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wunused-function"
+extern "C" {
+  uint32_t freeMemory();
+}
+#pragma GCC diagnostic pop
+
+// ADC
+
+void HAL_adc_init();
+
+#define HAL_ADC_VREF         3.3
+#define HAL_ADC_RESOLUTION  10
+#define HAL_ADC_FILTERED      // turn off ADC oversampling
+#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
+#define HAL_READ_ADC()      HAL_adc_get_result()
+#define HAL_ADC_READY()     true
+
+#define HAL_ANALOG_SELECT(pin)
+
+void HAL_adc_start_conversion(const uint8_t adc_pin);
+uint16_t HAL_adc_get_result();
+
+#define GET_PIN_MAP_PIN(index) index
+#define GET_PIN_MAP_INDEX(pin) pin
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
+
+bool is_output(uint8_t pin);

+ 138 - 0
Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp

@@ -0,0 +1,138 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program.  If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#ifdef __IMXRT1062__
+
+#include "HAL.h"
+#include <SPI.h>
+#include <pins_arduino.h>
+#include "spi_pins.h"
+#include "../../core/macros.h"
+
+static SPISettings spiConfig;
+
+// ------------------------
+// Public functions
+// ------------------------
+
+#if ENABLED(SOFTWARE_SPI)
+  // ------------------------
+  // Software SPI
+  // ------------------------
+  #error "Software SPI not supported for Teensy 4. Use Hardware SPI."
+#else
+
+// ------------------------
+// Hardware SPI
+// ------------------------
+
+void spiBegin() {
+  #ifndef SS_PIN
+    #error "SS_PIN is not defined!"
+  #endif
+
+  OUT_WRITE(SS_PIN, HIGH);
+
+  //SET_OUTPUT(SCK_PIN);
+  //SET_INPUT(MISO_PIN);
+  //SET_OUTPUT(MOSI_PIN);
+
+  #if 0 && DISABLED(SOFTWARE_SPI)
+    // 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
+}
+
+void spiInit(uint8_t spiRate) {
+  // Use Marlin data-rates
+  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();
+}
+
+uint8_t spiRec() {
+  SPI.beginTransaction(spiConfig);
+  uint8_t returnByte = SPI.transfer(0xFF);
+  SPI.endTransaction();
+  return returnByte;
+  //SPDR = 0xFF;
+  //while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
+  //return SPDR;
+}
+
+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;
+}
+
+void spiSend(uint8_t b) {
+  SPI.beginTransaction(spiConfig);
+  SPI.transfer(b);
+  SPI.endTransaction();
+  //SPDR = b;
+  //while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
+}
+
+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 // SOFTWARE_SPI
+#endif // __IMXRT1062__

+ 57 - 0
Marlin/src/HAL/TEENSY40_41/Servo.cpp

@@ -0,0 +1,57 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program.  If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#ifdef __IMXRT1062__
+
+#include "../../inc/MarlinConfig.h"
+
+#if HAS_SERVOS
+
+#include "Servo.h"
+
+int8_t libServo::attach(const int inPin) {
+  if (inPin > 0) servoPin = inPin;
+  return super::attach(servoPin);
+}
+
+int8_t libServo::attach(const int inPin, const int inMin, const int inMax) {
+  if (inPin > 0) servoPin = inPin;
+  return super::attach(servoPin, inMin, inMax);
+}
+
+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 (attach(0) >= 0) {
+    write(value);
+    safe_delay(servo_delay[servoIndex]);
+    TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
+  }
+}
+
+void libServo::detach() {
+  // PWMServo library does not have detach() function
+  //super::detach();
+}
+
+#endif // HAS_SERVOS
+
+#endif // __IMXRT1062__

+ 39 - 0
Marlin/src/HAL/TEENSY40_41/Servo.h

@@ -0,0 +1,39 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program.  If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#pragma once
+
+#include <PWMServo.h>
+
+// Inherit and expand on core Servo library
+class libServo : public PWMServo {
+  public:
+    int8_t attach(const int pin);
+    int8_t attach(const int pin, const int min, const int max);
+    void move(const int value);
+    void detach(void);
+  private:
+    typedef PWMServo super;
+    uint8_t servoPin;
+    uint16_t min_ticks;
+    uint16_t max_ticks;
+    uint8_t servoIndex; // Index into the channel data for this servo
+};

+ 77 - 0
Marlin/src/HAL/TEENSY40_41/eeprom.cpp

@@ -0,0 +1,77 @@
+/**
+ * Marlin 3D Printer Firmware
+ *
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
+ * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
+ * Copyright (c) 2016 Victor Perez victor_pv@hotmail.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 <https://www.gnu.org/licenses/>.
+ *
+ */
+#ifdef __IMXRT1062__
+
+#include "../../inc/MarlinConfig.h"
+
+#if USE_WIRED_EEPROM
+
+/**
+ * PersistentStore for Arduino-style EEPROM interface
+ * with implementations supplied by the framework.
+ */
+
+#include "../shared/eeprom_api.h"
+#include <avr/eeprom.h>
+
+#ifndef MARLIN_EEPROM_SIZE
+  #define MARLIN_EEPROM_SIZE size_t(E2END + 1)
+#endif
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+
+bool PersistentStore::access_start()  { return true; }
+bool PersistentStore::access_finish() { return true; }
+
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+  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_MSG(STR_ERR_EEPROM_WRITE);
+        return true;
+      }
+    }
+    crc16(crc, &v, 1);
+    pos++;
+    value++;
+  }
+  return false;
+}
+
+bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
+  do {
+    uint8_t c = eeprom_read_byte((uint8_t*)pos);
+    if (writing) *value = c;
+    crc16(crc, &c, 1);
+    pos++;
+    value++;
+  } while (--size);
+  return false;
+}
+
+#endif // USE_WIRED_EEPROM
+#endif // __IMXRT1062__

+ 66 - 0
Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h

@@ -0,0 +1,66 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program.  If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#pragma once
+
+/**
+ * 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)
+ */
+
+#include "../../module/endstops.h"
+
+// One ISR for all EXT-Interrupts
+void endstop_ISR() { endstops.update(); }
+
+/**
+ * Endstop interrupts for Due based targets.
+ * On Due, all pins support external interrupt capability.
+ */
+void setup_endstop_interrupts() {
+  #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
+  TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN));
+  TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN));
+  TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN));
+  TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN));
+  TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN));
+  TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN));
+  TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN));
+  TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN));
+  TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN));
+  TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN));
+  TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN));
+  TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN));
+  TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN));
+  TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN));
+  TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
+  TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
+  TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
+}

+ 58 - 0
Marlin/src/HAL/TEENSY40_41/fastio.h

@@ -0,0 +1,58 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ * Copyright (c) 2017 Victor Perez
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program.  If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#pragma once
+
+/**
+ * Fast I/O interfaces for Teensy 4
+ * These use GPIO functions instead of Direct Port Manipulation, as on AVR.
+ */
+
+#ifndef PWM
+  #define PWM OUTPUT
+#endif
+
+#define READ(IO)                digitalRead(IO)
+#define WRITE(IO,V)             digitalWrite(IO,V)
+
+#define _GET_MODE(IO)           !is_output(IO)
+#define _SET_MODE(IO,M)         pinMode(IO, M)
+#define _SET_OUTPUT(IO)         pinMode(IO, OUTPUT)                               /*!< Output Push Pull Mode & GPIO_NOPULL   */
+
+#define OUT_WRITE(IO,V)         do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
+
+#define SET_INPUT(IO)           _SET_MODE(IO, INPUT)                              /*!< Input Floating Mode                   */
+#define SET_INPUT_PULLUP(IO)    _SET_MODE(IO, INPUT_PULLUP)                       /*!< Input with Pull-up activation         */
+#define SET_INPUT_PULLDOWN(IO)  _SET_MODE(IO, INPUT_PULLDOWN)                     /*!< Input with Pull-down activation       */
+#define SET_OUTPUT(IO)          OUT_WRITE(IO, LOW)
+#define SET_PWM(IO)             _SET_MODE(IO, PWM)
+
+#define TOGGLE(IO)              OUT_WRITE(IO, !READ(IO))
+
+#define IS_INPUT(IO)            !is_output(IO)
+#define IS_OUTPUT(IO)           is_output(IO)
+
+#define PWM_PIN(P)            digitalPinHasPWM(P)
+
+// digitalRead/Write wrappers
+#define extDigitalRead(IO)    digitalRead(IO)
+#define extDigitalWrite(IO,V) digitalWrite(IO,V)

+ 26 - 0
Marlin/src/HAL/TEENSY40_41/inc/Conditionals_LCD.h

@@ -0,0 +1,26 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program.  If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#pragma once
+
+#if HAS_SPI_TFT || HAS_FSMC_TFT
+  #error "Sorry! TFT displays are not available for HAL/TEENSY40_41."
+#endif

+ 22 - 0
Marlin/src/HAL/TEENSY40_41/inc/Conditionals_adv.h

@@ -0,0 +1,22 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program.  If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#pragma once

Some files were not shown because too many files changed in this diff