aboutsummaryrefslogtreecommitdiff
path: root/Marlin/src/HAL/STM32
diff options
context:
space:
mode:
Diffstat (limited to 'Marlin/src/HAL/STM32')
-rw-r--r--Marlin/src/HAL/STM32/HAL.cpp163
-rw-r--r--Marlin/src/HAL/STM32/HAL.h214
-rw-r--r--Marlin/src/HAL/STM32/HAL_SPI.cpp219
-rw-r--r--Marlin/src/HAL/STM32/MarlinSPI.cpp168
-rw-r--r--Marlin/src/HAL/STM32/MarlinSPI.h107
-rw-r--r--Marlin/src/HAL/STM32/MarlinSerial.cpp89
-rw-r--r--Marlin/src/HAL/STM32/MarlinSerial.h56
-rw-r--r--Marlin/src/HAL/STM32/README.md11
-rw-r--r--Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp328
-rw-r--r--Marlin/src/HAL/STM32/Servo.cpp110
-rw-r--r--Marlin/src/HAL/STM32/Servo.h54
-rw-r--r--Marlin/src/HAL/STM32/eeprom_flash.cpp269
-rw-r--r--Marlin/src/HAL/STM32/eeprom_sdcard.cpp91
-rw-r--r--Marlin/src/HAL/STM32/eeprom_sram.cpp68
-rw-r--r--Marlin/src/HAL/STM32/eeprom_wired.cpp81
-rw-r--r--Marlin/src/HAL/STM32/endstop_interrupts.h49
-rw-r--r--Marlin/src/HAL/STM32/fast_pwm.cpp59
-rw-r--r--Marlin/src/HAL/STM32/fastio.cpp34
-rw-r--r--Marlin/src/HAL/STM32/fastio.h90
-rw-r--r--Marlin/src/HAL/STM32/inc/Conditionals_LCD.h22
-rw-r--r--Marlin/src/HAL/STM32/inc/Conditionals_adv.h26
-rw-r--r--Marlin/src/HAL/STM32/inc/Conditionals_post.h29
-rw-r--r--Marlin/src/HAL/STM32/inc/SanityCheck.h57
-rw-r--r--Marlin/src/HAL/STM32/msc_sd.cpp109
-rw-r--r--Marlin/src/HAL/STM32/msc_sd.h20
-rw-r--r--Marlin/src/HAL/STM32/pinsDebug.h264
-rw-r--r--Marlin/src/HAL/STM32/pins_Xref.h612
-rw-r--r--Marlin/src/HAL/STM32/spi_pins.h35
-rw-r--r--Marlin/src/HAL/STM32/tft/tft_fsmc.cpp181
-rw-r--r--Marlin/src/HAL/STM32/tft/tft_fsmc.h171
-rw-r--r--Marlin/src/HAL/STM32/tft/tft_spi.cpp235
-rw-r--r--Marlin/src/HAL/STM32/tft/tft_spi.h74
-rw-r--r--Marlin/src/HAL/STM32/tft/xpt2046.cpp170
-rw-r--r--Marlin/src/HAL/STM32/tft/xpt2046.h81
-rw-r--r--Marlin/src/HAL/STM32/timers.cpp322
-rw-r--r--Marlin/src/HAL/STM32/timers.h127
-rw-r--r--Marlin/src/HAL/STM32/usb_host.cpp117
-rw-r--r--Marlin/src/HAL/STM32/usb_host.h60
-rw-r--r--Marlin/src/HAL/STM32/usb_serial.cpp54
-rw-r--r--Marlin/src/HAL/STM32/usb_serial.h21
-rw-r--r--Marlin/src/HAL/STM32/watchdog.cpp49
-rw-r--r--Marlin/src/HAL/STM32/watchdog.h25
42 files changed, 5121 insertions, 0 deletions
diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp
new file mode 100644
index 0000000..06744f1
--- /dev/null
+++ b/Marlin/src/HAL/STM32/HAL.cpp
@@ -0,0 +1,163 @@
+/**
+ * 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) 2017 Victor Perez
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "HAL.h"
+#include "usb_serial.h"
+
+#include "../../inc/MarlinConfig.h"
+#include "../shared/Delay.h"
+
+#ifdef USBCON
+ DefaultSerial MSerial(false, SerialUSB);
+#endif
+
+#if ENABLED(SRAM_EEPROM_EMULATION)
+ #if STM32F7xx
+ #include <stm32f7xx_ll_pwr.h>
+ #elif STM32F4xx
+ #include <stm32f4xx_ll_pwr.h>
+ #else
+ #error "SRAM_EEPROM_EMULATION is currently only supported for STM32F4xx and STM32F7xx"
+ #endif
+#endif
+
+#if HAS_SD_HOST_DRIVE
+ #include "msc_sd.h"
+ #include "usbd_cdc_if.h"
+#endif
+
+// ------------------------
+// Public Variables
+// ------------------------
+
+uint16_t HAL_adc_result;
+
+// ------------------------
+// Public functions
+// ------------------------
+
+// Needed for DELAY_NS() / DELAY_US() on CORTEX-M7
+#if (defined(__arm__) || defined(__thumb__)) && __CORTEX_M == 7
+ // HAL pre-initialization task
+ // Force the preinit function to run between the premain() and main() function
+ // of the STM32 arduino core
+ __attribute__((constructor (102)))
+ void HAL_preinit() {
+ enableCycleCounter();
+ }
+#endif
+
+// HAL initialization task
+void HAL_init() {
+ FastIO_init();
+
+ #if ENABLED(SDSUPPORT) && DISABLED(SDIO_SUPPORT) && (defined(SDSS) && SDSS != -1)
+ OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up
+ #endif
+
+ #if PIN_EXISTS(LED)
+ OUT_WRITE(LED_PIN, LOW);
+ #endif
+
+ #if ENABLED(SRAM_EEPROM_EMULATION)
+ __HAL_RCC_PWR_CLK_ENABLE();
+ HAL_PWR_EnableBkUpAccess(); // Enable access to backup SRAM
+ __HAL_RCC_BKPSRAM_CLK_ENABLE();
+ LL_PWR_EnableBkUpRegulator(); // Enable backup regulator
+ while (!LL_PWR_IsActiveFlag_BRR()); // Wait until backup regulator is initialized
+ #endif
+
+ SetTimerInterruptPriorities();
+
+ #if ENABLED(EMERGENCY_PARSER) && USBD_USE_CDC
+ USB_Hook_init();
+ #endif
+
+ #if HAS_SD_HOST_DRIVE
+ MSC_SD_init(); // Enable USB SD card access
+ #endif
+}
+
+// HAL idle task
+void HAL_idletask() {
+ #if HAS_SHARED_MEDIA
+ // Stm32duino currently doesn't have a "loop/idle" method
+ CDC_resume_receive();
+ CDC_continue_transmit();
+ #endif
+}
+
+void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); }
+
+uint8_t HAL_get_reset_source() {
+ return
+ #ifdef RCC_FLAG_IWDGRST // Some sources may not exist...
+ RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) ? RST_WATCHDOG :
+ #endif
+ #ifdef RCC_FLAG_IWDG1RST
+ RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_IWDG1RST) ? RST_WATCHDOG :
+ #endif
+ #ifdef RCC_FLAG_IWDG2RST
+ RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_IWDG2RST) ? RST_WATCHDOG :
+ #endif
+ #ifdef RCC_FLAG_SFTRST
+ RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST) ? RST_SOFTWARE :
+ #endif
+ #ifdef RCC_FLAG_PINRST
+ RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_PINRST) ? RST_EXTERNAL :
+ #endif
+ #ifdef RCC_FLAG_PORRST
+ RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_PORRST) ? RST_POWER_ON :
+ #endif
+ 0
+ ;
+}
+
+void _delay_ms(const int delay_ms) { delay(delay_ms); }
+
+extern "C" {
+ extern unsigned int _ebss; // end of bss section
+}
+
+// ------------------------
+// ADC
+// ------------------------
+
+// TODO: Make sure this doesn't cause any delay
+void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); }
+uint16_t HAL_adc_get_result() { return HAL_adc_result; }
+
+// Reset the system (to initiate a firmware flash)
+void flashFirmware(const int16_t) { NVIC_SystemReset(); }
+
+// Maple Compatibility
+volatile uint32_t systick_uptime_millis = 0;
+systickCallback_t systick_user_callback;
+void systick_attach_callback(systickCallback_t cb) { systick_user_callback = cb; }
+void HAL_SYSTICK_Callback() {
+ systick_uptime_millis++;
+ if (systick_user_callback) systick_user_callback();
+}
+
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h
new file mode 100644
index 0000000..8f6c0a5
--- /dev/null
+++ b/Marlin/src/HAL/STM32/HAL.h
@@ -0,0 +1,214 @@
+/**
+ * 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) 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
+
+#define CPU_32_BIT
+
+#include "../../core/macros.h"
+#include "../shared/Marduino.h"
+#include "../shared/math_32bit.h"
+#include "../shared/HAL_SPI.h"
+#include "fastio.h"
+#include "Servo.h"
+#include "watchdog.h"
+#include "MarlinSerial.h"
+
+#include "../../inc/MarlinConfigPre.h"
+
+#include <stdint.h>
+
+#ifdef USBCON
+ #include <USBSerial.h>
+ #include "../../core/serial_hook.h"
+ typedef ForwardSerial0Type< decltype(SerialUSB) > DefaultSerial;
+ extern DefaultSerial MSerial;
+#endif
+
+// ------------------------
+// Defines
+// ------------------------
+#define _MSERIAL(X) MSerial##X
+#define MSERIAL(X) _MSERIAL(X)
+
+#if SERIAL_PORT == -1
+ #define MYSERIAL0 MSerial
+#elif WITHIN(SERIAL_PORT, 1, 6)
+ #define MYSERIAL0 MSERIAL(SERIAL_PORT)
+#else
+ #error "SERIAL_PORT must be -1 or from 1 to 6. Please update your configuration."
+#endif
+
+#ifdef SERIAL_PORT_2
+ #if SERIAL_PORT_2 == -1
+ #define MYSERIAL1 MSerial
+ #elif WITHIN(SERIAL_PORT_2, 1, 6)
+ #define MYSERIAL1 MSERIAL(SERIAL_PORT_2)
+ #else
+ #error "SERIAL_PORT_2 must be -1 or from 1 to 6. Please update your configuration."
+ #endif
+#endif
+
+#ifdef MMU2_SERIAL_PORT
+ #if MMU2_SERIAL_PORT == -1
+ #define MMU2_SERIAL MSerial
+ #elif WITHIN(MMU2_SERIAL_PORT, 1, 6)
+ #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT)
+ #else
+ #error "MMU2_SERIAL_PORT must be -1 or from 1 to 6. Please update your configuration."
+ #endif
+#endif
+
+#ifdef LCD_SERIAL_PORT
+ #if LCD_SERIAL_PORT == -1
+ #define LCD_SERIAL MSerial
+ #elif WITHIN(LCD_SERIAL_PORT, 1, 6)
+ #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT)
+ #else
+ #error "LCD_SERIAL_PORT must be -1 or from 1 to 6. Please update your configuration."
+ #endif
+ #if HAS_DGUS_LCD
+ #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite()
+ #endif
+#endif
+
+/**
+ * TODO: review this to return 1 for pins that are not analog input
+ */
+#ifndef analogInputToDigitalPin
+ #define analogInputToDigitalPin(p) (p)
+#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()
+#define cli() __disable_irq()
+#define sei() __enable_irq()
+
+// On AVR this is in math.h?
+#define square(x) ((x)*(x))
+
+// ------------------------
+// Types
+// ------------------------
+
+typedef int16_t pin_t;
+
+#define HAL_SERVO_LIB libServo
+#define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos()
+#define RESUME_SERVO_OUTPUT() libServo::resume_all_servos()
+
+// ------------------------
+// Public Variables
+// ------------------------
+
+// result of last ADC conversion
+extern uint16_t HAL_adc_result;
+
+// ------------------------
+// Public functions
+// ------------------------
+
+// Memory related
+#define __bss_end __bss_end__
+
+// Enable hooks into setup for HAL
+void HAL_init();
+#define HAL_IDLETASK 1
+void HAL_idletask();
+
+// Clear reset reason
+void HAL_clear_reset_source();
+
+// Reset reason
+uint8_t HAL_get_reset_source();
+
+inline void HAL_reboot() {} // reboot the board or restart the bootloader
+
+void _delay_ms(const int delay);
+
+extern "C" char* _sbrk(int incr);
+
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wunused-function"
+
+static inline int freeMemory() {
+ volatile char top;
+ return &top - reinterpret_cast<char*>(_sbrk(0));
+}
+
+#pragma GCC diagnostic pop
+
+//
+// ADC
+//
+
+#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT)
+
+#define HAL_ADC_VREF 3.3
+#define HAL_ADC_RESOLUTION ADC_RESOLUTION // 12
+#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
+#define HAL_READ_ADC() HAL_adc_result
+#define HAL_ADC_READY() true
+
+inline void HAL_adc_init() { analogReadResolution(HAL_ADC_RESOLUTION); }
+
+void HAL_adc_start_conversion(const uint8_t adc_pin);
+
+uint16_t HAL_adc_get_result();
+
+#define GET_PIN_MAP_PIN(index) index
+#define GET_PIN_MAP_INDEX(pin) pin
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
+
+#ifdef STM32F1xx
+ #define JTAG_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_JTAGDISABLE)
+ #define JTAGSWD_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_DISABLE)
+#endif
+
+#define PLATFORM_M997_SUPPORT
+void flashFirmware(const int16_t);
+
+// Maple Compatibility
+typedef void (*systickCallback_t)(void);
+void systick_attach_callback(systickCallback_t cb);
+void HAL_SYSTICK_Callback();
+extern volatile uint32_t systick_uptime_millis;
+
+#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment
+
+/**
+ * set_pwm_frequency
+ * Set the frequency of the timer corresponding to the provided pin
+ * All Timer PWM pins run at the same frequency
+ */
+void set_pwm_frequency(const pin_t pin, int f_desired);
+
+/**
+ * set_pwm_duty
+ * Set the PWM duty cycle of the provided pin to the provided value
+ * Optionally allows inverting the duty cycle [default = false]
+ * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255]
+ */
+void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp
new file mode 100644
index 0000000..eef4807
--- /dev/null
+++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp
@@ -0,0 +1,219 @@
+/**
+ * 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/>.
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../inc/MarlinConfig.h"
+
+#include <SPI.h>
+
+// ------------------------
+// Public Variables
+// ------------------------
+
+static SPISettings spiConfig;
+
+// ------------------------
+// Public functions
+// ------------------------
+
+#if ENABLED(SOFTWARE_SPI)
+
+ // ------------------------
+ // Software SPI
+ // ------------------------
+
+ #include "../shared/Delay.h"
+
+ void spiBegin(void) {
+ OUT_WRITE(SD_SS_PIN, HIGH);
+ OUT_WRITE(SD_SCK_PIN, HIGH);
+ SET_INPUT(SD_MISO_PIN);
+ OUT_WRITE(SD_MOSI_PIN, HIGH);
+ }
+
+ static uint16_t delay_STM32_soft_spi;
+
+ void spiInit(uint8_t spiRate) {
+ // Use datarates Marlin uses
+ switch (spiRate) {
+ case SPI_FULL_SPEED: delay_STM32_soft_spi = 125; break; // desired: 8,000,000 actual: ~1.1M
+ case SPI_HALF_SPEED: delay_STM32_soft_spi = 125; break; // desired: 4,000,000 actual: ~1.1M
+ case SPI_QUARTER_SPEED:delay_STM32_soft_spi = 250; break; // desired: 2,000,000 actual: ~890K
+ case SPI_EIGHTH_SPEED: delay_STM32_soft_spi = 500; break; // desired: 1,000,000 actual: ~590K
+ case SPI_SPEED_5: delay_STM32_soft_spi = 1000; break; // desired: 500,000 actual: ~360K
+ case SPI_SPEED_6: delay_STM32_soft_spi = 2000; break; // desired: 250,000 actual: ~210K
+ default: delay_STM32_soft_spi = 4000; break; // desired: 125,000 actual: ~123K
+ }
+ SPI.begin();
+ }
+
+ // Begin SPI transaction, set clock, bit order, data mode
+ void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { /* do nothing */ }
+
+ uint8_t HAL_SPI_STM32_SpiTransfer_Mode_3(uint8_t b) { // using Mode 3
+ for (uint8_t bits = 8; bits--;) {
+ WRITE(SD_SCK_PIN, LOW);
+ WRITE(SD_MOSI_PIN, b & 0x80);
+
+ DELAY_NS(delay_STM32_soft_spi);
+ WRITE(SD_SCK_PIN, HIGH);
+ DELAY_NS(delay_STM32_soft_spi);
+
+ b <<= 1; // little setup time
+ b |= (READ(SD_MISO_PIN) != 0);
+ }
+ DELAY_NS(125);
+ return b;
+ }
+
+ // Soft SPI receive byte
+ uint8_t spiRec() {
+ DISABLE_ISRS(); // No interrupts during byte receive
+ const uint8_t data = HAL_SPI_STM32_SpiTransfer_Mode_3(0xFF);
+ ENABLE_ISRS(); // Enable interrupts
+ return data;
+ }
+
+ // Soft SPI read data
+ void spiRead(uint8_t *buf, uint16_t nbyte) {
+ for (uint16_t i = 0; i < nbyte; i++)
+ buf[i] = spiRec();
+ }
+
+ // Soft SPI send byte
+ void spiSend(uint8_t data) {
+ DISABLE_ISRS(); // No interrupts during byte send
+ HAL_SPI_STM32_SpiTransfer_Mode_3(data); // Don't care what is received
+ ENABLE_ISRS(); // Enable interrupts
+ }
+
+ // Soft SPI send block
+ void spiSendBlock(uint8_t token, const uint8_t *buf) {
+ spiSend(token);
+ for (uint16_t i = 0; i < 512; i++)
+ spiSend(buf[i]);
+ }
+
+#else
+
+ // ------------------------
+ // Hardware SPI
+ // ------------------------
+
+ /**
+ * VGPV SPI speed start and PCLK2/2, by default 108/2 = 54Mhz
+ */
+
+ /**
+ * @brief Begin SPI port setup
+ *
+ * @return Nothing
+ *
+ * @details Only configures SS pin since stm32duino creates and initialize the SPI object
+ */
+ void spiBegin() {
+ #if PIN_EXISTS(SD_SS)
+ OUT_WRITE(SD_SS_PIN, HIGH);
+ #endif
+ }
+
+ // Configure SPI for specified SPI speed
+ void spiInit(uint8_t spiRate) {
+ // Use datarates Marlin uses
+ uint32_t clock;
+ switch (spiRate) {
+ case SPI_FULL_SPEED: clock = 20000000; break; // 13.9mhz=20000000 6.75mhz=10000000 3.38mhz=5000000 .833mhz=1000000
+ 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 = 300000; break;
+ default:
+ clock = 4000000; // Default from the SPI library
+ }
+ spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0);
+
+ #if ENABLED(CUSTOM_SPI_PINS)
+ SPI.setMISO(SD_MISO_PIN);
+ SPI.setMOSI(SD_MOSI_PIN);
+ SPI.setSCLK(SD_SCK_PIN);
+ #endif
+
+ SPI.begin();
+ }
+
+ /**
+ * @brief Receives a single byte from the SPI port.
+ *
+ * @return Byte received
+ *
+ * @details
+ */
+ uint8_t spiRec() {
+ uint8_t returnByte = SPI.transfer(0xFF);
+ return returnByte;
+ }
+
+ /**
+ * @brief Receive a number of bytes from the SPI port to a buffer
+ *
+ * @param buf Pointer to starting address of buffer to write to.
+ * @param nbyte Number of bytes to receive.
+ * @return Nothing
+ *
+ * @details Uses DMA
+ */
+ void spiRead(uint8_t* buf, uint16_t nbyte) {
+ if (nbyte == 0) return;
+ memset(buf, 0xFF, nbyte);
+ SPI.transfer(buf, nbyte);
+ }
+
+ /**
+ * @brief Send a single byte on SPI port
+ *
+ * @param b Byte to send
+ *
+ * @details
+ */
+ void spiSend(uint8_t b) {
+ SPI.transfer(b);
+ }
+
+ /**
+ * @brief Write token and then write from 512 byte buffer to SPI (for SD card)
+ *
+ * @param buf Pointer with buffer start address
+ * @return Nothing
+ *
+ * @details Use DMA
+ */
+ void spiSendBlock(uint8_t token, const uint8_t* buf) {
+ uint8_t rxBuf[512];
+ SPI.transfer(token);
+ SPI.transfer((uint8_t*)buf, &rxBuf, 512);
+ }
+
+#endif // SOFTWARE_SPI
+
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/MarlinSPI.cpp b/Marlin/src/HAL/STM32/MarlinSPI.cpp
new file mode 100644
index 0000000..5086b41
--- /dev/null
+++ b/Marlin/src/HAL/STM32/MarlinSPI.cpp
@@ -0,0 +1,168 @@
+/**
+ * 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/>.
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "MarlinSPI.h"
+
+static void spi_init(spi_t *obj, uint32_t speed, spi_mode_e mode, uint8_t msb, uint32_t dataSize) {
+ spi_init(obj, speed, mode, msb);
+ // spi_init set 8bit always
+ // TODO: copy the code from spi_init and handle data size, to avoid double init always!!
+ if (dataSize != SPI_DATASIZE_8BIT) {
+ obj->handle.Init.DataSize = dataSize;
+ HAL_SPI_Init(&obj->handle);
+ __HAL_SPI_ENABLE(&obj->handle);
+ }
+}
+
+void MarlinSPI::setClockDivider(uint8_t _div) {
+ _speed = spi_getClkFreq(&_spi);// / _div;
+ _clockDivider = _div;
+}
+
+void MarlinSPI::begin(void) {
+ //TODO: only call spi_init if any parameter changed!!
+ spi_init(&_spi, _speed, _dataMode, _bitOrder, _dataSize);
+}
+
+void MarlinSPI::setupDma(SPI_HandleTypeDef &_spiHandle, DMA_HandleTypeDef &_dmaHandle, uint32_t direction, bool minc) {
+ _dmaHandle.Init.Direction = direction;
+ _dmaHandle.Init.PeriphInc = DMA_PINC_DISABLE;
+ _dmaHandle.Init.Mode = DMA_NORMAL;
+ _dmaHandle.Init.Priority = DMA_PRIORITY_LOW;
+ _dmaHandle.Init.MemInc = minc ? DMA_MINC_ENABLE : DMA_MINC_DISABLE;
+
+ if (_dataSize == DATA_SIZE_8BIT) {
+ _dmaHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
+ _dmaHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
+ }
+ else {
+ _dmaHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD;
+ _dmaHandle.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD;
+ }
+ #ifdef STM32F4xx
+ _dmaHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
+ #endif
+
+ // start DMA hardware
+ // TODO: check if hardware is already enabled
+ #ifdef SPI1_BASE
+ if (_spiHandle.Instance == SPI1) {
+ #ifdef STM32F1xx
+ __HAL_RCC_DMA1_CLK_ENABLE();
+ _dmaHandle.Instance = (direction == DMA_MEMORY_TO_PERIPH) ? DMA1_Channel3 : DMA1_Channel2;
+ #elif defined(STM32F4xx)
+ __HAL_RCC_DMA2_CLK_ENABLE();
+ _dmaHandle.Init.Channel = DMA_CHANNEL_3;
+ _dmaHandle.Instance = (direction == DMA_MEMORY_TO_PERIPH) ? DMA2_Stream3 : DMA2_Stream0;
+ #endif
+ }
+ #endif
+ #ifdef SPI2_BASE
+ if (_spiHandle.Instance == SPI2) {
+ #ifdef STM32F1xx
+ __HAL_RCC_DMA1_CLK_ENABLE();
+ _dmaHandle.Instance = (direction == DMA_MEMORY_TO_PERIPH) ? DMA1_Channel5 : DMA1_Channel4;
+ #elif defined(STM32F4xx)
+ __HAL_RCC_DMA1_CLK_ENABLE();
+ _dmaHandle.Init.Channel = DMA_CHANNEL_0;
+ _dmaHandle.Instance = (direction == DMA_MEMORY_TO_PERIPH) ? DMA1_Stream4 : DMA1_Stream3;
+ #endif
+ }
+ #endif
+ #ifdef SPI3_BASE
+ if (_spiHandle.Instance == SPI3) {
+ #ifdef STM32F1xx
+ __HAL_RCC_DMA2_CLK_ENABLE();
+ _dmaHandle.Instance = (direction == DMA_MEMORY_TO_PERIPH) ? DMA2_Channel2 : DMA2_Channel1;
+ #elif defined(STM32F4xx)
+ __HAL_RCC_DMA1_CLK_ENABLE();
+ _dmaHandle.Init.Channel = DMA_CHANNEL_0;
+ _dmaHandle.Instance = (direction == DMA_MEMORY_TO_PERIPH) ? DMA1_Stream5 : DMA1_Stream2;
+ #endif
+ }
+ #endif
+
+ HAL_DMA_Init(&_dmaHandle);
+}
+
+byte MarlinSPI::transfer(uint8_t _data) {
+ uint8_t rxData = 0xFF;
+ HAL_SPI_TransmitReceive(&_spi.handle, &_data, &rxData, 1, HAL_MAX_DELAY);
+ return rxData;
+}
+
+uint8_t MarlinSPI::dmaTransfer(const void *transmitBuf, void *receiveBuf, uint16_t length) {
+ const uint8_t ff = 0xFF;
+
+ //if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) //only enable if disabled
+ __HAL_SPI_ENABLE(&_spi.handle);
+
+ if (receiveBuf) {
+ setupDma(_spi.handle, _dmaRx, DMA_PERIPH_TO_MEMORY, true);
+ HAL_DMA_Start(&_dmaRx, (uint32_t)&(_spi.handle.Instance->DR), (uint32_t)receiveBuf, length);
+ SET_BIT(_spi.handle.Instance->CR2, SPI_CR2_RXDMAEN); /* Enable Rx DMA Request */
+ }
+
+ // check for 2 lines transfer
+ bool mincTransmit = true;
+ if (transmitBuf == nullptr && _spi.handle.Init.Direction == SPI_DIRECTION_2LINES && _spi.handle.Init.Mode == SPI_MODE_MASTER) {
+ transmitBuf = &ff;
+ mincTransmit = false;
+ }
+
+ if (transmitBuf) {
+ setupDma(_spi.handle, _dmaTx, DMA_MEMORY_TO_PERIPH, mincTransmit);
+ HAL_DMA_Start(&_dmaTx, (uint32_t)transmitBuf, (uint32_t)&(_spi.handle.Instance->DR), length);
+ SET_BIT(_spi.handle.Instance->CR2, SPI_CR2_TXDMAEN); /* Enable Tx DMA Request */
+ }
+
+ if (transmitBuf) {
+ HAL_DMA_PollForTransfer(&_dmaTx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY);
+ HAL_DMA_Abort(&_dmaTx);
+ HAL_DMA_DeInit(&_dmaTx);
+ }
+
+ // while ((_spi.handle.Instance->SR & SPI_FLAG_RXNE) != SPI_FLAG_RXNE) {}
+
+ if (receiveBuf) {
+ HAL_DMA_PollForTransfer(&_dmaRx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY);
+ HAL_DMA_Abort(&_dmaRx);
+ HAL_DMA_DeInit(&_dmaRx);
+ }
+
+ return 1;
+}
+
+uint8_t MarlinSPI::dmaSend(const void * transmitBuf, uint16_t length, bool minc) {
+ setupDma(_spi.handle, _dmaTx, DMA_MEMORY_TO_PERIPH, minc);
+ HAL_DMA_Start(&_dmaTx, (uint32_t)transmitBuf, (uint32_t)&(_spi.handle.Instance->DR), length);
+ __HAL_SPI_ENABLE(&_spi.handle);
+ SET_BIT(_spi.handle.Instance->CR2, SPI_CR2_TXDMAEN); /* Enable Tx DMA Request */
+ HAL_DMA_PollForTransfer(&_dmaTx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY);
+ HAL_DMA_Abort(&_dmaTx);
+ // DeInit objects
+ HAL_DMA_DeInit(&_dmaTx);
+ return 1;
+}
+
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/MarlinSPI.h b/Marlin/src/HAL/STM32/MarlinSPI.h
new file mode 100644
index 0000000..fbd3585
--- /dev/null
+++ b/Marlin/src/HAL/STM32/MarlinSPI.h
@@ -0,0 +1,107 @@
+/**
+ * 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 "HAL.h"
+#include <SPI.h>
+
+extern "C" {
+ #include <utility/spi_com.h>
+}
+
+/**
+ * Marlin currently requires 3 SPI classes:
+ *
+ * SPIClass:
+ * This class is normally provided by frameworks and has a semi-default interface.
+ * This is needed because some libraries reference it globally.
+ *
+ * SPISettings:
+ * Container for SPI configs for SPIClass. As above, libraries may reference it globally.
+ *
+ * These two classes are often provided by frameworks so we cannot extend them to add
+ * useful methods for Marlin.
+ *
+ * MarlinSPI:
+ * Provides the default SPIClass interface plus some Marlin goodies such as a simplified
+ * interface for SPI DMA transfer.
+ *
+ */
+
+#define DATA_SIZE_8BIT SPI_DATASIZE_8BIT
+#define DATA_SIZE_16BIT SPI_DATASIZE_16BIT
+
+class MarlinSPI {
+public:
+ MarlinSPI() : MarlinSPI(NC, NC, NC, NC) {}
+
+ MarlinSPI(pin_t mosi, pin_t miso, pin_t sclk, pin_t ssel = (pin_t)NC) : _mosiPin(mosi), _misoPin(miso), _sckPin(sclk), _ssPin(ssel) {
+ _spi.pin_miso = digitalPinToPinName(_misoPin);
+ _spi.pin_mosi = digitalPinToPinName(_mosiPin);
+ _spi.pin_sclk = digitalPinToPinName(_sckPin);
+ _spi.pin_ssel = digitalPinToPinName(_ssPin);
+ _dataSize = DATA_SIZE_8BIT;
+ _bitOrder = MSBFIRST;
+ _dataMode = SPI_MODE_0;
+ _spi.handle.State = HAL_SPI_STATE_RESET;
+ setClockDivider(SPI_SPEED_CLOCK_DIV2_MHZ);
+ }
+
+ void begin(void);
+ void end(void) {}
+
+ byte transfer(uint8_t _data);
+ uint8_t dmaTransfer(const void *transmitBuf, void *receiveBuf, uint16_t length);
+ uint8_t dmaSend(const void * transmitBuf, uint16_t length, bool minc = true);
+
+ /* These methods are deprecated and kept for compatibility.
+ * Use SPISettings with SPI.beginTransaction() to configure SPI parameters.
+ */
+ void setBitOrder(BitOrder _order) { _bitOrder = _order; }
+
+ void setDataMode(uint8_t _mode) {
+ switch (_mode) {
+ case SPI_MODE0: _dataMode = SPI_MODE_0; break;
+ case SPI_MODE1: _dataMode = SPI_MODE_1; break;
+ case SPI_MODE2: _dataMode = SPI_MODE_2; break;
+ case SPI_MODE3: _dataMode = SPI_MODE_3; break;
+ }
+ }
+
+ void setClockDivider(uint8_t _div);
+
+private:
+ void setupDma(SPI_HandleTypeDef &_spiHandle, DMA_HandleTypeDef &_dmaHandle, uint32_t direction, bool minc = false);
+
+ spi_t _spi;
+ DMA_HandleTypeDef _dmaTx;
+ DMA_HandleTypeDef _dmaRx;
+ BitOrder _bitOrder;
+ spi_mode_e _dataMode;
+ uint8_t _clockDivider;
+ uint32_t _speed;
+ uint32_t _dataSize;
+ pin_t _mosiPin;
+ pin_t _misoPin;
+ pin_t _sckPin;
+ pin_t _ssPin;
+};
diff --git a/Marlin/src/HAL/STM32/MarlinSerial.cpp b/Marlin/src/HAL/STM32/MarlinSerial.cpp
new file mode 100644
index 0000000..cfb13f5
--- /dev/null
+++ b/Marlin/src/HAL/STM32/MarlinSerial.cpp
@@ -0,0 +1,89 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../inc/MarlinConfig.h"
+#include "MarlinSerial.h"
+
+#if ENABLED(EMERGENCY_PARSER)
+ #include "../../feature/e_parser.h"
+#endif
+
+#ifndef USART4
+ #define USART4 UART4
+#endif
+
+#ifndef USART5
+ #define USART5 UART5
+#endif
+
+#define DECLARE_SERIAL_PORT(ser_num) \
+ void _rx_complete_irq_ ## ser_num (serial_t * obj); \
+ MSerialT MSerial ## ser_num (true, USART ## ser_num, &_rx_complete_irq_ ## ser_num); \
+ void _rx_complete_irq_ ## ser_num (serial_t * obj) { MSerial ## ser_num ._rx_complete_irq(obj); }
+
+#define DECLARE_SERIAL_PORT_EXP(ser_num) DECLARE_SERIAL_PORT(ser_num)
+
+#if defined(SERIAL_PORT) && SERIAL_PORT >= 0
+ DECLARE_SERIAL_PORT_EXP(SERIAL_PORT)
+#endif
+
+#if defined(SERIAL_PORT_2) && SERIAL_PORT_2 >= 0
+ DECLARE_SERIAL_PORT_EXP(SERIAL_PORT_2)
+#endif
+
+#if defined(MMU2_SERIAL_PORT) && MMU2_SERIAL_PORT >= 0
+ DECLARE_SERIAL_PORT_EXP(MMU2_SERIAL_PORT)
+#endif
+
+#if defined(LCD_SERIAL_PORT) && LCD_SERIAL_PORT >= 0
+ DECLARE_SERIAL_PORT_EXP(LCD_SERIAL_PORT)
+#endif
+
+void MarlinSerial::begin(unsigned long baud, uint8_t config) {
+ HardwareSerial::begin(baud, config);
+ // Replace the IRQ callback with the one we have defined
+ TERN_(EMERGENCY_PARSER, _serial.rx_callback = _rx_callback);
+}
+
+// This function is Copyright (c) 2006 Nicholas Zambetti.
+void MarlinSerial::_rx_complete_irq(serial_t *obj) {
+ // No Parity error, read byte and store it in the buffer if there is room
+ unsigned char c;
+
+ if (uart_getc(obj, &c) == 0) {
+
+ rx_buffer_index_t i = (unsigned int)(obj->rx_head + 1) % SERIAL_RX_BUFFER_SIZE;
+
+ // if we should be storing the received character into the location
+ // just before the tail (meaning that the head would advance to the
+ // current location of the tail), we're about to overflow the buffer
+ // and so we don't write the character or advance the head.
+ if (i != obj->rx_tail) {
+ obj->rx_buff[obj->rx_head] = c;
+ obj->rx_head = i;
+ }
+
+ #if ENABLED(EMERGENCY_PARSER)
+ emergency_parser.update(static_cast<MSerialT*>(this)->emergency_state, c);
+ #endif
+ }
+}
+
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/MarlinSerial.h b/Marlin/src/HAL/STM32/MarlinSerial.h
new file mode 100644
index 0000000..8cc4f0d
--- /dev/null
+++ b/Marlin/src/HAL/STM32/MarlinSerial.h
@@ -0,0 +1,56 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * 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 "../../inc/MarlinConfigPre.h"
+
+#if ENABLED(EMERGENCY_PARSER)
+ #include "../../feature/e_parser.h"
+#endif
+
+#include "../../core/serial_hook.h"
+
+typedef void (*usart_rx_callback_t)(serial_t * obj);
+
+struct MarlinSerial : public HardwareSerial {
+ MarlinSerial(void* peripheral, usart_rx_callback_t rx_callback) :
+ HardwareSerial(peripheral), _rx_callback(rx_callback)
+ { }
+
+ void begin(unsigned long baud, uint8_t config);
+ inline void begin(unsigned long baud) { begin(baud, SERIAL_8N1); }
+
+ void _rx_complete_irq(serial_t* obj);
+
+protected:
+ usart_rx_callback_t _rx_callback;
+};
+
+typedef Serial0Type<MarlinSerial> MSerialT;
+extern MSerialT MSerial1;
+extern MSerialT MSerial2;
+extern MSerialT MSerial3;
+extern MSerialT MSerial4;
+extern MSerialT MSerial5;
+extern MSerialT MSerial6;
+extern MSerialT MSerial7;
+extern MSerialT MSerial8;
+extern MSerialT MSerial9;
+extern MSerialT MSerial10;
+extern MSerialT MSerialLP1;
diff --git a/Marlin/src/HAL/STM32/README.md b/Marlin/src/HAL/STM32/README.md
new file mode 100644
index 0000000..7680df6
--- /dev/null
+++ b/Marlin/src/HAL/STM32/README.md
@@ -0,0 +1,11 @@
+# Generic STM32 HAL based on the stm32duino core
+
+This HAL is intended to act as the generic STM32 HAL for all STM32 chips (The whole F, H and L family).
+
+Currently it supports:
+ * STM32F0xx
+ * STM32F1xx
+ * STM32F4xx
+ * STM32F7xx
+
+Targeting the official [Arduino STM32 Core](https://github.com/stm32duino/Arduino_Core_STM32).
diff --git a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp
new file mode 100644
index 0000000..fc9b960
--- /dev/null
+++ b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp
@@ -0,0 +1,328 @@
+/**
+ * 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/>.
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(SDIO_SUPPORT)
+
+#include <stdint.h>
+#include <stdbool.h>
+
+#if NONE(STM32F103xE, STM32F103xG, STM32F4xx, STM32F7xx)
+ #error "ERROR - Only STM32F103xE, STM32F103xG, STM32F4xx or STM32F7xx CPUs supported"
+#endif
+
+#if HAS_SD_HOST_DRIVE
+
+ // use USB drivers
+
+ extern "C" { int8_t SD_MSC_Read(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len);
+ int8_t SD_MSC_Write(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len);
+ extern SD_HandleTypeDef hsd;
+ }
+
+ bool SDIO_Init() {
+ return hsd.State == HAL_SD_STATE_READY; // return pass/fail status
+ }
+
+ bool SDIO_ReadBlock(uint32_t block, uint8_t *src) {
+ int8_t status = SD_MSC_Read(0, (uint8_t*)src, block, 1); // read one 512 byte block
+ return (bool) status;
+ }
+
+ bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) {
+ int8_t status = SD_MSC_Write(0, (uint8_t*)src, block, 1); // write one 512 byte block
+ return (bool) status;
+ }
+
+#else // !USBD_USE_CDC_COMPOSITE
+
+ // use local drivers
+ #if defined(STM32F103xE) || defined(STM32F103xG)
+ #include <stm32f1xx_hal_rcc_ex.h>
+ #include <stm32f1xx_hal_sd.h>
+ #elif defined(STM32F4xx)
+ #include <stm32f4xx_hal_rcc.h>
+ #include <stm32f4xx_hal_dma.h>
+ #include <stm32f4xx_hal_gpio.h>
+ #include <stm32f4xx_hal_sd.h>
+ #elif defined(STM32F7xx)
+ #include <stm32f7xx_hal_rcc.h>
+ #include <stm32f7xx_hal_dma.h>
+ #include <stm32f7xx_hal_gpio.h>
+ #include <stm32f7xx_hal_sd.h>
+ #else
+ #error "ERROR - Only STM32F103xE, STM32F103xG, STM32F4xx or STM32F7xx CPUs supported"
+ #endif
+
+ SD_HandleTypeDef hsd; // create SDIO structure
+
+ /*
+ SDIO_INIT_CLK_DIV is 118
+ SDIO clock frequency is 48MHz / (TRANSFER_CLOCK_DIV + 2)
+ SDIO init clock frequency should not exceed 400KHz = 48MHz / (118 + 2)
+
+ Default TRANSFER_CLOCK_DIV is 2 (118 / 40)
+ Default SDIO clock frequency is 48MHz / (2 + 2) = 12 MHz
+ This might be too fast for stable SDIO operations
+
+ MKS Robin board seems to have stable SDIO with BusWide 1bit and ClockDiv 8 i.e. 4.8MHz SDIO clock frequency
+ Additional testing is required as there are clearly some 4bit initialization problems
+ */
+
+ #ifndef USBD_OK
+ #define USBD_OK 0
+ #endif
+
+ // Target Clock, configurable. Default is 18MHz, from STM32F1
+ #ifndef SDIO_CLOCK
+ #define SDIO_CLOCK 18000000 /* 18 MHz */
+ #endif
+
+ // SDIO retries, configurable. Default is 3, from STM32F1
+ #ifndef SDIO_READ_RETRIES
+ #define SDIO_READ_RETRIES 3
+ #endif
+
+ // SDIO Max Clock (naming from STM Manual, don't change)
+ #define SDIOCLK 48000000
+
+ static uint32_t clock_to_divider(uint32_t clk) {
+ // limit the SDIO master clock to 8/3 of PCLK2. See STM32 Manuals
+ // Also limited to no more than 48Mhz (SDIOCLK).
+ const uint32_t pclk2 = HAL_RCC_GetPCLK2Freq();
+ clk = min(clk, (uint32_t)(pclk2 * 8 / 3));
+ clk = min(clk, (uint32_t)SDIOCLK);
+ // Round up divider, so we don't run the card over the speed supported,
+ // and subtract by 2, because STM32 will add 2, as written in the manual:
+ // SDIO_CK frequency = SDIOCLK / [CLKDIV + 2]
+ return pclk2 / clk + (pclk2 % clk != 0) - 2;
+ }
+
+ void go_to_transfer_speed() {
+ SD_InitTypeDef Init;
+
+ /* Default SDIO peripheral configuration for SD card initialization */
+ Init.ClockEdge = hsd.Init.ClockEdge;
+ Init.ClockBypass = hsd.Init.ClockBypass;
+ Init.ClockPowerSave = hsd.Init.ClockPowerSave;
+ Init.BusWide = hsd.Init.BusWide;
+ Init.HardwareFlowControl = hsd.Init.HardwareFlowControl;
+ Init.ClockDiv = clock_to_divider(SDIO_CLOCK);
+
+ /* Initialize SDIO peripheral interface with default configuration */
+ SDIO_Init(hsd.Instance, Init);
+ }
+
+ void SD_LowLevel_Init(void) {
+ uint32_t tempreg;
+
+ __HAL_RCC_SDIO_CLK_ENABLE();
+ __HAL_RCC_GPIOC_CLK_ENABLE(); //enable GPIO clocks
+ __HAL_RCC_GPIOD_CLK_ENABLE(); //enable GPIO clocks
+
+ GPIO_InitTypeDef GPIO_InitStruct;
+
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = 1; //GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
+
+ #if DISABLED(STM32F1xx)
+ GPIO_InitStruct.Alternate = GPIO_AF12_SDIO;
+ #endif
+
+ GPIO_InitStruct.Pin = GPIO_PIN_8 | GPIO_PIN_12; // D0 & SCK
+ HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
+
+ #if PINS_EXIST(SDIO_D1, SDIO_D2, SDIO_D3) // define D1-D3 only if have a four bit wide SDIO bus
+ GPIO_InitStruct.Pin = GPIO_PIN_9 | GPIO_PIN_10 | GPIO_PIN_11; // D1-D3
+ HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
+ #endif
+
+ // Configure PD.02 CMD line
+ GPIO_InitStruct.Pin = GPIO_PIN_2;
+ HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
+
+ #if DISABLED(STM32F1xx)
+ // TODO: use __HAL_RCC_SDIO_RELEASE_RESET() and __HAL_RCC_SDIO_CLK_ENABLE();
+ RCC->APB2RSTR &= ~RCC_APB2RSTR_SDIORST_Msk; // take SDIO out of reset
+ RCC->APB2ENR |= RCC_APB2RSTR_SDIORST_Msk; // enable SDIO clock
+ // Enable the DMA2 Clock
+ #endif
+
+ //Initialize the SDIO (with initial <400Khz Clock)
+ tempreg = 0; //Reset value
+ tempreg |= SDIO_CLKCR_CLKEN; // Clock enabled
+ tempreg |= SDIO_INIT_CLK_DIV; // Clock Divider. Clock = 48000 / (118 + 2) = 400Khz
+ // Keep the rest at 0 => HW_Flow Disabled, Rising Clock Edge, Disable CLK ByPass, Bus Width = 0, Power save Disable
+ SDIO->CLKCR = tempreg;
+
+ // Power up the SDIO
+ SDIO_PowerState_ON(SDIO);
+ }
+
+ void HAL_SD_MspInit(SD_HandleTypeDef *hsd) { // application specific init
+ UNUSED(hsd); // Prevent unused argument(s) compilation warning
+ __HAL_RCC_SDIO_CLK_ENABLE(); // turn on SDIO clock
+ }
+
+ bool SDIO_Init() {
+ uint8_t retryCnt = SDIO_READ_RETRIES;
+
+ bool status;
+ hsd.Instance = SDIO;
+ hsd.State = HAL_SD_STATE_RESET;
+
+ SD_LowLevel_Init();
+
+ uint8_t retry_Cnt = retryCnt;
+ for (;;) {
+ TERN_(USE_WATCHDOG, HAL_watchdog_refresh());
+ status = (bool) HAL_SD_Init(&hsd);
+ if (!status) break;
+ if (!--retry_Cnt) return false; // return failing status if retries are exhausted
+ }
+
+ go_to_transfer_speed();
+
+ #if PINS_EXIST(SDIO_D1, SDIO_D2, SDIO_D3) // go to 4 bit wide mode if pins are defined
+ retry_Cnt = retryCnt;
+ for (;;) {
+ TERN_(USE_WATCHDOG, HAL_watchdog_refresh());
+ if (!HAL_SD_ConfigWideBusOperation(&hsd, SDIO_BUS_WIDE_4B)) break; // some cards are only 1 bit wide so a pass here is not required
+ if (!--retry_Cnt) break;
+ }
+ if (!retry_Cnt) { // wide bus failed, go back to one bit wide mode
+ hsd.State = (HAL_SD_StateTypeDef) 0; // HAL_SD_STATE_RESET
+ SD_LowLevel_Init();
+ retry_Cnt = retryCnt;
+ for (;;) {
+ TERN_(USE_WATCHDOG, HAL_watchdog_refresh());
+ status = (bool) HAL_SD_Init(&hsd);
+ if (!status) break;
+ if (!--retry_Cnt) return false; // return failing status if retries are exhausted
+ }
+ }
+ #endif
+
+ return true;
+ }
+ /*
+ void init_SDIO_pins(void) {
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+
+ // SDIO GPIO Configuration
+ // PC8 ------> SDIO_D0
+ // PC12 ------> SDIO_CK
+ // PD2 ------> SDIO_CMD
+
+ GPIO_InitStruct.Pin = GPIO_PIN_8;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF12_SDIO;
+ HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
+
+ GPIO_InitStruct.Pin = GPIO_PIN_12;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF12_SDIO;
+ HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
+
+ GPIO_InitStruct.Pin = GPIO_PIN_2;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF12_SDIO;
+ HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
+ }
+ */
+ //bool SDIO_init() { return (bool) (SD_SDIO_Init() ? 1 : 0);}
+ //bool SDIO_Init_C() { return (bool) (SD_SDIO_Init() ? 1 : 0);}
+
+ bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) {
+ hsd.Instance = SDIO;
+ uint8_t retryCnt = SDIO_READ_RETRIES;
+
+ bool status;
+ for (;;) {
+ TERN_(USE_WATCHDOG, HAL_watchdog_refresh());
+ status = (bool) HAL_SD_ReadBlocks(&hsd, (uint8_t*)dst, block, 1, 1000); // read one 512 byte block with 500mS timeout
+ status |= (bool) HAL_SD_GetCardState(&hsd); // make sure all is OK
+ if (!status) break; // return passing status
+ if (!--retryCnt) break; // return failing status if retries are exhausted
+ }
+ return status;
+
+ /*
+ return (bool) ((status_read | status_card) ? 1 : 0);
+
+ if (SDIO_GetCardState() != SDIO_CARD_TRANSFER) return false;
+ if (blockAddress >= SdCard.LogBlockNbr) return false;
+ if ((0x03 & (uint32_t)data)) return false; // misaligned data
+
+ if (SdCard.CardType != CARD_SDHC_SDXC) { blockAddress *= 512U; }
+
+ if (!SDIO_CmdReadSingleBlock(blockAddress)) {
+ SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS);
+ dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
+ return false;
+ }
+
+ while (!SDIO_GET_FLAG(SDIO_STA_DATAEND | SDIO_STA_TRX_ERROR_FLAGS)) {}
+
+ dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
+
+ if (SDIO->STA & SDIO_STA_RXDAVL) {
+ while (SDIO->STA & SDIO_STA_RXDAVL) (void)SDIO->FIFO;
+ SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS);
+ return false;
+ }
+
+ if (SDIO_GET_FLAG(SDIO_STA_TRX_ERROR_FLAGS)) {
+ SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS);
+ return false;
+ }
+ SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS);
+ */
+
+ return true;
+ }
+
+ bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) {
+ hsd.Instance = SDIO;
+ uint8_t retryCnt = SDIO_READ_RETRIES;
+ bool status;
+ for (;;) {
+ status = (bool) HAL_SD_WriteBlocks(&hsd, (uint8_t*)src, block, 1, 500); // write one 512 byte block with 500mS timeout
+ status |= (bool) HAL_SD_GetCardState(&hsd); // make sure all is OK
+ if (!status) break; // return passing status
+ if (!--retryCnt) break; // return failing status if retries are exhausted
+ }
+ return status;
+ }
+
+#endif // !USBD_USE_CDC_COMPOSITE
+#endif // SDIO_SUPPORT
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/Servo.cpp b/Marlin/src/HAL/STM32/Servo.cpp
new file mode 100644
index 0000000..1cf117a
--- /dev/null
+++ b/Marlin/src/HAL/STM32/Servo.cpp
@@ -0,0 +1,110 @@
+/**
+ * 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/>.
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../inc/MarlinConfig.h"
+
+#if HAS_SERVOS
+
+#include "Servo.h"
+
+static uint_fast8_t servoCount = 0;
+static libServo *servos[NUM_SERVOS] = {0};
+constexpr millis_t servoDelay[] = SERVO_DELAY;
+static_assert(COUNT(servoDelay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
+
+// Initialize to the default timer priority. This will be overridden by a call from timers.cpp.
+// This allows all timer interrupt priorities to be managed from a single location in the HAL.
+static uint32_t servo_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), TIM_IRQ_PRIO, TIM_IRQ_SUBPRIO);
+
+// This must be called after the STM32 Servo class has intialized the timer.
+// It may only be needed after the first call to attach(), but it is possible
+// that is is necessary after every detach() call. To be safe this is currently
+// called after every call to attach().
+static void fixServoTimerInterruptPriority() {
+ NVIC_SetPriority(getTimerUpIrq(TIMER_SERVO), servo_interrupt_priority);
+}
+
+libServo::libServo()
+: delay(servoDelay[servoCount]),
+ was_attached_before_pause(false),
+ value_before_pause(0)
+{
+ servos[servoCount++] = this;
+}
+
+int8_t libServo::attach(const int pin) {
+ if (servoCount >= MAX_SERVOS) return -1;
+ if (pin > 0) servo_pin = pin;
+ auto result = stm32_servo.attach(servo_pin);
+ fixServoTimerInterruptPriority();
+ return result;
+}
+
+int8_t libServo::attach(const int pin, const int min, const int max) {
+ if (servoCount >= MAX_SERVOS) return -1;
+ if (pin > 0) servo_pin = pin;
+ auto result = stm32_servo.attach(servo_pin, min, max);
+ fixServoTimerInterruptPriority();
+ return result;
+}
+
+void libServo::move(const int value) {
+ if (attach(0) >= 0) {
+ stm32_servo.write(value);
+ safe_delay(delay);
+ TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
+ }
+}
+
+void libServo::pause() {
+ was_attached_before_pause = stm32_servo.attached();
+ if (was_attached_before_pause) {
+ value_before_pause = stm32_servo.read();
+ stm32_servo.detach();
+ }
+}
+
+void libServo::resume() {
+ if (was_attached_before_pause) {
+ attach();
+ move(value_before_pause);
+ }
+}
+
+void libServo::pause_all_servos() {
+ for (auto& servo : servos)
+ if (servo) servo->pause();
+}
+
+void libServo::resume_all_servos() {
+ for (auto& servo : servos)
+ if (servo) servo->resume();
+}
+
+void libServo::setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority) {
+ servo_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), preemptPriority, subPriority);
+}
+
+#endif // HAS_SERVOS
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/Servo.h b/Marlin/src/HAL/STM32/Servo.h
new file mode 100644
index 0000000..1527e75
--- /dev/null
+++ b/Marlin/src/HAL/STM32/Servo.h
@@ -0,0 +1,54 @@
+/**
+ * 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
+
+#include <Servo.h>
+
+#include "../../core/millis_t.h"
+
+// Inherit and expand on the official library
+class libServo {
+ public:
+ libServo();
+ int8_t attach(const int pin = 0); // pin == 0 uses value from previous call
+ int8_t attach(const int pin, const int min, const int max);
+ void detach() { stm32_servo.detach(); }
+ int read() { return stm32_servo.read(); }
+ void move(const int value);
+
+ void pause();
+ void resume();
+
+ static void pause_all_servos();
+ static void resume_all_servos();
+ static void setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority);
+
+ private:
+ Servo stm32_servo;
+
+ int servo_pin = 0;
+ millis_t delay = 0;
+
+ bool was_attached_before_pause;
+ int value_before_pause;
+};
diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp
new file mode 100644
index 0000000..633a286
--- /dev/null
+++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp
@@ -0,0 +1,269 @@
+/**
+ * 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/>.
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(FLASH_EEPROM_EMULATION)
+
+#include "../shared/eeprom_api.h"
+
+/**
+ * The STM32 HAL supports chips that deal with "pages" and some with "sectors" and some that
+ * even have multiple "banks" of flash.
+ *
+ * This code is a bit of a mashup of
+ * framework-arduinoststm32/cores/arduino/stm32/stm32_eeprom.c
+ * hal/hal_lpc1768/persistent_store_flash.cpp
+ *
+ * This has only be written against those that use a single "sector" design.
+ *
+ * Those that deal with "pages" could be made to work. Looking at the STM32F07 for example, there are
+ * 128 "pages", each 2kB in size. If we continued with our EEPROM being 4Kb, we'd always need to operate
+ * on 2 of these pages. Each write, we'd use 2 different pages from a pool of pages until we are done.
+ */
+
+#if ENABLED(FLASH_EEPROM_LEVELING)
+
+ #include "stm32_def.h"
+
+ #define DEBUG_OUT ENABLED(EEPROM_CHITCHAT)
+ #include "src/core/debug_out.h"
+
+ #ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE 0x1000 // 4KB
+ #endif
+
+ #ifndef FLASH_SECTOR
+ #define FLASH_SECTOR (FLASH_SECTOR_TOTAL - 1)
+ #endif
+ #ifndef FLASH_UNIT_SIZE
+ #define FLASH_UNIT_SIZE 0x20000 // 128kB
+ #endif
+
+ #ifndef FLASH_ADDRESS_START
+ #define FLASH_ADDRESS_START (FLASH_END - ((FLASH_SECTOR_TOTAL - (FLASH_SECTOR)) * (FLASH_UNIT_SIZE)) + 1)
+ #endif
+ #define FLASH_ADDRESS_END (FLASH_ADDRESS_START + FLASH_UNIT_SIZE - 1)
+
+ #define EEPROM_SLOTS ((FLASH_UNIT_SIZE) / (MARLIN_EEPROM_SIZE))
+ #define SLOT_ADDRESS(slot) (FLASH_ADDRESS_START + (slot * (MARLIN_EEPROM_SIZE)))
+
+ #define UNLOCK_FLASH() if (!flash_unlocked) { \
+ HAL_FLASH_Unlock(); \
+ __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | \
+ FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR); \
+ flash_unlocked = true; \
+ }
+ #define LOCK_FLASH() if (flash_unlocked) { HAL_FLASH_Lock(); flash_unlocked = false; }
+
+ #define EMPTY_UINT32 ((uint32_t)-1)
+ #define EMPTY_UINT8 ((uint8_t)-1)
+
+ static uint8_t ram_eeprom[MARLIN_EEPROM_SIZE] __attribute__((aligned(4))) = {0};
+ static int current_slot = -1;
+
+ static_assert(0 == MARLIN_EEPROM_SIZE % 4, "MARLIN_EEPROM_SIZE must be a multiple of 4"); // Ensure copying as uint32_t is safe
+ static_assert(0 == FLASH_UNIT_SIZE % MARLIN_EEPROM_SIZE, "MARLIN_EEPROM_SIZE must divide evenly into your FLASH_UNIT_SIZE");
+ static_assert(FLASH_UNIT_SIZE >= MARLIN_EEPROM_SIZE, "FLASH_UNIT_SIZE must be greater than or equal to your MARLIN_EEPROM_SIZE");
+ static_assert(IS_FLASH_SECTOR(FLASH_SECTOR), "FLASH_SECTOR is invalid");
+ static_assert(IS_POWER_OF_2(FLASH_UNIT_SIZE), "FLASH_UNIT_SIZE should be a power of 2, please check your chip's spec sheet");
+
+#endif
+
+static bool eeprom_data_written = false;
+
+#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() {
+
+ #if ENABLED(FLASH_EEPROM_LEVELING)
+
+ if (current_slot == -1 || eeprom_data_written) {
+ // This must be the first time since power on that we have accessed the storage, or someone
+ // loaded and called write_data and never called access_finish.
+ // Lets go looking for the slot that holds our configuration.
+ if (eeprom_data_written) DEBUG_ECHOLNPGM("Dangling EEPROM write_data");
+ uint32_t address = FLASH_ADDRESS_START;
+ while (address <= FLASH_ADDRESS_END) {
+ uint32_t address_value = (*(__IO uint32_t*)address);
+ if (address_value != EMPTY_UINT32) {
+ current_slot = (address - (FLASH_ADDRESS_START)) / (MARLIN_EEPROM_SIZE);
+ break;
+ }
+ address += sizeof(uint32_t);
+ }
+ if (current_slot == -1) {
+ // We didn't find anything, so we'll just intialize to empty
+ for (int i = 0; i < MARLIN_EEPROM_SIZE; i++) ram_eeprom[i] = EMPTY_UINT8;
+ current_slot = EEPROM_SLOTS;
+ }
+ else {
+ // load current settings
+ uint8_t *eeprom_data = (uint8_t *)SLOT_ADDRESS(current_slot);
+ for (int i = 0; i < MARLIN_EEPROM_SIZE; i++) ram_eeprom[i] = eeprom_data[i];
+ DEBUG_ECHOLNPAIR("EEPROM loaded from slot ", current_slot, ".");
+ }
+ eeprom_data_written = false;
+ }
+
+ #else
+ eeprom_buffer_fill();
+ #endif
+
+ return true;
+}
+
+bool PersistentStore::access_finish() {
+
+ if (eeprom_data_written) {
+ #ifdef STM32F4xx
+ // MCU may come up with flash error bits which prevent some flash operations.
+ // Clear flags prior to flash operations to prevent errors.
+ __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
+ #endif
+
+ #if ENABLED(FLASH_EEPROM_LEVELING)
+
+ HAL_StatusTypeDef status = HAL_ERROR;
+ bool flash_unlocked = false;
+
+ if (--current_slot < 0) {
+ // all slots have been used, erase everything and start again
+
+ FLASH_EraseInitTypeDef EraseInitStruct;
+ uint32_t SectorError = 0;
+
+ EraseInitStruct.TypeErase = FLASH_TYPEERASE_SECTORS;
+ EraseInitStruct.VoltageRange = FLASH_VOLTAGE_RANGE_3;
+ EraseInitStruct.Sector = FLASH_SECTOR;
+ EraseInitStruct.NbSectors = 1;
+
+ current_slot = EEPROM_SLOTS - 1;
+ UNLOCK_FLASH();
+
+ TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT());
+ DISABLE_ISRS();
+ status = HAL_FLASHEx_Erase(&EraseInitStruct, &SectorError);
+ ENABLE_ISRS();
+ TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT());
+ if (status != HAL_OK) {
+ DEBUG_ECHOLNPAIR("HAL_FLASHEx_Erase=", status);
+ DEBUG_ECHOLNPAIR("GetError=", HAL_FLASH_GetError());
+ DEBUG_ECHOLNPAIR("SectorError=", SectorError);
+ LOCK_FLASH();
+ return false;
+ }
+ }
+
+ UNLOCK_FLASH();
+
+ uint32_t offset = 0;
+ uint32_t address = SLOT_ADDRESS(current_slot);
+ uint32_t address_end = address + MARLIN_EEPROM_SIZE;
+ uint32_t data = 0;
+
+ bool success = true;
+
+ while (address < address_end) {
+ memcpy(&data, ram_eeprom + offset, sizeof(uint32_t));
+ status = HAL_FLASH_Program(FLASH_TYPEPROGRAM_WORD, address, data);
+ if (status == HAL_OK) {
+ address += sizeof(uint32_t);
+ offset += sizeof(uint32_t);
+ }
+ else {
+ DEBUG_ECHOLNPAIR("HAL_FLASH_Program=", status);
+ DEBUG_ECHOLNPAIR("GetError=", HAL_FLASH_GetError());
+ DEBUG_ECHOLNPAIR("address=", address);
+ success = false;
+ break;
+ }
+ }
+
+ LOCK_FLASH();
+
+ if (success) {
+ eeprom_data_written = false;
+ DEBUG_ECHOLNPAIR("EEPROM saved to slot ", current_slot, ".");
+ }
+
+ return success;
+
+ #else
+ // The following was written for the STM32F4 but may work with other MCUs as well.
+ // Most STM32F4 flash does not allow reading from flash during erase operations.
+ // This takes about a second on a STM32F407 with a 128kB sector used as EEPROM.
+ // Interrupts during this time can have unpredictable results, such as killing Servo
+ // output. Servo output still glitches with interrupts disabled, but recovers after the
+ // erase.
+ TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT());
+ DISABLE_ISRS();
+ eeprom_buffer_flush();
+ ENABLE_ISRS();
+ TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT());
+
+ eeprom_data_written = false;
+ #endif
+ }
+
+ return true;
+}
+
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ while (size--) {
+ uint8_t v = *value;
+ #if ENABLED(FLASH_EEPROM_LEVELING)
+ if (v != ram_eeprom[pos]) {
+ ram_eeprom[pos] = v;
+ eeprom_data_written = true;
+ }
+ #else
+ if (v != eeprom_buffered_read_byte(pos)) {
+ eeprom_buffered_write_byte(pos, v);
+ eeprom_data_written = true;
+ }
+ #endif
+ 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 {
+ const uint8_t c = TERN(FLASH_EEPROM_LEVELING, ram_eeprom[pos], eeprom_buffered_read_byte(pos));
+ if (writing) *value = c;
+ crc16(crc, &c, 1);
+ pos++;
+ value++;
+ } while (--size);
+ return false;
+}
+
+#endif // FLASH_EEPROM_EMULATION
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/eeprom_sdcard.cpp b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp
new file mode 100644
index 0000000..f811468
--- /dev/null
+++ b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp
@@ -0,0 +1,91 @@
+/**
+ * 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/>.
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+/**
+ * Implementation of EEPROM settings in SD Card
+ */
+
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(SDCARD_EEPROM_EMULATION)
+
+#include "../shared/eeprom_api.h"
+#include "../../sd/cardreader.h"
+
+#define EEPROM_FILENAME "eeprom.dat"
+
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE 0x1000 // 4KB
+#endif
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+
+#define _ALIGN(x) __attribute__ ((aligned(x)))
+static char _ALIGN(4) HAL_eeprom_data[MARLIN_EEPROM_SIZE];
+
+bool PersistentStore::access_start() {
+ if (!card.isMounted()) return false;
+
+ SdFile file, root = card.getroot();
+ if (!file.open(&root, EEPROM_FILENAME, O_RDONLY))
+ return true;
+
+ int bytes_read = file.read(HAL_eeprom_data, MARLIN_EEPROM_SIZE);
+ if (bytes_read < 0) return false;
+ for (; bytes_read < MARLIN_EEPROM_SIZE; bytes_read++)
+ HAL_eeprom_data[bytes_read] = 0xFF;
+ file.close();
+ return true;
+}
+
+bool PersistentStore::access_finish() {
+ if (!card.isMounted()) return false;
+
+ SdFile file, root = card.getroot();
+ int bytes_written = 0;
+ if (file.open(&root, EEPROM_FILENAME, O_CREAT | O_WRITE | O_TRUNC)) {
+ bytes_written = file.write(HAL_eeprom_data, MARLIN_EEPROM_SIZE);
+ file.close();
+ }
+ return (bytes_written == MARLIN_EEPROM_SIZE);
+}
+
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ for (size_t i = 0; i < size; i++)
+ HAL_eeprom_data[pos + i] = value[i];
+ crc16(crc, value, size);
+ pos += size;
+ return false;
+}
+
+bool PersistentStore::read_data(int &pos, uint8_t *value, const size_t size, uint16_t *crc, const bool writing/*=true*/) {
+ for (size_t i = 0; i < size; i++) {
+ uint8_t c = HAL_eeprom_data[pos + i];
+ if (writing) value[i] = c;
+ crc16(crc, &c, 1);
+ }
+ pos += size;
+ return false;
+}
+
+#endif // SDCARD_EEPROM_EMULATION
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/eeprom_sram.cpp b/Marlin/src/HAL/STM32/eeprom_sram.cpp
new file mode 100644
index 0000000..135bcab
--- /dev/null
+++ b/Marlin/src/HAL/STM32/eeprom_sram.cpp
@@ -0,0 +1,68 @@
+/**
+ * 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/>.
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(SRAM_EEPROM_EMULATION)
+
+#include "../shared/eeprom_if.h"
+#include "../shared/eeprom_api.h"
+
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE 0x1000 // 4KB
+#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 v = *value;
+
+ // Save to Backup SRAM
+ *(__IO uint8_t *)(BKPSRAM_BASE + (uint8_t * const)pos) = v;
+
+ 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 {
+ // Read from either external EEPROM, program flash or Backup SRAM
+ const uint8_t c = ( *(__IO uint8_t *)(BKPSRAM_BASE + ((uint8_t*)pos)) );
+ if (writing) *value = c;
+ crc16(crc, &c, 1);
+ pos++;
+ value++;
+ } while (--size);
+ return false;
+}
+
+#endif // SRAM_EEPROM_EMULATION
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/eeprom_wired.cpp b/Marlin/src/HAL/STM32/eeprom_wired.cpp
new file mode 100644
index 0000000..ad54c12
--- /dev/null
+++ b/Marlin/src/HAL/STM32/eeprom_wired.cpp
@@ -0,0 +1,81 @@
+/**
+ * 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/>.
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../inc/MarlinConfig.h"
+
+#if USE_WIRED_EEPROM
+
+/**
+ * PersistentStore for Arduino-style EEPROM interface
+ * with simple implementations supplied by Marlin.
+ */
+
+#include "../shared/eeprom_if.h"
+#include "../shared/eeprom_api.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() { eeprom_init(); 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 v = *value;
+
+ // EEPROM has only ~100,000 write cycles,
+ // so only write bytes that have changed!
+ uint8_t * const p = (uint8_t * const)pos;
+ 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 {
+ // Read from either external EEPROM, program flash or Backup SRAM
+ const 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 // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/endstop_interrupts.h b/Marlin/src/HAL/STM32/endstop_interrupts.h
new file mode 100644
index 0000000..fdff8cc
--- /dev/null
+++ b/Marlin/src/HAL/STM32/endstop_interrupts.h
@@ -0,0 +1,49 @@
+/**
+ * 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
+
+#include "../../module/endstops.h"
+
+// One ISR for all EXT-Interrupts
+void endstop_ISR() { endstops.update(); }
+
+void setup_endstop_interrupts() {
+ #define _ATTACH(P) attachInterrupt(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));
+}
diff --git a/Marlin/src/HAL/STM32/fast_pwm.cpp b/Marlin/src/HAL/STM32/fast_pwm.cpp
new file mode 100644
index 0000000..42eecb5
--- /dev/null
+++ b/Marlin/src/HAL/STM32/fast_pwm.cpp
@@ -0,0 +1,59 @@
+/**
+ * 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/>.
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../inc/MarlinConfigPre.h"
+
+#if NEEDS_HARDWARE_PWM
+
+#include "HAL.h"
+#include "timers.h"
+
+void set_pwm_frequency(const pin_t pin, int f_desired) {
+ if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
+
+ PinName pin_name = digitalPinToPinName(pin);
+ TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance
+
+ LOOP_S_L_N(i, 0, NUM_HARDWARE_TIMERS) // Protect used timers
+ if (timer_instance[i] && timer_instance[i]->getHandle()->Instance == Instance)
+ return;
+
+ pwm_start(pin_name, f_desired, 0, RESOLUTION_8B_COMPARE_FORMAT);
+}
+
+void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
+ PinName pin_name = digitalPinToPinName(pin);
+ TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM);
+ uint16_t adj_val = Instance->ARR * v / v_size;
+ if (invert) adj_val = Instance->ARR - adj_val;
+
+ switch (get_pwm_channel(pin_name)) {
+ case TIM_CHANNEL_1: LL_TIM_OC_SetCompareCH1(Instance, adj_val); break;
+ case TIM_CHANNEL_2: LL_TIM_OC_SetCompareCH2(Instance, adj_val); break;
+ case TIM_CHANNEL_3: LL_TIM_OC_SetCompareCH3(Instance, adj_val); break;
+ case TIM_CHANNEL_4: LL_TIM_OC_SetCompareCH4(Instance, adj_val); break;
+ }
+}
+
+#endif // NEEDS_HARDWARE_PWM
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/fastio.cpp b/Marlin/src/HAL/STM32/fastio.cpp
new file mode 100644
index 0000000..0d55579
--- /dev/null
+++ b/Marlin/src/HAL/STM32/fastio.cpp
@@ -0,0 +1,34 @@
+/**
+ * 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/>.
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../inc/MarlinConfig.h"
+
+GPIO_TypeDef* FastIOPortMap[LastPort + 1];
+
+void FastIO_init() {
+ LOOP_L_N(i, NUM_DIGITAL_PINS)
+ FastIOPortMap[STM_PORT(digitalPin[i])] = get_GPIO_Port(STM_PORT(digitalPin[i]));
+}
+
+#endif
diff --git a/Marlin/src/HAL/STM32/fastio.h b/Marlin/src/HAL/STM32/fastio.h
new file mode 100644
index 0000000..17751c4
--- /dev/null
+++ b/Marlin/src/HAL/STM32/fastio.h
@@ -0,0 +1,90 @@
+/**
+ * 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 STM32
+ * These use GPIO register access for fast port manipulation.
+ */
+
+// ------------------------
+// Public Variables
+// ------------------------
+
+extern GPIO_TypeDef * FastIOPortMap[];
+
+// ------------------------
+// Public functions
+// ------------------------
+
+void FastIO_init(); // Must be called before using fast io macros
+
+// ------------------------
+// Defines
+// ------------------------
+
+#define _BV32(b) (1UL << (b))
+
+#ifndef PWM
+ #define PWM OUTPUT
+#endif
+
+#if defined(STM32F0xx) || defined(STM32F1xx) || defined(STM32F3xx) || defined(STM32L0xx) || defined(STM32L4xx)
+ #define _WRITE(IO, V) do { \
+ if (V) FastIOPortMap[STM_PORT(digitalPinToPinName(IO))]->BSRR = _BV32(STM_PIN(digitalPinToPinName(IO))) ; \
+ else FastIOPortMap[STM_PORT(digitalPinToPinName(IO))]->BRR = _BV32(STM_PIN(digitalPinToPinName(IO))) ; \
+ }while(0)
+#else
+ #define _WRITE(IO, V) (FastIOPortMap[STM_PORT(digitalPinToPinName(IO))]->BSRR = _BV32(STM_PIN(digitalPinToPinName(IO)) + ((V) ? 0 : 16)))
+#endif
+
+#define _READ(IO) bool(READ_BIT(FastIOPortMap[STM_PORT(digitalPinToPinName(IO))]->IDR, _BV32(STM_PIN(digitalPinToPinName(IO)))))
+#define _TOGGLE(IO) TBI32(FastIOPortMap[STM_PORT(digitalPinToPinName(IO))]->ODR, STM_PIN(digitalPinToPinName(IO)))
+
+#define _GET_MODE(IO)
+#define _SET_MODE(IO,M) pinMode(IO, M)
+#define _SET_OUTPUT(IO) pinMode(IO, OUTPUT) //!< Output Push Pull Mode & GPIO_NOPULL
+#define _SET_OUTPUT_OD(IO) pinMode(IO, OUTPUT_OPEN_DRAIN)
+
+#define WRITE(IO,V) _WRITE(IO,V)
+#define READ(IO) _READ(IO)
+#define TOGGLE(IO) _TOGGLE(IO)
+
+#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
+#define OUT_WRITE_OD(IO,V) do{ _SET_OUTPUT_OD(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 IS_INPUT(IO)
+#define IS_OUTPUT(IO)
+
+#define PWM_PIN(P) digitalPinHasPWM(P)
+#define NO_COMPILE_TIME_PWM
+
+// digitalRead/Write wrappers
+#define extDigitalRead(IO) digitalRead(IO)
+#define extDigitalWrite(IO,V) digitalWrite(IO,V)
diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_LCD.h b/Marlin/src/HAL/STM32/inc/Conditionals_LCD.h
new file mode 100644
index 0000000..5f1c4b1
--- /dev/null
+++ b/Marlin/src/HAL/STM32/inc/Conditionals_LCD.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
diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_adv.h b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h
new file mode 100644
index 0000000..672d405
--- /dev/null
+++ b/Marlin/src/HAL/STM32/inc/Conditionals_adv.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 defined(USBD_USE_CDC_MSC) && DISABLED(NO_SD_HOST_DRIVE)
+ #define HAS_SD_HOST_DRIVE 1
+#endif
diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_post.h b/Marlin/src/HAL/STM32/inc/Conditionals_post.h
new file mode 100644
index 0000000..18826e1
--- /dev/null
+++ b/Marlin/src/HAL/STM32/inc/Conditionals_post.h
@@ -0,0 +1,29 @@
+/**
+ * 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 no real or emulated EEPROM selected, fall back to SD emulation
+#if USE_FALLBACK_EEPROM
+ #define SDCARD_EEPROM_EMULATION
+#elif EITHER(I2C_EEPROM, SPI_EEPROM)
+ #define USE_SHARED_EEPROM 1
+#endif
diff --git a/Marlin/src/HAL/STM32/inc/SanityCheck.h b/Marlin/src/HAL/STM32/inc/SanityCheck.h
new file mode 100644
index 0000000..4df75a0
--- /dev/null
+++ b/Marlin/src/HAL/STM32/inc/SanityCheck.h
@@ -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/>.
+ *
+ */
+#pragma once
+
+/**
+ * Test STM32-specific configuration values for errors at compile-time.
+ */
+//#if ENABLED(SPINDLE_LASER_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11)
+// #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector"
+//#endif
+
+
+#if ENABLED(SDCARD_EEPROM_EMULATION) && DISABLED(SDSUPPORT)
+ #undef SDCARD_EEPROM_EMULATION // Avoid additional error noise
+ #if USE_FALLBACK_EEPROM
+ #warning "EEPROM type not specified. Fallback is SDCARD_EEPROM_EMULATION."
+ #endif
+ #error "SDCARD_EEPROM_EMULATION requires SDSUPPORT. Enable SDSUPPORT or choose another EEPROM emulation."
+#endif
+
+#if defined(STM32F4xx) && BOTH(PRINTCOUNTER, FLASH_EEPROM_EMULATION)
+ #warning "FLASH_EEPROM_EMULATION may cause long delays when writing and should not be used while printing."
+ #error "Disable PRINTCOUNTER or choose another EEPROM emulation."
+#endif
+
+#if !defined(STM32F4xx) && ENABLED(FLASH_EEPROM_LEVELING)
+ #error "FLASH_EEPROM_LEVELING is currently only supported on STM32F4 hardware."
+#endif
+
+#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
+ #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on this platform."
+#elif ENABLED(SERIAL_STATS_DROPPED_RX)
+ #error "SERIAL_STATS_DROPPED_RX is not supported on this platform."
+#endif
+
+#if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) && NOT_TARGET(STM32F4xx, STM32F1xx)
+ #error "TFT_COLOR_UI, TFT_LVGL_UI and TFT_CLASSIC_UI are currently only supported on STM32F4 and STM32F1 hardware."
+#endif
diff --git a/Marlin/src/HAL/STM32/msc_sd.cpp b/Marlin/src/HAL/STM32/msc_sd.cpp
new file mode 100644
index 0000000..8c71318
--- /dev/null
+++ b/Marlin/src/HAL/STM32/msc_sd.cpp
@@ -0,0 +1,109 @@
+/**
+ * Marlin 3D Printer Firmware
+ *
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech]
+ *
+ * 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.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#include "../../inc/MarlinConfigPre.h"
+
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && HAS_SD_HOST_DRIVE
+
+#include "msc_sd.h"
+#include "../shared/Marduino.h"
+#include "usbd_core.h"
+#include <USB.h>
+#include <USBMscHandler.h>
+
+#define BLOCK_SIZE 512
+#define PRODUCT_ID 0x29
+
+#include "../../sd/cardreader.h"
+
+class Sd2CardUSBMscHandler : public USBMscHandler {
+public:
+ bool GetCapacity(uint32_t *pBlockNum, uint16_t *pBlockSize) {
+ *pBlockNum = card.getSd2Card().cardSize();
+ *pBlockSize = BLOCK_SIZE;
+ return true;
+ }
+
+ bool Write(uint8_t *pBuf, uint32_t blkAddr, uint16_t blkLen) {
+ auto sd2card = card.getSd2Card();
+ if (blkLen == 1) {
+ watchdog_refresh();
+ sd2card.writeBlock(blkAddr, pBuf);
+ return true;
+ }
+
+ sd2card.writeStart(blkAddr, blkLen);
+ while (blkLen--) {
+ watchdog_refresh();
+ sd2card.writeData(pBuf);
+ pBuf += BLOCK_SIZE;
+ }
+ sd2card.writeStop();
+ return true;
+ }
+
+ bool Read(uint8_t *pBuf, uint32_t blkAddr, uint16_t blkLen) {
+ auto sd2card = card.getSd2Card();
+ if (blkLen == 1) {
+ watchdog_refresh();
+ sd2card.readBlock(blkAddr, pBuf);
+ return true;
+ }
+
+ sd2card.readStart(blkAddr);
+ while (blkLen--) {
+ watchdog_refresh();
+ sd2card.readData(pBuf);
+ pBuf += BLOCK_SIZE;
+ }
+ sd2card.readStop();
+ return true;
+ }
+
+ bool IsReady() {
+ return card.isMounted();
+ }
+};
+
+Sd2CardUSBMscHandler usbMscHandler;
+
+/* USB Mass storage Standard Inquiry Data */
+uint8_t Marlin_STORAGE_Inquirydata[] = /* 36 */
+{
+ /* LUN 0 */
+ 0x00,
+ 0x80,
+ 0x02,
+ 0x02,
+ (STANDARD_INQUIRY_DATA_LEN - 5),
+ 0x00,
+ 0x00,
+ 0x00,
+ 'M', 'A', 'R', 'L', 'I', 'N', ' ', ' ', /* Manufacturer : 8 bytes */
+ 'P', 'r', 'o', 'd', 'u', 'c', 't', ' ', /* Product : 16 Bytes */
+ ' ', ' ', ' ', ' ', ' ', ' ', ' ', ' ',
+ '0', '.', '0', '1', /* Version : 4 Bytes */
+};
+
+USBMscHandler *pSingleMscHandler = &usbMscHandler;
+
+void MSC_SD_init() {
+ USBDevice.end();
+ delay(200);
+ USBDevice.begin();
+ USBDevice.registerMscHandlers(1, &pSingleMscHandler, Marlin_STORAGE_Inquirydata);
+}
+
+#endif // __STM32F1__ && HAS_SD_HOST_DRIVE
diff --git a/Marlin/src/HAL/STM32/msc_sd.h b/Marlin/src/HAL/STM32/msc_sd.h
new file mode 100644
index 0000000..4a8e5b0
--- /dev/null
+++ b/Marlin/src/HAL/STM32/msc_sd.h
@@ -0,0 +1,20 @@
+/**
+ * Marlin 3D Printer Firmware
+ *
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech]
+ *
+ * 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.
+ *
+ * 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 "../../inc/MarlinConfigPre.h"
+
+void MSC_SD_init();
diff --git a/Marlin/src/HAL/STM32/pinsDebug.h b/Marlin/src/HAL/STM32/pinsDebug.h
new file mode 100644
index 0000000..048f788
--- /dev/null
+++ b/Marlin/src/HAL/STM32/pinsDebug.h
@@ -0,0 +1,264 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * 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 <Arduino.h>
+
+#ifndef NUM_DIGITAL_PINS
+ // Only in ST's Arduino core (STM32duino, STM32Core)
+ #error "Expected NUM_DIGITAL_PINS not found"
+#endif
+
+/**
+ * Life gets complicated if you want an easy to use 'M43 I' output (in port/pin order)
+ * because the variants in this platform do not always define all the I/O port/pins
+ * that a CPU has.
+ *
+ * VARIABLES:
+ * Ard_num - Arduino pin number - defined by the platform. It is used by digitalRead and
+ * digitalWrite commands and by M42.
+ * - does not contain port/pin info
+ * - is not in port/pin order
+ * - typically a variant will only assign Ard_num to port/pins that are actually used
+ * Index - M43 counter - only used to get Ard_num
+ * x - a parameter/argument used to search the pin_array to try to find a signal name
+ * associated with a Ard_num
+ * Port_pin - port number and pin number for use with CPU registers and printing reports
+ *
+ * Since M43 uses digitalRead and digitalWrite commands, only the Port_pins with an Ard_num
+ * are accessed and/or displayed.
+ *
+ * Three arrays are used.
+ *
+ * digitalPin[] is provided by the platform. It consists of the Port_pin numbers in
+ * Arduino pin number order.
+ *
+ * pin_array is a structure generated by the pins/pinsDebug.h header file. It is generated by
+ * the preprocessor. Only the signals associated with enabled options are in this table.
+ * It contains:
+ * - name of the signal
+ * - the Ard_num assigned by the pins_YOUR_BOARD.h file using the platform defines.
+ * EXAMPLE: "#define KILL_PIN PB1" results in Ard_num of 57. 57 is then used as the
+ * argument to digitalPinToPinName(IO) to get the Port_pin number
+ * - if it is a digital or analog signal. PWMs are considered digital here.
+ *
+ * pin_xref is a structure generated by this header file. It is generated by the
+ * preprocessor. It is in port/pin order. It contains just the port/pin numbers defined by the
+ * platform for this variant.
+ * - Ard_num
+ * - printable version of Port_pin
+ *
+ * Routines with an "x" as a parameter/argument are used to search the pin_array to try to
+ * find a signal name associated with a port/pin.
+ *
+ * NOTE - the Arduino pin number is what is used by the M42 command, NOT the port/pin for that
+ * signal. The Arduino pin number is listed by the M43 I command.
+ */
+
+////////////////////////////////////////////////////////
+//
+// make a list of the Arduino pin numbers in the Port/Pin order
+//
+
+#define _PIN_ADD_2(NAME_ALPHA, ARDUINO_NUM) { {NAME_ALPHA}, ARDUINO_NUM },
+#define _PIN_ADD(NAME_ALPHA, ARDUINO_NUM) { NAME_ALPHA, ARDUINO_NUM },
+#define PIN_ADD(NAME) _PIN_ADD(#NAME, NAME)
+
+typedef struct {
+ char Port_pin_alpha[5];
+ pin_t Ard_num;
+} XrefInfo;
+
+const XrefInfo pin_xref[] PROGMEM = {
+ #include "pins_Xref.h"
+};
+
+////////////////////////////////////////////////////////////
+
+#define MODE_PIN_INPUT 0 // Input mode (reset state)
+#define MODE_PIN_OUTPUT 1 // General purpose output mode
+#define MODE_PIN_ALT 2 // Alternate function mode
+#define MODE_PIN_ANALOG 3 // Analog mode
+
+#define PIN_NUM(P) (P & 0x000F)
+#define PIN_NUM_ALPHA_LEFT(P) (((P & 0x000F) < 10) ? ('0' + (P & 0x000F)) : '1')
+#define PIN_NUM_ALPHA_RIGHT(P) (((P & 0x000F) > 9) ? ('0' + (P & 0x000F) - 10) : 0 )
+#define PORT_NUM(P) ((P >> 4) & 0x0007)
+#define PORT_ALPHA(P) ('A' + (P >> 4))
+
+/**
+ * Translation of routines & variables used by pinsDebug.h
+ */
+#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
+#define VALID_PIN(ANUM) ((ANUM) >= 0 && (ANUM) < NUMBER_PINS_TOTAL)
+#define digitalRead_mod(Ard_num) extDigitalRead(Ard_num) // must use Arduino pin numbers when doing reads
+#define PRINT_PIN(Q)
+#define PRINT_PORT(ANUM) port_print(ANUM)
+#define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine
+#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num
+
+// x is a variable used to search pin_array
+#define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital)
+#define GET_ARRAY_PIN(x) ((pin_t) pin_array[x].pin)
+#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
+#define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin
+
+#ifndef M43_NEVER_TOUCH
+ #define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP)
+ #ifdef KILL_PIN
+ #define M43_NEVER_TOUCH(Index) m43_never_touch(Index)
+
+ bool m43_never_touch(const pin_t Index) {
+ static pin_t M43_kill_index = -1;
+ if (M43_kill_index < 0)
+ for (M43_kill_index = 0; M43_kill_index < NUMBER_PINS_TOTAL; M43_kill_index++)
+ if (KILL_PIN == GET_PIN_MAP_PIN_M43(M43_kill_index)) break;
+ return _M43_NEVER_TOUCH(Index) || Index == M43_kill_index; // KILL_PIN and SERIAL/USB
+ }
+ #else
+ #define M43_NEVER_TOUCH(Index) _M43_NEVER_TOUCH(Index)
+ #endif
+#endif
+
+uint8_t get_pin_mode(const pin_t Ard_num) {
+ const PinName dp = digitalPinToPinName(Ard_num);
+ uint32_t ll_pin = STM_LL_GPIO_PIN(dp);
+ GPIO_TypeDef *port = get_GPIO_Port(STM_PORT(dp));
+ uint32_t mode = LL_GPIO_GetPinMode(port, ll_pin);
+ switch (mode) {
+ case LL_GPIO_MODE_ANALOG: return MODE_PIN_ANALOG;
+ case LL_GPIO_MODE_INPUT: return MODE_PIN_INPUT;
+ case LL_GPIO_MODE_OUTPUT: return MODE_PIN_OUTPUT;
+ case LL_GPIO_MODE_ALTERNATE: return MODE_PIN_ALT;
+ TERN_(STM32F1xx, case LL_GPIO_MODE_FLOATING:)
+ default: return 0;
+ }
+}
+
+bool GET_PINMODE(const pin_t Ard_num) {
+ const uint8_t pin_mode = get_pin_mode(Ard_num);
+ return pin_mode == MODE_PIN_OUTPUT || pin_mode == MODE_PIN_ALT; // assume all alt definitions are PWM
+}
+
+int8_t digital_pin_to_analog_pin(pin_t Ard_num) {
+ Ard_num -= NUM_ANALOG_FIRST;
+ return (Ard_num >= 0 && Ard_num < NUM_ANALOG_INPUTS) ? Ard_num : -1;
+}
+
+bool IS_ANALOG(const pin_t Ard_num) {
+ return get_pin_mode(Ard_num) == MODE_PIN_ANALOG;
+}
+
+bool is_digital(const pin_t x) {
+ const uint8_t pin_mode = get_pin_mode(pin_array[x].pin);
+ return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT;
+}
+
+void port_print(const pin_t Ard_num) {
+ char buffer[16];
+ pin_t Index;
+ for (Index = 0; Index < NUMBER_PINS_TOTAL; Index++)
+ if (Ard_num == GET_PIN_MAP_PIN_M43(Index)) break;
+
+ const char * ppa = pin_xref[Index].Port_pin_alpha;
+ sprintf_P(buffer, PSTR("%s"), ppa);
+ SERIAL_ECHO(buffer);
+ if (ppa[3] == '\0') SERIAL_CHAR(' ');
+
+ // print analog pin number
+ const int8_t Port_pin = digital_pin_to_analog_pin(Ard_num);
+ if (Port_pin >= 0) {
+ sprintf_P(buffer, PSTR(" (A%d) "), Port_pin);
+ SERIAL_ECHO(buffer);
+ if (Port_pin < 10) SERIAL_CHAR(' ');
+ }
+ else
+ SERIAL_ECHO_SP(7);
+
+ // Print number to be used with M42
+ sprintf_P(buffer, PSTR(" M42 P%d "), Ard_num);
+ SERIAL_ECHO(buffer);
+ if (Ard_num < 10) SERIAL_CHAR(' ');
+ if (Ard_num < 100) SERIAL_CHAR(' ');
+}
+
+bool pwm_status(const pin_t Ard_num) {
+ return get_pin_mode(Ard_num) == MODE_PIN_ALT;
+}
+
+void pwm_details(const pin_t Ard_num) {
+ #ifndef STM32F1xx
+ if (pwm_status(Ard_num)) {
+ uint32_t alt_all = 0;
+ const PinName dp = digitalPinToPinName(Ard_num);
+ pin_t pin_number = uint8_t(PIN_NUM(dp));
+ const bool over_7 = pin_number >= 8;
+ const uint8_t ind = over_7 ? 1 : 0;
+ switch (PORT_ALPHA(dp)) { // get alt function
+ case 'A' : alt_all = GPIOA->AFR[ind]; break;
+ case 'B' : alt_all = GPIOB->AFR[ind]; break;
+ case 'C' : alt_all = GPIOC->AFR[ind]; break;
+ case 'D' : alt_all = GPIOD->AFR[ind]; break;
+ #ifdef PE_0
+ case 'E' : alt_all = GPIOE->AFR[ind]; break;
+ #elif defined (PF_0)
+ case 'F' : alt_all = GPIOF->AFR[ind]; break;
+ #elif defined (PG_0)
+ case 'G' : alt_all = GPIOG->AFR[ind]; break;
+ #elif defined (PH_0)
+ case 'H' : alt_all = GPIOH->AFR[ind]; break;
+ #elif defined (PI_0)
+ case 'I' : alt_all = GPIOI->AFR[ind]; break;
+ #elif defined (PJ_0)
+ case 'J' : alt_all = GPIOJ->AFR[ind]; break;
+ #elif defined (PK_0)
+ case 'K' : alt_all = GPIOK->AFR[ind]; break;
+ #elif defined (PL_0)
+ case 'L' : alt_all = GPIOL->AFR[ind]; break;
+ #endif
+ }
+ if (over_7) pin_number -= 8;
+
+ uint8_t alt_func = (alt_all >> (4 * pin_number)) & 0x0F;
+ SERIAL_ECHOPAIR("Alt Function: ", alt_func);
+ if (alt_func < 10) SERIAL_CHAR(' ');
+ SERIAL_ECHOPGM(" - ");
+ switch (alt_func) {
+ case 0 : SERIAL_ECHOPGM("system (misc. I/O)"); break;
+ case 1 : SERIAL_ECHOPGM("TIM1/TIM2 (probably PWM)"); break;
+ case 2 : SERIAL_ECHOPGM("TIM3..5 (probably PWM)"); break;
+ case 3 : SERIAL_ECHOPGM("TIM8..11 (probably PWM)"); break;
+ case 4 : SERIAL_ECHOPGM("I2C1..3"); break;
+ case 5 : SERIAL_ECHOPGM("SPI1/SPI2"); break;
+ case 6 : SERIAL_ECHOPGM("SPI3"); break;
+ case 7 : SERIAL_ECHOPGM("USART1..3"); break;
+ case 8 : SERIAL_ECHOPGM("USART4..6"); break;
+ case 9 : SERIAL_ECHOPGM("CAN1/CAN2, TIM12..14 (probably PWM)"); break;
+ case 10 : SERIAL_ECHOPGM("OTG"); break;
+ case 11 : SERIAL_ECHOPGM("ETH"); break;
+ case 12 : SERIAL_ECHOPGM("FSMC, SDIO, OTG"); break;
+ case 13 : SERIAL_ECHOPGM("DCMI"); break;
+ case 14 : SERIAL_ECHOPGM("unused (shouldn't see this)"); break;
+ case 15 : SERIAL_ECHOPGM("EVENTOUT"); break;
+ }
+ }
+ #else
+ // TODO: F1 doesn't support changing pins function, so we need to check the function of the PIN and if it's enabled
+ #endif
+} // pwm_details
diff --git a/Marlin/src/HAL/STM32/pins_Xref.h b/Marlin/src/HAL/STM32/pins_Xref.h
new file mode 100644
index 0000000..890e561
--- /dev/null
+++ b/Marlin/src/HAL/STM32/pins_Xref.h
@@ -0,0 +1,612 @@
+/**
+ * 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/>.
+ *
+ */
+
+//
+// make a list of the Arduino pin numbers in the Port/Pin order
+//
+#ifdef PA0
+ PIN_ADD(PA0)
+#endif
+#ifdef PA1
+ PIN_ADD(PA1)
+#endif
+#ifdef PA2
+ PIN_ADD(PA2)
+#endif
+#ifdef PA3
+ PIN_ADD(PA3)
+#endif
+#ifdef PA4
+ PIN_ADD(PA4)
+#endif
+#ifdef PA5
+ PIN_ADD(PA5)
+#endif
+#ifdef PA6
+ PIN_ADD(PA6)
+#endif
+#ifdef PA7
+ PIN_ADD(PA7)
+#endif
+#ifdef PA8
+ PIN_ADD(PA8)
+#endif
+#ifdef PA9
+ PIN_ADD(PA9)
+#endif
+#ifdef PA10
+ PIN_ADD(PA10)
+#endif
+#ifdef PA11
+ PIN_ADD(PA11)
+#endif
+#ifdef PA12
+ PIN_ADD(PA12)
+#endif
+#ifdef PA13
+ PIN_ADD(PA13)
+#endif
+#ifdef PA14
+ PIN_ADD(PA14)
+#endif
+#ifdef PA15
+ PIN_ADD(PA15)
+#endif
+
+#ifdef PB0
+ PIN_ADD(PB0)
+#endif
+#ifdef PB1
+ PIN_ADD(PB1)
+#endif
+#ifdef PB2
+ PIN_ADD(PB2)
+#endif
+#ifdef PB3
+ PIN_ADD(PB3)
+#endif
+#ifdef PB4
+ PIN_ADD(PB4)
+#endif
+#ifdef PB5
+ PIN_ADD(PB5)
+#endif
+#ifdef PB6
+ PIN_ADD(PB6)
+#endif
+#ifdef PB7
+ PIN_ADD(PB7)
+#endif
+#ifdef PB8
+ PIN_ADD(PB8)
+#endif
+#ifdef PB9
+ PIN_ADD(PB9)
+#endif
+#ifdef PB10
+ PIN_ADD(PB10)
+#endif
+#ifdef PB11
+ PIN_ADD(PB11)
+#endif
+#ifdef PB12
+ PIN_ADD(PB12)
+#endif
+#ifdef PB13
+ PIN_ADD(PB13)
+#endif
+#ifdef PB14
+ PIN_ADD(PB14)
+#endif
+#ifdef PB15
+ PIN_ADD(PB15)
+#endif
+
+#ifdef PC0
+ PIN_ADD(PC0)
+#endif
+#ifdef PC1
+ PIN_ADD(PC1)
+#endif
+#ifdef PC2
+ PIN_ADD(PC2)
+#endif
+#ifdef PC3
+ PIN_ADD(PC3)
+#endif
+#ifdef PC4
+ PIN_ADD(PC4)
+#endif
+#ifdef PC5
+ PIN_ADD(PC5)
+#endif
+#ifdef PC6
+ PIN_ADD(PC6)
+#endif
+#ifdef PC7
+ PIN_ADD(PC7)
+#endif
+#ifdef PC8
+ PIN_ADD(PC8)
+#endif
+#ifdef PC9
+ PIN_ADD(PC9)
+#endif
+#ifdef PC10
+ PIN_ADD(PC10)
+#endif
+#ifdef PC11
+ PIN_ADD(PC11)
+#endif
+#ifdef PC12
+ PIN_ADD(PC12)
+#endif
+#ifdef PC13
+ PIN_ADD(PC13)
+#endif
+#ifdef PC14
+ PIN_ADD(PC14)
+#endif
+#ifdef PC15
+ PIN_ADD(PC15)
+#endif
+
+#ifdef PD0
+ PIN_ADD(PD0)
+#endif
+#ifdef PD1
+ PIN_ADD(PD1)
+#endif
+#ifdef PD2
+ PIN_ADD(PD2)
+#endif
+#ifdef PD3
+ PIN_ADD(PD3)
+#endif
+#ifdef PD4
+ PIN_ADD(PD4)
+#endif
+#ifdef PD5
+ PIN_ADD(PD5)
+#endif
+#ifdef PD6
+ PIN_ADD(PD6)
+#endif
+#ifdef PD7
+ PIN_ADD(PD7)
+#endif
+#ifdef PD8
+ PIN_ADD(PD8)
+#endif
+#ifdef PD9
+ PIN_ADD(PD9)
+#endif
+#ifdef PD10
+ PIN_ADD(PD10)
+#endif
+#ifdef PD11
+ PIN_ADD(PD11)
+#endif
+#ifdef PD12
+ PIN_ADD(PD12)
+#endif
+#ifdef PD13
+ PIN_ADD(PD13)
+#endif
+#ifdef PD14
+ PIN_ADD(PD14)
+#endif
+#ifdef PD15
+ PIN_ADD(PD15)
+#endif
+
+#ifdef PE0
+ PIN_ADD(PE0)
+#endif
+#ifdef PE1
+ PIN_ADD(PE1)
+#endif
+#ifdef PE2
+ PIN_ADD(PE2)
+#endif
+#ifdef PE3
+ PIN_ADD(PE3)
+#endif
+#ifdef PE4
+ PIN_ADD(PE4)
+#endif
+#ifdef PE5
+ PIN_ADD(PE5)
+#endif
+#ifdef PE6
+ PIN_ADD(PE6)
+#endif
+#ifdef PE7
+ PIN_ADD(PE7)
+#endif
+#ifdef PE8
+ PIN_ADD(PE8)
+#endif
+#ifdef PE9
+ PIN_ADD(PE9)
+#endif
+#ifdef PE10
+ PIN_ADD(PE10)
+#endif
+#ifdef PE11
+ PIN_ADD(PE11)
+#endif
+#ifdef PE12
+ PIN_ADD(PE12)
+#endif
+#ifdef PE13
+ PIN_ADD(PE13)
+#endif
+#ifdef PE14
+ PIN_ADD(PE14)
+#endif
+#ifdef PE15
+ PIN_ADD(PE15)
+#endif
+
+#ifdef PF0
+ PIN_ADD(PF0)
+#endif
+#ifdef PF1
+ PIN_ADD(PF1)
+#endif
+#ifdef PF2
+ PIN_ADD(PF2)
+#endif
+#ifdef PF3
+ PIN_ADD(PF3)
+#endif
+#ifdef PF4
+ PIN_ADD(PF4)
+#endif
+#ifdef PF5
+ PIN_ADD(PF5)
+#endif
+#ifdef PF6
+ PIN_ADD(PF6)
+#endif
+#ifdef PF7
+ PIN_ADD(PF7)
+#endif
+#ifdef PF8
+ PIN_ADD(PF8)
+#endif
+#ifdef PF9
+ PIN_ADD(PF9)
+#endif
+#ifdef PF10
+ PIN_ADD(PF10)
+#endif
+#ifdef PF11
+ PIN_ADD(PF11)
+#endif
+#ifdef PF12
+ PIN_ADD(PF12)
+#endif
+#ifdef PF13
+ PIN_ADD(PF13)
+#endif
+#ifdef PF14
+ PIN_ADD(PF14)
+#endif
+#ifdef PF15
+ PIN_ADD(PF15)
+#endif
+
+#ifdef PG0
+ PIN_ADD(PG0)
+#endif
+#ifdef PG1
+ PIN_ADD(PG1)
+#endif
+#ifdef PG2
+ PIN_ADD(PG2)
+#endif
+#ifdef PG3
+ PIN_ADD(PG3)
+#endif
+#ifdef PG4
+ PIN_ADD(PG4)
+#endif
+#ifdef PG5
+ PIN_ADD(PG5)
+#endif
+#ifdef PG6
+ PIN_ADD(PG6)
+#endif
+#ifdef PG7
+ PIN_ADD(PG7)
+#endif
+#ifdef PG8
+ PIN_ADD(PG8)
+#endif
+#ifdef PG9
+ PIN_ADD(PG9)
+#endif
+#ifdef PG10
+ PIN_ADD(PG10)
+#endif
+#ifdef PG11
+ PIN_ADD(PG11)
+#endif
+#ifdef PG12
+ PIN_ADD(PG12)
+#endif
+#ifdef PG13
+ PIN_ADD(PG13)
+#endif
+#ifdef PG14
+ PIN_ADD(PG14)
+#endif
+#ifdef PG15
+ PIN_ADD(PG15)
+#endif
+
+#ifdef PH0
+ PIN_ADD(PH0)
+#endif
+#ifdef PH1
+ PIN_ADD(PH1)
+#endif
+#ifdef PH2
+ PIN_ADD(PH2)
+#endif
+#ifdef PH3
+ PIN_ADD(PH3)
+#endif
+#ifdef PH4
+ PIN_ADD(PH4)
+#endif
+#ifdef PH5
+ PIN_ADD(PH5)
+#endif
+#ifdef PH6
+ PIN_ADD(PH6)
+#endif
+#ifdef PH7
+ PIN_ADD(PH7)
+#endif
+#ifdef PH8
+ PIN_ADD(PH8)
+#endif
+#ifdef PH9
+ PIN_ADD(PH9)
+#endif
+#ifdef PH10
+ PIN_ADD(PH10)
+#endif
+#ifdef PH11
+ PIN_ADD(PH11)
+#endif
+#ifdef PH12
+ PIN_ADD(PH12)
+#endif
+#ifdef PH13
+ PIN_ADD(PH13)
+#endif
+#ifdef PH14
+ PIN_ADD(PH14)
+#endif
+#ifdef PH15
+ PIN_ADD(PH15)
+#endif
+
+#ifdef PI0
+ PIN_ADD(PI0)
+#endif
+#ifdef PI1
+ PIN_ADD(PI1)
+#endif
+#ifdef PI2
+ PIN_ADD(PI2)
+#endif
+#ifdef PI3
+ PIN_ADD(PI3)
+#endif
+#ifdef PI4
+ PIN_ADD(PI4)
+#endif
+#ifdef PI5
+ PIN_ADD(PI5)
+#endif
+#ifdef PI6
+ PIN_ADD(PI6)
+#endif
+#ifdef PI7
+ PIN_ADD(PI7)
+#endif
+#ifdef PI8
+ PIN_ADD(PI8)
+#endif
+#ifdef PI9
+ PIN_ADD(PI9)
+#endif
+#ifdef PI10
+ PIN_ADD(PI10)
+#endif
+#ifdef PI11
+ PIN_ADD(PI11)
+#endif
+#ifdef PI12
+ PIN_ADD(PI12)
+#endif
+#ifdef PI13
+ PIN_ADD(PI13)
+#endif
+#ifdef PI14
+ PIN_ADD(PI14)
+#endif
+#ifdef PI15
+ PIN_ADD(PI15)
+#endif
+
+#ifdef PJ0
+ PIN_ADD(PJ0)
+#endif
+#ifdef PJ1
+ PIN_ADD(PJ1)
+#endif
+#ifdef PJ2
+ PIN_ADD(PJ2)
+#endif
+#ifdef PJ3
+ PIN_ADD(PJ3)
+#endif
+#ifdef PJ4
+ PIN_ADD(PJ4)
+#endif
+#ifdef PJ5
+ PIN_ADD(PJ5)
+#endif
+#ifdef PJ6
+ PIN_ADD(PJ6)
+#endif
+#ifdef PJ7
+ PIN_ADD(PJ7)
+#endif
+#ifdef PJ8
+ PIN_ADD(PJ8)
+#endif
+#ifdef PJ9
+ PIN_ADD(PJ9)
+#endif
+#ifdef PJ10
+ PIN_ADD(PJ10)
+#endif
+#ifdef PJ11
+ PIN_ADD(PJ11)
+#endif
+#ifdef PJ12
+ PIN_ADD(PJ12)
+#endif
+#ifdef PJ13
+ PIN_ADD(PJ13)
+#endif
+#ifdef PJ14
+ PIN_ADD(PJ14)
+#endif
+#ifdef PJ15
+ PIN_ADD(PJ15)
+#endif
+
+#ifdef PK0
+ PIN_ADD(PK0)
+#endif
+#ifdef PK1
+ PIN_ADD(PK1)
+#endif
+#ifdef PK2
+ PIN_ADD(PK2)
+#endif
+#ifdef PK3
+ PIN_ADD(PK3)
+#endif
+#ifdef PK4
+ PIN_ADD(PK4)
+#endif
+#ifdef PK5
+ PIN_ADD(PK5)
+#endif
+#ifdef PK6
+ PIN_ADD(PK6)
+#endif
+#ifdef PK7
+ PIN_ADD(PK7)
+#endif
+#ifdef PK8
+ PIN_ADD(PK8)
+#endif
+#ifdef PK9
+ PIN_ADD(PK9)
+#endif
+#ifdef PK10
+ PIN_ADD(PK10)
+#endif
+#ifdef PK11
+ PIN_ADD(PK11)
+#endif
+#ifdef PK12
+ PIN_ADD(PK12)
+#endif
+#ifdef PK13
+ PIN_ADD(PK13)
+#endif
+#ifdef PK14
+ PIN_ADD(PK14)
+#endif
+#ifdef PK15
+ PIN_ADD(PK15)
+#endif
+
+#ifdef PL0
+ PIN_ADD(PL0)
+#endif
+#ifdef PL1
+ PIN_ADD(PL1)
+#endif
+#ifdef PL2
+ PIN_ADD(PL2)
+#endif
+#ifdef PL3
+ PIN_ADD(PL3)
+#endif
+#ifdef PL4
+ PIN_ADD(PL4)
+#endif
+#ifdef PL5
+ PIN_ADD(PL5)
+#endif
+#ifdef PL6
+ PIN_ADD(PL6)
+#endif
+#ifdef PL7
+ PIN_ADD(PL7)
+#endif
+#ifdef PL8
+ PIN_ADD(PL8)
+#endif
+#ifdef PL9
+ PIN_ADD(PL9)
+#endif
+#ifdef PL10
+ PIN_ADD(PL10)
+#endif
+#ifdef PL11
+ PIN_ADD(PL11)
+#endif
+#ifdef PL12
+ PIN_ADD(PL12)
+#endif
+#ifdef PL13
+ PIN_ADD(PL13)
+#endif
+#ifdef PL14
+ PIN_ADD(PL14)
+#endif
+#ifdef PL15
+ PIN_ADD(PL15)
+#endif
diff --git a/Marlin/src/HAL/STM32/spi_pins.h b/Marlin/src/HAL/STM32/spi_pins.h
new file mode 100644
index 0000000..e2052c5
--- /dev/null
+++ b/Marlin/src/HAL/STM32/spi_pins.h
@@ -0,0 +1,35 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * 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
+
+/**
+ * Define SPI Pins: SCK, MISO, MOSI, SS
+ */
+#ifndef SD_SCK_PIN
+ #define SD_SCK_PIN PIN_SPI_SCK
+#endif
+#ifndef SD_MISO_PIN
+ #define SD_MISO_PIN PIN_SPI_MISO
+#endif
+#ifndef SD_MOSI_PIN
+ #define SD_MOSI_PIN PIN_SPI_MOSI
+#endif
+#ifndef SD_SS_PIN
+ #define SD_SS_PIN PIN_SPI_SS
+#endif
diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp
new file mode 100644
index 0000000..87ca2db
--- /dev/null
+++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp
@@ -0,0 +1,181 @@
+/**
+ * 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/>.
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../../inc/MarlinConfig.h"
+
+#if HAS_FSMC_TFT
+
+#include "tft_fsmc.h"
+#include "pinconfig.h"
+
+SRAM_HandleTypeDef TFT_FSMC::SRAMx;
+DMA_HandleTypeDef TFT_FSMC::DMAtx;
+LCD_CONTROLLER_TypeDef *TFT_FSMC::LCD;
+
+void TFT_FSMC::Init() {
+ uint32_t controllerAddress;
+
+ #if PIN_EXISTS(TFT_RESET)
+ OUT_WRITE(TFT_RESET_PIN, HIGH);
+ HAL_Delay(100);
+ #endif
+
+ #if PIN_EXISTS(TFT_BACKLIGHT)
+ OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH);
+ #endif
+
+ FSMC_NORSRAM_TimingTypeDef Timing, ExtTiming;
+
+ uint32_t NSBank = (uint32_t)pinmap_peripheral(digitalPinToPinName(TFT_CS_PIN), PinMap_FSMC_CS);
+
+ // Perform the SRAM1 memory initialization sequence
+ SRAMx.Instance = FSMC_NORSRAM_DEVICE;
+ SRAMx.Extended = FSMC_NORSRAM_EXTENDED_DEVICE;
+ // SRAMx.Init
+ SRAMx.Init.NSBank = NSBank;
+ SRAMx.Init.DataAddressMux = FSMC_DATA_ADDRESS_MUX_DISABLE;
+ SRAMx.Init.MemoryType = FSMC_MEMORY_TYPE_SRAM;
+ SRAMx.Init.MemoryDataWidth = TERN(TFT_INTERFACE_FSMC_8BIT, FSMC_NORSRAM_MEM_BUS_WIDTH_8, FSMC_NORSRAM_MEM_BUS_WIDTH_16);
+ SRAMx.Init.BurstAccessMode = FSMC_BURST_ACCESS_MODE_DISABLE;
+ SRAMx.Init.WaitSignalPolarity = FSMC_WAIT_SIGNAL_POLARITY_LOW;
+ SRAMx.Init.WrapMode = FSMC_WRAP_MODE_DISABLE;
+ SRAMx.Init.WaitSignalActive = FSMC_WAIT_TIMING_BEFORE_WS;
+ SRAMx.Init.WriteOperation = FSMC_WRITE_OPERATION_ENABLE;
+ SRAMx.Init.WaitSignal = FSMC_WAIT_SIGNAL_DISABLE;
+ SRAMx.Init.ExtendedMode = FSMC_EXTENDED_MODE_ENABLE;
+ SRAMx.Init.AsynchronousWait = FSMC_ASYNCHRONOUS_WAIT_DISABLE;
+ SRAMx.Init.WriteBurst = FSMC_WRITE_BURST_DISABLE;
+ #ifdef STM32F4xx
+ SRAMx.Init.PageSize = FSMC_PAGE_SIZE_NONE;
+ #endif
+ // Read Timing - relatively slow to ensure ID information is correctly read from TFT controller
+ // Can be decreases from 15-15-24 to 4-4-8 with risk of stability loss
+ Timing.AddressSetupTime = 15;
+ Timing.AddressHoldTime = 15;
+ Timing.DataSetupTime = 24;
+ Timing.BusTurnAroundDuration = 0;
+ Timing.CLKDivision = 16;
+ Timing.DataLatency = 17;
+ Timing.AccessMode = FSMC_ACCESS_MODE_A;
+ // Write Timing
+ // Can be decreases from 8-15-8 to 0-0-1 with risk of stability loss
+ ExtTiming.AddressSetupTime = 8;
+ ExtTiming.AddressHoldTime = 15;
+ ExtTiming.DataSetupTime = 8;
+ ExtTiming.BusTurnAroundDuration = 0;
+ ExtTiming.CLKDivision = 16;
+ ExtTiming.DataLatency = 17;
+ ExtTiming.AccessMode = FSMC_ACCESS_MODE_A;
+
+ __HAL_RCC_FSMC_CLK_ENABLE();
+
+ for (uint16_t i = 0; PinMap_FSMC[i].pin != NC; i++)
+ pinmap_pinout(PinMap_FSMC[i].pin, PinMap_FSMC);
+ pinmap_pinout(digitalPinToPinName(TFT_CS_PIN), PinMap_FSMC_CS);
+ pinmap_pinout(digitalPinToPinName(TFT_RS_PIN), PinMap_FSMC_RS);
+
+ controllerAddress = FSMC_BANK1_1;
+ #ifdef PF0
+ switch (NSBank) {
+ case FSMC_NORSRAM_BANK2: controllerAddress = FSMC_BANK1_2 ; break;
+ case FSMC_NORSRAM_BANK3: controllerAddress = FSMC_BANK1_3 ; break;
+ case FSMC_NORSRAM_BANK4: controllerAddress = FSMC_BANK1_4 ; break;
+ }
+ #endif
+
+ controllerAddress |= (uint32_t)pinmap_peripheral(digitalPinToPinName(TFT_RS_PIN), PinMap_FSMC_RS);
+
+ HAL_SRAM_Init(&SRAMx, &Timing, &ExtTiming);
+
+ __HAL_RCC_DMA2_CLK_ENABLE();
+
+ #ifdef STM32F1xx
+ DMAtx.Instance = DMA2_Channel1;
+ #elif defined(STM32F4xx)
+ DMAtx.Instance = DMA2_Stream0;
+ DMAtx.Init.Channel = DMA_CHANNEL_0;
+ DMAtx.Init.FIFOMode = DMA_FIFOMODE_ENABLE;
+ DMAtx.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL;
+ DMAtx.Init.MemBurst = DMA_MBURST_SINGLE;
+ DMAtx.Init.PeriphBurst = DMA_PBURST_SINGLE;
+ #endif
+
+ DMAtx.Init.Direction = DMA_MEMORY_TO_MEMORY;
+ DMAtx.Init.MemInc = DMA_MINC_DISABLE;
+ DMAtx.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD;
+ DMAtx.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD;
+ DMAtx.Init.Mode = DMA_NORMAL;
+ DMAtx.Init.Priority = DMA_PRIORITY_HIGH;
+
+ LCD = (LCD_CONTROLLER_TypeDef *)controllerAddress;
+}
+
+uint32_t TFT_FSMC::GetID() {
+ uint32_t id;
+ WriteReg(0);
+ id = LCD->RAM;
+
+ if (id == 0)
+ id = ReadID(LCD_READ_ID);
+ if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF)
+ id = ReadID(LCD_READ_ID4);
+ return id;
+}
+
+uint32_t TFT_FSMC::ReadID(tft_data_t Reg) {
+ uint32_t id;
+ WriteReg(Reg);
+ id = LCD->RAM; // dummy read
+ id = Reg << 24;
+ id |= (LCD->RAM & 0x00FF) << 16;
+ id |= (LCD->RAM & 0x00FF) << 8;
+ id |= LCD->RAM & 0x00FF;
+ return id;
+}
+
+bool TFT_FSMC::isBusy() {
+ #if defined(STM32F1xx)
+ volatile bool dmaEnabled = (DMAtx.Instance->CCR & DMA_CCR_EN) != RESET;
+ #elif defined(STM32F4xx)
+ volatile bool dmaEnabled = DMAtx.Instance->CR & DMA_SxCR_EN;
+ #endif
+ if (dmaEnabled) {
+ if (__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TC_FLAG_INDEX(&DMAtx)) != 0 || __HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TE_FLAG_INDEX(&DMAtx)) != 0)
+ Abort();
+ }
+ else
+ Abort();
+ return dmaEnabled;
+}
+
+void TFT_FSMC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
+ DMAtx.Init.PeriphInc = MemoryIncrease;
+ HAL_DMA_Init(&DMAtx);
+ DataTransferBegin();
+ HAL_DMA_Start(&DMAtx, (uint32_t)Data, (uint32_t)&(LCD->RAM), Count);
+ HAL_DMA_PollForTransfer(&DMAtx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY);
+ Abort();
+}
+
+#endif // HAS_FSMC_TFT
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.h b/Marlin/src/HAL/STM32/tft/tft_fsmc.h
new file mode 100644
index 0000000..2200aba
--- /dev/null
+++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.h
@@ -0,0 +1,171 @@
+/**
+ * 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 "../../../inc/MarlinConfig.h"
+
+#ifdef STM32F1xx
+ #include "stm32f1xx_hal.h"
+#elif defined(STM32F4xx)
+ #include "stm32f4xx_hal.h"
+#else
+ #error "FSMC TFT is currently only supported on STM32F1 and STM32F4 hardware."
+#endif
+
+#ifndef LCD_READ_ID
+ #define LCD_READ_ID 0x04 // Read display identification information (0xD3 on ILI9341)
+#endif
+#ifndef LCD_READ_ID4
+ #define LCD_READ_ID4 0xD3 // Read display identification information (0xD3 on ILI9341)
+#endif
+
+#define DATASIZE_8BIT SPI_DATASIZE_8BIT
+#define DATASIZE_16BIT SPI_DATASIZE_16BIT
+#define TFT_IO_DRIVER TFT_FSMC
+
+#define TFT_DATASIZE TERN(TFT_INTERFACE_FSMC_8BIT, DATASIZE_8BIT, DATASIZE_16BIT)
+typedef TERN(TFT_INTERFACE_FSMC_8BIT, uint8_t, uint16_t) tft_data_t;
+
+typedef struct {
+ __IO tft_data_t REG;
+ __IO tft_data_t RAM;
+} LCD_CONTROLLER_TypeDef;
+
+class TFT_FSMC {
+ private:
+ static SRAM_HandleTypeDef SRAMx;
+ static DMA_HandleTypeDef DMAtx;
+
+ static LCD_CONTROLLER_TypeDef *LCD;
+
+ static uint32_t ReadID(tft_data_t Reg);
+ static void Transmit(tft_data_t Data) { LCD->RAM = Data; __DSB(); }
+ static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count);
+
+ public:
+ static void Init();
+ static uint32_t GetID();
+ static bool isBusy();
+ static void Abort() { __HAL_DMA_DISABLE(&DMAtx); }
+
+ static void DataTransferBegin(uint16_t DataWidth = TFT_DATASIZE) {}
+ static void DataTransferEnd() {};
+
+ static void WriteData(uint16_t Data) { Transmit(tft_data_t(Data)); }
+ static void WriteReg(uint16_t Reg) { LCD->REG = tft_data_t(Reg); __DSB(); }
+
+ static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_PINC_ENABLE, Data, Count); }
+ static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_PINC_DISABLE, &Data, Count); }
+ static void WriteMultiple(uint16_t Color, uint32_t Count) {
+ static uint16_t Data; Data = Color;
+ while (Count > 0) {
+ TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count);
+ Count = Count > 0xFFFF ? Count - 0xFFFF : 0;
+ }
+ }
+};
+
+#ifdef STM32F1xx
+ #define FSMC_PIN_DATA STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_NONE)
+#elif defined(STM32F4xx)
+ #define FSMC_PIN_DATA STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_FSMC)
+ #define FSMC_BANK1_1 0x60000000U
+ #define FSMC_BANK1_2 0x64000000U
+ #define FSMC_BANK1_3 0x68000000U
+ #define FSMC_BANK1_4 0x6C000000U
+#else
+ #error No configuration for this MCU
+#endif
+
+const PinMap PinMap_FSMC[] = {
+ {PD_14, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D00
+ {PD_15, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D01
+ {PD_0, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D02
+ {PD_1, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D03
+ {PE_7, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D04
+ {PE_8, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D05
+ {PE_9, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D06
+ {PE_10, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D07
+ #if DISABLED(TFT_INTERFACE_FSMC_8BIT)
+ {PE_11, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D08
+ {PE_12, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D09
+ {PE_13, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D10
+ {PE_14, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D11
+ {PE_15, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D12
+ {PD_8, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D13
+ {PD_9, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D14
+ {PD_10, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_D15
+ #endif
+ {PD_4, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_NOE
+ {PD_5, FSMC_NORSRAM_DEVICE, FSMC_PIN_DATA}, // FSMC_NWE
+ {NC, NP, 0}
+};
+
+const PinMap PinMap_FSMC_CS[] = {
+ {PD_7, (void *)FSMC_NORSRAM_BANK1, FSMC_PIN_DATA}, // FSMC_NE1
+ #ifdef PF0
+ {PG_9, (void *)FSMC_NORSRAM_BANK2, FSMC_PIN_DATA}, // FSMC_NE2
+ {PG_10, (void *)FSMC_NORSRAM_BANK3, FSMC_PIN_DATA}, // FSMC_NE3
+ {PG_12, (void *)FSMC_NORSRAM_BANK4, FSMC_PIN_DATA}, // FSMC_NE4
+ #endif
+ {NC, NP, 0}
+};
+
+#if ENABLED(TFT_INTERFACE_FSMC_8BIT)
+ #define FSMC_RS(A) (void *)((2 << (A-1)) - 1)
+#else
+ #define FSMC_RS(A) (void *)((2 << A) - 2)
+#endif
+
+const PinMap PinMap_FSMC_RS[] = {
+ #ifdef PF0
+ {PF_0, FSMC_RS( 0), FSMC_PIN_DATA}, // FSMC_A0
+ {PF_1, FSMC_RS( 1), FSMC_PIN_DATA}, // FSMC_A1
+ {PF_2, FSMC_RS( 2), FSMC_PIN_DATA}, // FSMC_A2
+ {PF_3, FSMC_RS( 3), FSMC_PIN_DATA}, // FSMC_A3
+ {PF_4, FSMC_RS( 4), FSMC_PIN_DATA}, // FSMC_A4
+ {PF_5, FSMC_RS( 5), FSMC_PIN_DATA}, // FSMC_A5
+ {PF_12, FSMC_RS( 6), FSMC_PIN_DATA}, // FSMC_A6
+ {PF_13, FSMC_RS( 7), FSMC_PIN_DATA}, // FSMC_A7
+ {PF_14, FSMC_RS( 8), FSMC_PIN_DATA}, // FSMC_A8
+ {PF_15, FSMC_RS( 9), FSMC_PIN_DATA}, // FSMC_A9
+ {PG_0, FSMC_RS(10), FSMC_PIN_DATA}, // FSMC_A10
+ {PG_1, FSMC_RS(11), FSMC_PIN_DATA}, // FSMC_A11
+ {PG_2, FSMC_RS(12), FSMC_PIN_DATA}, // FSMC_A12
+ {PG_3, FSMC_RS(13), FSMC_PIN_DATA}, // FSMC_A13
+ {PG_4, FSMC_RS(14), FSMC_PIN_DATA}, // FSMC_A14
+ {PG_5, FSMC_RS(15), FSMC_PIN_DATA}, // FSMC_A15
+ #endif
+ {PD_11, FSMC_RS(16), FSMC_PIN_DATA}, // FSMC_A16
+ {PD_12, FSMC_RS(17), FSMC_PIN_DATA}, // FSMC_A17
+ {PD_13, FSMC_RS(18), FSMC_PIN_DATA}, // FSMC_A18
+ {PE_3, FSMC_RS(19), FSMC_PIN_DATA}, // FSMC_A19
+ {PE_4, FSMC_RS(20), FSMC_PIN_DATA}, // FSMC_A20
+ {PE_5, FSMC_RS(21), FSMC_PIN_DATA}, // FSMC_A21
+ {PE_6, FSMC_RS(22), FSMC_PIN_DATA}, // FSMC_A22
+ {PE_2, FSMC_RS(23), FSMC_PIN_DATA}, // FSMC_A23
+ #ifdef PF0
+ {PG_13, FSMC_RS(24), FSMC_PIN_DATA}, // FSMC_A24
+ {PG_14, FSMC_RS(25), FSMC_PIN_DATA}, // FSMC_A25
+ #endif
+ {NC, NP, 0}
+};
diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.cpp b/Marlin/src/HAL/STM32/tft/tft_spi.cpp
new file mode 100644
index 0000000..3cb797d
--- /dev/null
+++ b/Marlin/src/HAL/STM32/tft/tft_spi.cpp
@@ -0,0 +1,235 @@
+/**
+ * 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/>.
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../../inc/MarlinConfig.h"
+
+#if HAS_SPI_TFT
+
+#include "tft_spi.h"
+#include "pinconfig.h"
+
+SPI_HandleTypeDef TFT_SPI::SPIx;
+DMA_HandleTypeDef TFT_SPI::DMAtx;
+
+void TFT_SPI::Init() {
+ SPI_TypeDef *spiInstance;
+
+ OUT_WRITE(TFT_A0_PIN, HIGH);
+ OUT_WRITE(TFT_CS_PIN, HIGH);
+
+ if ((spiInstance = (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TFT_SCK_PIN), PinMap_SPI_SCLK)) == NP) return;
+ if (spiInstance != (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TFT_MOSI_PIN), PinMap_SPI_MOSI)) return;
+
+ #if PIN_EXISTS(TFT_MISO) && TFT_MISO_PIN != TFT_MOSI_PIN
+ if (spiInstance != (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TFT_MISO_PIN), PinMap_SPI_MISO)) return;
+ #endif
+
+ SPIx.Instance = spiInstance;
+ SPIx.State = HAL_SPI_STATE_RESET;
+ SPIx.Init.NSS = SPI_NSS_SOFT;
+ SPIx.Init.Mode = SPI_MODE_MASTER;
+ SPIx.Init.Direction = (TFT_MISO_PIN == TFT_MOSI_PIN) ? SPI_DIRECTION_1LINE : SPI_DIRECTION_2LINES;
+ SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2;
+ SPIx.Init.CLKPhase = SPI_PHASE_1EDGE;
+ SPIx.Init.CLKPolarity = SPI_POLARITY_LOW;
+ SPIx.Init.DataSize = SPI_DATASIZE_8BIT;
+ SPIx.Init.FirstBit = SPI_FIRSTBIT_MSB;
+ SPIx.Init.TIMode = SPI_TIMODE_DISABLE;
+ SPIx.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
+ SPIx.Init.CRCPolynomial = 10;
+
+ pinmap_pinout(digitalPinToPinName(TFT_SCK_PIN), PinMap_SPI_SCLK);
+ pinmap_pinout(digitalPinToPinName(TFT_MOSI_PIN), PinMap_SPI_MOSI);
+ #if PIN_EXISTS(TFT_MISO) && TFT_MISO_PIN != TFT_MOSI_PIN
+ pinmap_pinout(digitalPinToPinName(TFT_MISO_PIN), PinMap_SPI_MISO);
+ #endif
+ pin_PullConfig(get_GPIO_Port(STM_PORT(digitalPinToPinName(TFT_SCK_PIN))), STM_LL_GPIO_PIN(digitalPinToPinName(TFT_SCK_PIN)), GPIO_PULLDOWN);
+
+ #ifdef SPI1_BASE
+ if (SPIx.Instance == SPI1) {
+ __HAL_RCC_SPI1_CLK_ENABLE();
+ #ifdef STM32F1xx
+ __HAL_RCC_DMA1_CLK_ENABLE();
+ DMAtx.Instance = DMA1_Channel3;
+ #elif defined(STM32F4xx)
+ __HAL_RCC_DMA2_CLK_ENABLE();
+ DMAtx.Instance = DMA2_Stream3;
+ DMAtx.Init.Channel = DMA_CHANNEL_3;
+ #endif
+ SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_4;
+ }
+ #endif
+ #ifdef SPI2_BASE
+ if (SPIx.Instance == SPI2) {
+ __HAL_RCC_SPI2_CLK_ENABLE();
+ #ifdef STM32F1xx
+ __HAL_RCC_DMA1_CLK_ENABLE();
+ DMAtx.Instance = DMA1_Channel5;
+ #elif defined(STM32F4xx)
+ __HAL_RCC_DMA1_CLK_ENABLE();
+ DMAtx.Instance = DMA1_Stream4;
+ DMAtx.Init.Channel = DMA_CHANNEL_0;
+ #endif
+ }
+ #endif
+ #ifdef SPI3_BASE
+ if (SPIx.Instance == SPI3) {
+ __HAL_RCC_SPI3_CLK_ENABLE();
+ #ifdef STM32F1xx
+ __HAL_RCC_DMA2_CLK_ENABLE();
+ DMAtx.Instance = DMA2_Channel2;
+ #elif defined(STM32F4xx)
+ __HAL_RCC_DMA1_CLK_ENABLE();
+ DMAtx.Instance = DMA1_Stream5;
+ DMAtx.Init.Channel = DMA_CHANNEL_0;
+ #endif
+ }
+ #endif
+
+ HAL_SPI_Init(&SPIx);
+
+ DMAtx.Init.Direction = DMA_MEMORY_TO_PERIPH;
+ DMAtx.Init.PeriphInc = DMA_PINC_DISABLE;
+ DMAtx.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD;
+ DMAtx.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD;
+ DMAtx.Init.Mode = DMA_NORMAL;
+ DMAtx.Init.Priority = DMA_PRIORITY_LOW;
+ #ifdef STM32F4xx
+ DMAtx.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
+ #endif
+}
+
+void TFT_SPI::DataTransferBegin(uint16_t DataSize) {
+ SPIx.Init.DataSize = DataSize == DATASIZE_8BIT ? SPI_DATASIZE_8BIT : SPI_DATASIZE_16BIT;
+ HAL_SPI_Init(&SPIx);
+ WRITE(TFT_CS_PIN, LOW);
+}
+
+uint32_t TFT_SPI::GetID() {
+ uint32_t id;
+ id = ReadID(LCD_READ_ID);
+
+ if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF)
+ id = ReadID(LCD_READ_ID4);
+ return id;
+}
+
+uint32_t TFT_SPI::ReadID(uint16_t Reg) {
+ uint32_t Data = 0;
+ #if PIN_EXISTS(TFT_MISO)
+ uint32_t BaudRatePrescaler = SPIx.Init.BaudRatePrescaler;
+ uint32_t i;
+
+ SPIx.Init.BaudRatePrescaler = SPIx.Instance == SPI1 ? SPI_BAUDRATEPRESCALER_8 : SPI_BAUDRATEPRESCALER_4;
+ DataTransferBegin(DATASIZE_8BIT);
+ WriteReg(Reg);
+
+ if (SPIx.Init.Direction == SPI_DIRECTION_1LINE) SPI_1LINE_RX(&SPIx);
+ __HAL_SPI_ENABLE(&SPIx);
+
+ for (i = 0; i < 4; i++) {
+ #if TFT_MISO_PIN != TFT_MOSI_PIN
+ //if (hspi->Init.Direction == SPI_DIRECTION_2LINES) {
+ while ((SPIx.Instance->SR & SPI_FLAG_TXE) != SPI_FLAG_TXE) {}
+ SPIx.Instance->DR = 0;
+ //}
+ #endif
+ while ((SPIx.Instance->SR & SPI_FLAG_RXNE) != SPI_FLAG_RXNE) {}
+ Data = (Data << 8) | SPIx.Instance->DR;
+ }
+
+ __HAL_SPI_DISABLE(&SPIx);
+ DataTransferEnd();
+
+ SPIx.Init.BaudRatePrescaler = BaudRatePrescaler;
+ #endif
+
+ return Data >> 7;
+}
+
+bool TFT_SPI::isBusy() {
+ #if defined(STM32F1xx)
+ volatile bool dmaEnabled = (DMAtx.Instance->CCR & DMA_CCR_EN) != RESET;
+ #elif defined(STM32F4xx)
+ volatile bool dmaEnabled = DMAtx.Instance->CR & DMA_SxCR_EN;
+ #endif
+ if (dmaEnabled) {
+ if (__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TC_FLAG_INDEX(&DMAtx)) != 0 || __HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TE_FLAG_INDEX(&DMAtx)) != 0)
+ Abort();
+ }
+ else
+ Abort();
+ return dmaEnabled;
+}
+
+void TFT_SPI::Abort() {
+ // Wait for any running spi
+ while ((SPIx.Instance->SR & SPI_FLAG_TXE) != SPI_FLAG_TXE) {}
+ while ((SPIx.Instance->SR & SPI_FLAG_BSY) == SPI_FLAG_BSY) {}
+ // First, abort any running dma
+ HAL_DMA_Abort(&DMAtx);
+ // DeInit objects
+ HAL_DMA_DeInit(&DMAtx);
+ HAL_SPI_DeInit(&SPIx);
+ // Deselect CS
+ DataTransferEnd();
+}
+
+void TFT_SPI::Transmit(uint16_t Data) {
+ if (TFT_MISO_PIN == TFT_MOSI_PIN)
+ SPI_1LINE_TX(&SPIx);
+
+ __HAL_SPI_ENABLE(&SPIx);
+
+ SPIx.Instance->DR = Data;
+
+ while ((SPIx.Instance->SR & SPI_FLAG_TXE) != SPI_FLAG_TXE) {}
+ while ((SPIx.Instance->SR & SPI_FLAG_BSY) == SPI_FLAG_BSY) {}
+
+ if (TFT_MISO_PIN != TFT_MOSI_PIN)
+ __HAL_SPI_CLEAR_OVRFLAG(&SPIx); /* Clear overrun flag in 2 Lines communication mode because received is not read */
+}
+
+void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
+ // Wait last dma finish, to start another
+ while(isBusy()) { }
+
+ DMAtx.Init.MemInc = MemoryIncrease;
+ HAL_DMA_Init(&DMAtx);
+
+ if (TFT_MISO_PIN == TFT_MOSI_PIN)
+ SPI_1LINE_TX(&SPIx);
+
+ DataTransferBegin();
+
+ HAL_DMA_Start(&DMAtx, (uint32_t)Data, (uint32_t)&(SPIx.Instance->DR), Count);
+ __HAL_SPI_ENABLE(&SPIx);
+
+ SET_BIT(SPIx.Instance->CR2, SPI_CR2_TXDMAEN); /* Enable Tx DMA Request */
+
+ HAL_DMA_PollForTransfer(&DMAtx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY);
+ Abort();
+}
+
+#endif // HAS_SPI_TFT
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.h b/Marlin/src/HAL/STM32/tft/tft_spi.h
new file mode 100644
index 0000000..667b5f3
--- /dev/null
+++ b/Marlin/src/HAL/STM32/tft/tft_spi.h
@@ -0,0 +1,74 @@
+/**
+ * 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
+
+#ifdef STM32F1xx
+ #include "stm32f1xx_hal.h"
+#elif defined(STM32F4xx)
+ #include "stm32f4xx_hal.h"
+#else
+ #error SPI TFT is currently only supported on STM32F1 and STM32F4 hardware.
+#endif
+
+#ifndef LCD_READ_ID
+ #define LCD_READ_ID 0x04 // Read display identification information (0xD3 on ILI9341)
+#endif
+#ifndef LCD_READ_ID4
+ #define LCD_READ_ID4 0xD3 // Read display identification information (0xD3 on ILI9341)
+#endif
+
+#define DATASIZE_8BIT SPI_DATASIZE_8BIT
+#define DATASIZE_16BIT SPI_DATASIZE_16BIT
+#define TFT_IO_DRIVER TFT_SPI
+
+class TFT_SPI {
+private:
+ static SPI_HandleTypeDef SPIx;
+ static DMA_HandleTypeDef DMAtx;
+
+ static uint32_t ReadID(uint16_t Reg);
+ static void Transmit(uint16_t Data);
+ static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count);
+
+public:
+ static void Init();
+ static uint32_t GetID();
+ static bool isBusy();
+ static void Abort();
+
+ static void DataTransferBegin(uint16_t DataWidth = DATASIZE_16BIT);
+ static void DataTransferEnd() { WRITE(TFT_CS_PIN, HIGH); };
+ static void DataTransferAbort();
+
+ static void WriteData(uint16_t Data) { Transmit(Data); }
+ static void WriteReg(uint16_t Reg) { WRITE(TFT_A0_PIN, LOW); Transmit(Reg); WRITE(TFT_A0_PIN, HIGH); }
+
+ static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); }
+ static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); }
+ static void WriteMultiple(uint16_t Color, uint32_t Count) {
+ static uint16_t Data; Data = Color;
+ while (Count > 0) {
+ TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count);
+ Count = Count > 0xFFFF ? Count - 0xFFFF : 0;
+ }
+ }
+};
diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.cpp b/Marlin/src/HAL/STM32/tft/xpt2046.cpp
new file mode 100644
index 0000000..04294e6
--- /dev/null
+++ b/Marlin/src/HAL/STM32/tft/xpt2046.cpp
@@ -0,0 +1,170 @@
+/**
+ * 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/>.
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../../inc/MarlinConfig.h"
+
+#if HAS_TFT_XPT2046 || HAS_TOUCH_BUTTONS
+
+#include "xpt2046.h"
+#include "pinconfig.h"
+
+uint16_t delta(uint16_t a, uint16_t b) { return a > b ? a - b : b - a; }
+
+SPI_HandleTypeDef XPT2046::SPIx;
+
+void XPT2046::Init() {
+ SPI_TypeDef *spiInstance;
+
+ OUT_WRITE(TOUCH_CS_PIN, HIGH);
+
+ #if PIN_EXISTS(TOUCH_INT)
+ // Optional Pendrive interrupt pin
+ SET_INPUT(TOUCH_INT_PIN);
+ #endif
+
+ spiInstance = (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TOUCH_SCK_PIN), PinMap_SPI_SCLK);
+ if (spiInstance != (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TOUCH_MOSI_PIN), PinMap_SPI_MOSI)) spiInstance = NP;
+ if (spiInstance != (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TOUCH_MISO_PIN), PinMap_SPI_MISO)) spiInstance = NP;
+
+ SPIx.Instance = spiInstance;
+
+ if (SPIx.Instance) {
+ SPIx.State = HAL_SPI_STATE_RESET;
+ SPIx.Init.NSS = SPI_NSS_SOFT;
+ SPIx.Init.Mode = SPI_MODE_MASTER;
+ SPIx.Init.Direction = SPI_DIRECTION_2LINES;
+ SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_8;
+ SPIx.Init.CLKPhase = SPI_PHASE_2EDGE;
+ SPIx.Init.CLKPolarity = SPI_POLARITY_HIGH;
+ SPIx.Init.DataSize = SPI_DATASIZE_8BIT;
+ SPIx.Init.FirstBit = SPI_FIRSTBIT_MSB;
+ SPIx.Init.TIMode = SPI_TIMODE_DISABLE;
+ SPIx.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
+ SPIx.Init.CRCPolynomial = 10;
+
+ pinmap_pinout(digitalPinToPinName(TOUCH_SCK_PIN), PinMap_SPI_SCLK);
+ pinmap_pinout(digitalPinToPinName(TOUCH_MOSI_PIN), PinMap_SPI_MOSI);
+ pinmap_pinout(digitalPinToPinName(TOUCH_MISO_PIN), PinMap_SPI_MISO);
+
+ #ifdef SPI1_BASE
+ if (SPIx.Instance == SPI1) {
+ __HAL_RCC_SPI1_CLK_ENABLE();
+ SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_16;
+ }
+ #endif
+ #ifdef SPI2_BASE
+ if (SPIx.Instance == SPI2) {
+ __HAL_RCC_SPI2_CLK_ENABLE();
+ }
+ #endif
+ #ifdef SPI3_BASE
+ if (SPIx.Instance == SPI3) {
+ __HAL_RCC_SPI3_CLK_ENABLE();
+ }
+ #endif
+ }
+ else {
+ SPIx.Instance = nullptr;
+ SET_INPUT(TOUCH_MISO_PIN);
+ SET_OUTPUT(TOUCH_MOSI_PIN);
+ SET_OUTPUT(TOUCH_SCK_PIN);
+ }
+
+ getRawData(XPT2046_Z1);
+}
+
+bool XPT2046::isTouched() {
+ return isBusy() ? false : (
+ #if PIN_EXISTS(TOUCH_INT)
+ READ(TOUCH_INT_PIN) != HIGH
+ #else
+ getRawData(XPT2046_Z1) >= XPT2046_Z1_THRESHOLD
+ #endif
+ );
+}
+
+bool XPT2046::getRawPoint(int16_t *x, int16_t *y) {
+ if (isBusy()) return false;
+ if (!isTouched()) return false;
+ *x = getRawData(XPT2046_X);
+ *y = getRawData(XPT2046_Y);
+ return isTouched();
+}
+
+uint16_t XPT2046::getRawData(const XPTCoordinate coordinate) {
+ uint16_t data[3];
+
+ DataTransferBegin();
+
+ for (uint16_t i = 0; i < 3 ; i++) {
+ IO(coordinate);
+ data[i] = (IO() << 4) | (IO() >> 4);
+ }
+
+ DataTransferEnd();
+
+ uint16_t delta01 = delta(data[0], data[1]);
+ uint16_t delta02 = delta(data[0], data[2]);
+ uint16_t delta12 = delta(data[1], data[2]);
+
+ if (delta01 > delta02 || delta01 > delta12) {
+ if (delta02 > delta12)
+ data[0] = data[2];
+ else
+ data[1] = data[2];
+ }
+
+ return (data[0] + data[1]) >> 1;
+}
+
+uint16_t XPT2046::HardwareIO(uint16_t data) {
+ __HAL_SPI_ENABLE(&SPIx);
+ while ((SPIx.Instance->SR & SPI_FLAG_TXE) != SPI_FLAG_TXE) {}
+ SPIx.Instance->DR = data;
+ while ((SPIx.Instance->SR & SPI_FLAG_RXNE) != SPI_FLAG_RXNE) {}
+ __HAL_SPI_DISABLE(&SPIx);
+
+ return SPIx.Instance->DR;
+}
+
+uint16_t XPT2046::SoftwareIO(uint16_t data) {
+ uint16_t result = 0;
+
+ for (uint8_t j = 0x80; j > 0; j >>= 1) {
+ WRITE(TOUCH_SCK_PIN, LOW);
+ __DSB();
+ WRITE(TOUCH_MOSI_PIN, data & j ? HIGH : LOW);
+ __DSB();
+ if (READ(TOUCH_MISO_PIN)) result |= j;
+ __DSB();
+ WRITE(TOUCH_SCK_PIN, HIGH);
+ __DSB();
+ }
+ WRITE(TOUCH_SCK_PIN, LOW);
+ __DSB();
+
+ return result;
+}
+
+#endif // HAS_TFT_XPT2046
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.h b/Marlin/src/HAL/STM32/tft/xpt2046.h
new file mode 100644
index 0000000..5b8acf4
--- /dev/null
+++ b/Marlin/src/HAL/STM32/tft/xpt2046.h
@@ -0,0 +1,81 @@
+/**
+ * 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
+
+#ifdef STM32F1xx
+ #include <stm32f1xx_hal.h>
+#elif defined(STM32F4xx)
+ #include <stm32f4xx_hal.h>
+#endif
+
+#include "../../../inc/MarlinConfig.h"
+
+// Not using regular SPI interface by default to avoid SPI mode conflicts with other SPI devices
+
+#if !PIN_EXISTS(TOUCH_MISO)
+ #error "TOUCH_MISO_PIN is not defined."
+#elif !PIN_EXISTS(TOUCH_MOSI)
+ #error "TOUCH_MOSI_PIN is not defined."
+#elif !PIN_EXISTS(TOUCH_SCK)
+ #error "TOUCH_SCK_PIN is not defined."
+#elif !PIN_EXISTS(TOUCH_CS)
+ #error "TOUCH_CS_PIN is not defined."
+#endif
+
+#ifndef TOUCH_INT_PIN
+ #define TOUCH_INT_PIN -1
+#endif
+
+#define XPT2046_DFR_MODE 0x00
+#define XPT2046_SER_MODE 0x04
+#define XPT2046_CONTROL 0x80
+
+enum XPTCoordinate : uint8_t {
+ XPT2046_X = 0x10 | XPT2046_CONTROL | XPT2046_DFR_MODE,
+ XPT2046_Y = 0x50 | XPT2046_CONTROL | XPT2046_DFR_MODE,
+ XPT2046_Z1 = 0x30 | XPT2046_CONTROL | XPT2046_DFR_MODE,
+ XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE,
+};
+
+#if !defined(XPT2046_Z1_THRESHOLD)
+ #define XPT2046_Z1_THRESHOLD 10
+#endif
+
+class XPT2046 {
+private:
+ static SPI_HandleTypeDef SPIx;
+
+ static bool isBusy() { return false; }
+
+ static uint16_t getRawData(const XPTCoordinate coordinate);
+ static bool isTouched();
+
+ static inline void DataTransferBegin() { if (SPIx.Instance) { HAL_SPI_Init(&SPIx); } WRITE(TOUCH_CS_PIN, LOW); };
+ static inline void DataTransferEnd() { WRITE(TOUCH_CS_PIN, HIGH); };
+ static uint16_t HardwareIO(uint16_t data);
+ static uint16_t SoftwareIO(uint16_t data);
+ static uint16_t IO(uint16_t data = 0) { return SPIx.Instance ? HardwareIO(data) : SoftwareIO(data); }
+
+public:
+ static void Init();
+ static bool getRawPoint(int16_t *x, int16_t *y);
+};
diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp
new file mode 100644
index 0000000..e8e18a4
--- /dev/null
+++ b/Marlin/src/HAL/STM32/timers.cpp
@@ -0,0 +1,322 @@
+/**
+ * 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/>.
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../inc/MarlinConfig.h"
+
+// ------------------------
+// Local defines
+// ------------------------
+
+// Default timer priorities. Override by specifying alternate priorities in the board pins file.
+// The TONE timer is not present here, as it currently cannot be set programmatically. It is set
+// by defining TIM_IRQ_PRIO in the variant.h or platformio.ini file, which adjusts the default
+// priority for STM32 HardwareTimer objects.
+#define SWSERIAL_TIMER_IRQ_PRIO_DEFAULT 1 // Requires tight bit timing to communicate reliably with TMC drivers
+#define SERVO_TIMER_IRQ_PRIO_DEFAULT 1 // Requires tight PWM timing to control a BLTouch reliably
+#define STEP_TIMER_IRQ_PRIO_DEFAULT 2
+#define TEMP_TIMER_IRQ_PRIO_DEFAULT 14 // Low priority avoids interference with other hardware and timers
+
+#ifndef STEP_TIMER_IRQ_PRIO
+ #define STEP_TIMER_IRQ_PRIO STEP_TIMER_IRQ_PRIO_DEFAULT
+#endif
+#ifndef TEMP_TIMER_IRQ_PRIO
+ #define TEMP_TIMER_IRQ_PRIO TEMP_TIMER_IRQ_PRIO_DEFAULT
+#endif
+#if HAS_TMC_SW_SERIAL
+ #include <SoftwareSerial.h>
+ #ifndef SWSERIAL_TIMER_IRQ_PRIO
+ #define SWSERIAL_TIMER_IRQ_PRIO SWSERIAL_TIMER_IRQ_PRIO_DEFAULT
+ #endif
+#endif
+#if HAS_SERVOS
+ #include "Servo.h"
+ #ifndef SERVO_TIMER_IRQ_PRIO
+ #define SERVO_TIMER_IRQ_PRIO SERVO_TIMER_IRQ_PRIO_DEFAULT
+ #endif
+#endif
+#if ENABLED(SPEAKER)
+ // Ensure the default timer priority is somewhere between the STEP and TEMP priorities.
+ // The STM32 framework defaults to interrupt 14 for all timers. This should be increased so that
+ // timing-sensitive operations such as speaker output are not impacted by the long-running
+ // temperature ISR. This must be defined in the platformio.ini file or the board's variant.h,
+ // so that it will be consumed by framework code.
+ #if !(TIM_IRQ_PRIO > STEP_TIMER_IRQ_PRIO && TIM_IRQ_PRIO < TEMP_TIMER_IRQ_PRIO)
+ #error "Default timer interrupt priority is unspecified or set to a value which may degrade performance."
+ #endif
+#endif
+
+#ifdef STM32F0xx
+ #define MCU_STEP_TIMER 16
+ #define MCU_TEMP_TIMER 17
+#elif defined(STM32F1xx)
+ #define MCU_STEP_TIMER 4
+ #define MCU_TEMP_TIMER 2
+#elif defined(STM32F401xC) || defined(STM32F401xE)
+ #define MCU_STEP_TIMER 9
+ #define MCU_TEMP_TIMER 10
+#elif defined(STM32F4xx) || defined(STM32F7xx)
+ #define MCU_STEP_TIMER 6 // STM32F401 has no TIM6, TIM7, or TIM8
+ #define MCU_TEMP_TIMER 14 // TIM7 is consumed by Software Serial if used.
+#endif
+
+#ifndef HAL_TIMER_RATE
+ #define HAL_TIMER_RATE GetStepperTimerClkFreq()
+#endif
+
+#ifndef STEP_TIMER
+ #define STEP_TIMER MCU_STEP_TIMER
+#endif
+#ifndef TEMP_TIMER
+ #define TEMP_TIMER MCU_TEMP_TIMER
+#endif
+
+#define __TIMER_DEV(X) TIM##X
+#define _TIMER_DEV(X) __TIMER_DEV(X)
+#define STEP_TIMER_DEV _TIMER_DEV(STEP_TIMER)
+#define TEMP_TIMER_DEV _TIMER_DEV(TEMP_TIMER)
+
+// ------------------------
+// Private Variables
+// ------------------------
+
+HardwareTimer *timer_instance[NUM_HARDWARE_TIMERS] = { nullptr };
+
+// ------------------------
+// Public functions
+// ------------------------
+
+uint32_t GetStepperTimerClkFreq() {
+ // Timer input clocks vary between devices, and in some cases between timers on the same device.
+ // Retrieve at runtime to ensure device compatibility. Cache result to avoid repeated overhead.
+ static uint32_t clkfreq = timer_instance[STEP_TIMER_NUM]->getTimerClkFreq();
+ return clkfreq;
+}
+
+// frequency is in Hertz
+void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
+ if (!HAL_timer_initialized(timer_num)) {
+ switch (timer_num) {
+ case STEP_TIMER_NUM: // STEPPER TIMER - use a 32bit timer if possible
+ timer_instance[timer_num] = new HardwareTimer(STEP_TIMER_DEV);
+ /* Set the prescaler to the final desired value.
+ * This will change the effective ISR callback frequency but when
+ * HAL_timer_start(timer_num=0) is called in the core for the first time
+ * the real frequency isn't important as long as, after boot, the ISR
+ * gets called with the correct prescaler and count register. So here
+ * we set the prescaler to the correct, final value and ignore the frequency
+ * asked. We will call back the ISR in 1 second to start at full speed.
+ *
+ * The proper fix, however, would be a correct initialization OR a
+ * HAL_timer_change(const uint8_t timer_num, const uint32_t frequency)
+ * which changes the prescaler when an IRQ frequency change is needed
+ * (for example when steppers are turned on)
+ */
+
+ timer_instance[timer_num]->setPrescaleFactor(STEPPER_TIMER_PRESCALE); //the -1 is done internally
+ timer_instance[timer_num]->setOverflow(_MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE) /* /frequency */), TICK_FORMAT);
+ break;
+ case TEMP_TIMER_NUM: // TEMP TIMER - any available 16bit timer
+ timer_instance[timer_num] = new HardwareTimer(TEMP_TIMER_DEV);
+ // The prescale factor is computed automatically for HERTZ_FORMAT
+ timer_instance[timer_num]->setOverflow(frequency, HERTZ_FORMAT);
+ break;
+ }
+
+ // Disable preload. Leaving it default-enabled can cause the timer to stop if it happens
+ // to exit the ISR after the start time for the next interrupt has already passed.
+ timer_instance[timer_num]->setPreloadEnable(false);
+
+ HAL_timer_enable_interrupt(timer_num);
+
+ // Start the timer.
+ timer_instance[timer_num]->resume(); // First call to resume() MUST follow the attachInterrupt()
+
+ // This is fixed in Arduino_Core_STM32 1.8.
+ // These calls can be removed and replaced with
+ // timer_instance[timer_num]->setInterruptPriority
+ switch (timer_num) {
+ case STEP_TIMER_NUM:
+ timer_instance[timer_num]->setInterruptPriority(STEP_TIMER_IRQ_PRIO, 0);
+ break;
+ case TEMP_TIMER_NUM:
+ timer_instance[timer_num]->setInterruptPriority(TEMP_TIMER_IRQ_PRIO, 0);
+ break;
+ }
+ }
+}
+
+void HAL_timer_enable_interrupt(const uint8_t timer_num) {
+ if (HAL_timer_initialized(timer_num) && !timer_instance[timer_num]->hasInterrupt()) {
+ switch (timer_num) {
+ case STEP_TIMER_NUM:
+ timer_instance[timer_num]->attachInterrupt(Step_Handler);
+ break;
+ case TEMP_TIMER_NUM:
+ timer_instance[timer_num]->attachInterrupt(Temp_Handler);
+ break;
+ }
+ }
+}
+
+void HAL_timer_disable_interrupt(const uint8_t timer_num) {
+ if (HAL_timer_initialized(timer_num)) timer_instance[timer_num]->detachInterrupt();
+}
+
+bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
+ return HAL_timer_initialized(timer_num) && timer_instance[timer_num]->hasInterrupt();
+}
+
+void SetTimerInterruptPriorities() {
+ TERN_(HAS_TMC_SW_SERIAL, SoftwareSerial::setInterruptPriority(SWSERIAL_TIMER_IRQ_PRIO, 0));
+ TERN_(HAS_SERVOS, libServo::setInterruptPriority(SERVO_TIMER_IRQ_PRIO, 0));
+}
+
+// ------------------------
+// Detect timer conflicts
+// ------------------------
+
+// This list serves two purposes. Firstly, it facilitates build-time mapping between
+// variant-defined timer names (such as TIM1) and timer numbers. It also replicates
+// the order of timers used in the framework's SoftwareSerial.cpp. The first timer in
+// this list will be automatically used by SoftwareSerial if it is not already defined
+// in the board's variant or compiler options.
+static constexpr struct {uintptr_t base_address; int timer_number;} stm32_timer_map[] = {
+ #ifdef TIM18_BASE
+ { uintptr_t(TIM18), 18 },
+ #endif
+ #ifdef TIM7_BASE
+ { uintptr_t(TIM7), 7 },
+ #endif
+ #ifdef TIM6_BASE
+ { uintptr_t(TIM6), 6 },
+ #endif
+ #ifdef TIM22_BASE
+ { uintptr_t(TIM22), 22 },
+ #endif
+ #ifdef TIM21_BASE
+ { uintptr_t(TIM21), 21 },
+ #endif
+ #ifdef TIM17_BASE
+ { uintptr_t(TIM17), 17 },
+ #endif
+ #ifdef TIM16_BASE
+ { uintptr_t(TIM16), 16 },
+ #endif
+ #ifdef TIM15_BASE
+ { uintptr_t(TIM15), 15 },
+ #endif
+ #ifdef TIM14_BASE
+ { uintptr_t(TIM14), 14 },
+ #endif
+ #ifdef TIM13_BASE
+ { uintptr_t(TIM13), 13 },
+ #endif
+ #ifdef TIM11_BASE
+ { uintptr_t(TIM11), 11 },
+ #endif
+ #ifdef TIM10_BASE
+ { uintptr_t(TIM10), 10 },
+ #endif
+ #ifdef TIM12_BASE
+ { uintptr_t(TIM12), 12 },
+ #endif
+ #ifdef TIM19_BASE
+ { uintptr_t(TIM19), 19 },
+ #endif
+ #ifdef TIM9_BASE
+ { uintptr_t(TIM9), 9 },
+ #endif
+ #ifdef TIM5_BASE
+ { uintptr_t(TIM5), 5 },
+ #endif
+ #ifdef TIM4_BASE
+ { uintptr_t(TIM4), 4 },
+ #endif
+ #ifdef TIM3_BASE
+ { uintptr_t(TIM3), 3 },
+ #endif
+ #ifdef TIM2_BASE
+ { uintptr_t(TIM2), 2 },
+ #endif
+ #ifdef TIM20_BASE
+ { uintptr_t(TIM20), 20 },
+ #endif
+ #ifdef TIM8_BASE
+ { uintptr_t(TIM8), 8 },
+ #endif
+ #ifdef TIM1_BASE
+ { uintptr_t(TIM1), 1 }
+ #endif
+};
+
+// Convert from a timer base address to its integer timer number.
+static constexpr int get_timer_num_from_base_address(uintptr_t base_address) {
+ for (const auto &timer : stm32_timer_map)
+ if (timer.base_address == base_address) return timer.timer_number;
+ return 0;
+}
+
+// The platform's SoftwareSerial.cpp will use the first timer from stm32_timer_map.
+#if HAS_TMC_SW_SERIAL && !defined(TIMER_SERIAL)
+ #define TIMER_SERIAL (stm32_timer_map[0].base_address)
+#endif
+
+// constexpr doesn't like using the base address pointers that timers evaluate to.
+// We can get away with casting them to uintptr_t, if we do so inside an array.
+// GCC will not currently do it directly to a uintptr_t.
+IF_ENABLED(HAS_TMC_SW_SERIAL, static constexpr uintptr_t timer_serial[] = {uintptr_t(TIMER_SERIAL)});
+IF_ENABLED(SPEAKER, static constexpr uintptr_t timer_tone[] = {uintptr_t(TIMER_TONE)});
+IF_ENABLED(HAS_SERVOS, static constexpr uintptr_t timer_servo[] = {uintptr_t(TIMER_SERVO)});
+
+enum TimerPurpose { TP_SERIAL, TP_TONE, TP_SERVO, TP_STEP, TP_TEMP };
+
+// List of timers, to enable checking for conflicts.
+// Includes the purpose of each timer to ease debugging when evaluating at build-time.
+// This cannot yet account for timers used for PWM output, such as for fans.
+static constexpr struct { TimerPurpose p; int t; } timers_in_use[] = {
+ #if HAS_TMC_SW_SERIAL
+ {TP_SERIAL, get_timer_num_from_base_address(timer_serial[0])}, // Set in variant.h, or as a define in platformio.h if not present in variant.h
+ #endif
+ #if ENABLED(SPEAKER)
+ {TP_TONE, get_timer_num_from_base_address(timer_tone[0])}, // Set in variant.h, or as a define in platformio.h if not present in variant.h
+ #endif
+ #if HAS_SERVOS
+ {TP_SERVO, get_timer_num_from_base_address(timer_servo[0])}, // Set in variant.h, or as a define in platformio.h if not present in variant.h
+ #endif
+ {TP_STEP, STEP_TIMER},
+ {TP_TEMP, TEMP_TIMER},
+};
+
+static constexpr bool verify_no_timer_conflicts() {
+ LOOP_L_N(i, COUNT(timers_in_use))
+ LOOP_S_L_N(j, i + 1, COUNT(timers_in_use))
+ if (timers_in_use[i].t == timers_in_use[j].t) return false;
+ return true;
+}
+
+// If this assertion fails at compile time, review the timers_in_use array.
+// If default_envs is defined properly in platformio.ini, VS Code can evaluate the array
+// when hovering over it, making it easy to identify the conflicting timers.
+static_assert(verify_no_timer_conflicts(), "One or more timer conflict detected. Examine \"timers_in_use\" to help identify conflict.");
+
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h
new file mode 100644
index 0000000..4649824
--- /dev/null
+++ b/Marlin/src/HAL/STM32/timers.h
@@ -0,0 +1,127 @@
+/**
+ * Marlin 3D Printer Firmware
+ *
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
+ * 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
+
+#include <stdint.h>
+#include "../../inc/MarlinConfig.h"
+
+// ------------------------
+// Defines
+// ------------------------
+
+#define FORCE_INLINE __attribute__((always_inline)) inline
+
+// STM32 timers may be 16 or 32 bit. Limiting HAL_TIMER_TYPE_MAX to 16 bits
+// avoids issues with STM32F0 MCUs, which seem to pause timers if UINT32_MAX
+// is written to the register. STM32F4 timers do not manifest this issue,
+// even when writing to 16 bit timers.
+//
+// The range of the timer can be queried at runtime using IS_TIM_32B_COUNTER_INSTANCE.
+// This is a more expensive check than a simple compile-time constant, so its
+// implementation is deferred until the desire for a 32-bit range outweighs the cost
+// of adding a run-time check and HAL_TIMER_TYPE_MAX is refactored to allow unique
+// values for each timer.
+#define hal_timer_t uint32_t
+#define HAL_TIMER_TYPE_MAX UINT16_MAX
+
+#define NUM_HARDWARE_TIMERS 2
+
+#ifndef STEP_TIMER_NUM
+ #define STEP_TIMER_NUM 0 // Timer Index for Stepper
+#endif
+#ifndef PULSE_TIMER_NUM
+ #define PULSE_TIMER_NUM STEP_TIMER_NUM
+#endif
+#ifndef TEMP_TIMER_NUM
+ #define TEMP_TIMER_NUM 1 // Timer Index for Temperature
+#endif
+
+#define TEMP_TIMER_FREQUENCY 1000 // Temperature::isr() is expected to be called at around 1kHz
+
+// TODO: get rid of manual rate/prescale/ticks/cycles taken for procedures in stepper.cpp
+#define STEPPER_TIMER_RATE 2000000 // 2 Mhz
+extern uint32_t GetStepperTimerClkFreq();
+#define STEPPER_TIMER_PRESCALE (GetStepperTimerClkFreq() / (STEPPER_TIMER_RATE))
+#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
+
+#define PULSE_TIMER_RATE STEPPER_TIMER_RATE
+#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)
+
+extern void Step_Handler();
+extern void Temp_Handler();
+
+#ifndef HAL_STEP_TIMER_ISR
+ #define HAL_STEP_TIMER_ISR() void Step_Handler()
+#endif
+#ifndef HAL_TEMP_TIMER_ISR
+ #define HAL_TEMP_TIMER_ISR() void Temp_Handler()
+#endif
+
+// ------------------------
+// Public Variables
+// ------------------------
+
+extern HardwareTimer *timer_instance[];
+
+// ------------------------
+// Public functions
+// ------------------------
+
+void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
+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);
+
+// Configure timer priorities for peripherals such as Software Serial or Servos.
+// Exposed here to allow all timer priority information to reside in timers.cpp
+void SetTimerInterruptPriorities();
+
+// FORCE_INLINE because these are used in performance-critical situations
+FORCE_INLINE bool HAL_timer_initialized(const uint8_t timer_num) {
+ return timer_instance[timer_num] != nullptr;
+}
+FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
+ return HAL_timer_initialized(timer_num) ? timer_instance[timer_num]->getCount() : 0;
+}
+
+// NOTE: Method name may be misleading.
+// STM32 has an Auto-Reload Register (ARR) as opposed to a "compare" register
+FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t overflow) {
+ if (HAL_timer_initialized(timer_num)) {
+ timer_instance[timer_num]->setOverflow(overflow + 1, TICK_FORMAT); // Value decremented by setOverflow()
+ // wiki: "force all registers (Autoreload, prescaler, compare) to be taken into account"
+ // So, if the new overflow value is less than the count it will trigger a rollover interrupt.
+ if (overflow < timer_instance[timer_num]->getCount()) // Added 'if' here because reports say it won't boot without it
+ timer_instance[timer_num]->refresh();
+ }
+}
+
+#define HAL_timer_isr_prologue(TIMER_NUM)
+#define HAL_timer_isr_epilogue(TIMER_NUM)
diff --git a/Marlin/src/HAL/STM32/usb_host.cpp b/Marlin/src/HAL/STM32/usb_host.cpp
new file mode 100644
index 0000000..ed74336
--- /dev/null
+++ b/Marlin/src/HAL/STM32/usb_host.cpp
@@ -0,0 +1,117 @@
+/**
+ * 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/>.
+ *
+ */
+
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../inc/MarlinConfig.h"
+
+#if BOTH(USE_OTG_USB_HOST, USBHOST)
+
+#include "usb_host.h"
+#include "../shared/Marduino.h"
+#include "usbh_core.h"
+#include "usbh_msc.h"
+
+USBH_HandleTypeDef hUsbHost;
+USBHost usb;
+BulkStorage bulk(&usb);
+
+static void USBH_UserProcess(USBH_HandleTypeDef *phost, uint8_t id) {
+ switch(id) {
+ case HOST_USER_SELECT_CONFIGURATION:
+ //SERIAL_ECHOLNPGM("APPLICATION_SELECT_CONFIGURATION");
+ break;
+ case HOST_USER_DISCONNECTION:
+ //SERIAL_ECHOLNPGM("APPLICATION_DISCONNECT");
+ //usb.setUsbTaskState(USB_STATE_RUNNING);
+ break;
+ case HOST_USER_CLASS_ACTIVE:
+ //SERIAL_ECHOLNPGM("APPLICATION_READY");
+ usb.setUsbTaskState(USB_STATE_RUNNING);
+ break;
+ case HOST_USER_CONNECTION:
+ break;
+ default:
+ break;
+ }
+}
+
+bool USBHost::start() {
+ if (USBH_Init(&hUsbHost, USBH_UserProcess, TERN(USE_USB_HS_IN_FS, HOST_HS, HOST_FS)) != USBH_OK) {
+ SERIAL_ECHOLNPGM("Error: USBH_Init");
+ return false;
+ }
+ if (USBH_RegisterClass(&hUsbHost, USBH_MSC_CLASS) != USBH_OK) {
+ SERIAL_ECHOLNPGM("Error: USBH_RegisterClass");
+ return false;
+ }
+ if (USBH_Start(&hUsbHost) != USBH_OK) {
+ SERIAL_ECHOLNPGM("Error: USBH_Start");
+ return false;
+ }
+ return true;
+}
+
+void USBHost::Task() {
+ USBH_Process(&hUsbHost);
+}
+
+uint8_t USBHost::getUsbTaskState() {
+ return usb_task_state;
+}
+
+void USBHost::setUsbTaskState(uint8_t state) {
+ usb_task_state = state;
+ if (usb_task_state == USB_STATE_RUNNING) {
+ MSC_LUNTypeDef info;
+ USBH_MSC_GetLUNInfo(&hUsbHost, usb.lun, &info);
+ capacity = info.capacity.block_nbr / 2000;
+ block_size = info.capacity.block_size;
+ block_count = info.capacity.block_nbr;
+ // SERIAL_ECHOLNPAIR("info.capacity.block_nbr : %ld\n", info.capacity.block_nbr);
+ // SERIAL_ECHOLNPAIR("info.capacity.block_size: %d\n", info.capacity.block_size);
+ // SERIAL_ECHOLNPAIR("capacity : %d MB\n", capacity);
+ }
+};
+
+bool BulkStorage::LUNIsGood(uint8_t t) {
+ return USBH_MSC_IsReady(&hUsbHost) && USBH_MSC_UnitIsReady(&hUsbHost, t);
+}
+
+uint32_t BulkStorage::GetCapacity(uint8_t lun) {
+ return usb->block_count;
+}
+
+uint16_t BulkStorage::GetSectorSize(uint8_t lun) {
+ return usb->block_size;
+}
+
+uint8_t BulkStorage::Read(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t blocks, uint8_t *buf) {
+ return USBH_MSC_Read(&hUsbHost, lun, addr, buf, blocks) != USBH_OK;
+}
+
+uint8_t BulkStorage::Write(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t blocks, const uint8_t * buf) {
+ return USBH_MSC_Write(&hUsbHost, lun, addr, const_cast <uint8_t*>(buf), blocks) != USBH_OK;
+}
+
+#endif // USE_OTG_USB_HOST && USBHOST
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/usb_host.h b/Marlin/src/HAL/STM32/usb_host.h
new file mode 100644
index 0000000..c0001c0
--- /dev/null
+++ b/Marlin/src/HAL/STM32/usb_host.h
@@ -0,0 +1,60 @@
+/**
+ * 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 <stdint.h>
+
+typedef enum {
+ USB_STATE_INIT,
+ USB_STATE_ERROR,
+ USB_STATE_RUNNING,
+} usb_state_t;
+
+class USBHost {
+public:
+ bool start();
+ void Task();
+ uint8_t getUsbTaskState();
+ void setUsbTaskState(uint8_t state);
+ uint8_t regRd(uint8_t reg) { return 0x0; };
+ uint8_t usb_task_state = USB_STATE_INIT;
+ uint8_t lun = 0;
+ uint32_t capacity = 0;
+ uint16_t block_size = 0;
+ uint32_t block_count = 0;
+};
+
+class BulkStorage {
+public:
+ BulkStorage(USBHost *usb) : usb(usb) {};
+
+ bool LUNIsGood(uint8_t t);
+ uint32_t GetCapacity(uint8_t lun);
+ uint16_t GetSectorSize(uint8_t lun);
+ uint8_t Read(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t blocks, uint8_t *buf);
+ uint8_t Write(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t blocks, const uint8_t * buf);
+
+ USBHost *usb;
+};
+
+extern USBHost usb;
+extern BulkStorage bulk;
diff --git a/Marlin/src/HAL/STM32/usb_serial.cpp b/Marlin/src/HAL/STM32/usb_serial.cpp
new file mode 100644
index 0000000..705d649
--- /dev/null
+++ b/Marlin/src/HAL/STM32/usb_serial.cpp
@@ -0,0 +1,54 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../inc/MarlinConfigPre.h"
+
+#if ENABLED(EMERGENCY_PARSER) && USBD_USE_CDC
+
+#include "usb_serial.h"
+#include "../../feature/e_parser.h"
+
+EmergencyParser::State emergency_state = EmergencyParser::State::EP_RESET;
+
+int8_t (*USBD_CDC_Receive_original) (uint8_t *Buf, uint32_t *Len) = nullptr;
+
+static int8_t USBD_CDC_Receive_hook(uint8_t *Buf, uint32_t *Len) {
+ for (uint32_t i = 0; i < *Len; i++)
+ emergency_parser.update(emergency_state, Buf[i]);
+ return USBD_CDC_Receive_original(Buf, Len);
+}
+
+typedef struct _USBD_CDC_Itf {
+ int8_t (* Init)(void);
+ int8_t (* DeInit)(void);
+ int8_t (* Control)(uint8_t cmd, uint8_t *pbuf, uint16_t length);
+ int8_t (* Receive)(uint8_t *Buf, uint32_t *Len);
+ int8_t (* Transferred)(void);
+} USBD_CDC_ItfTypeDef;
+
+extern USBD_CDC_ItfTypeDef USBD_CDC_fops;
+
+void USB_Hook_init() {
+ USBD_CDC_Receive_original = USBD_CDC_fops.Receive;
+ USBD_CDC_fops.Receive = USBD_CDC_Receive_hook;
+}
+
+#endif // EMERGENCY_PARSER && USBD_USE_CDC
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/usb_serial.h b/Marlin/src/HAL/STM32/usb_serial.h
new file mode 100644
index 0000000..ca61b9e
--- /dev/null
+++ b/Marlin/src/HAL/STM32/usb_serial.h
@@ -0,0 +1,21 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * 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
+
+void USB_Hook_init();
diff --git a/Marlin/src/HAL/STM32/watchdog.cpp b/Marlin/src/HAL/STM32/watchdog.cpp
new file mode 100644
index 0000000..aad0a79
--- /dev/null
+++ b/Marlin/src/HAL/STM32/watchdog.cpp
@@ -0,0 +1,49 @@
+/**
+ * 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/>.
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../inc/MarlinConfigPre.h"
+
+#if ENABLED(USE_WATCHDOG)
+
+#define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout
+
+#include "../../inc/MarlinConfig.h"
+
+#include "watchdog.h"
+#include <IWatchdog.h>
+
+void watchdog_init() {
+ #if DISABLED(DISABLE_WATCHDOG_INIT)
+ IWatchdog.begin(WDT_TIMEOUT_US);
+ #endif
+}
+
+void HAL_watchdog_refresh() {
+ IWatchdog.reload();
+ #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
+ TOGGLE(LED_PIN); // heartbeat indicator
+ #endif
+}
+
+#endif // USE_WATCHDOG
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/watchdog.h b/Marlin/src/HAL/STM32/watchdog.h
new file mode 100644
index 0000000..49a0d9c
--- /dev/null
+++ b/Marlin/src/HAL/STM32/watchdog.h
@@ -0,0 +1,25 @@
+/**
+ * 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
+
+void watchdog_init();
+void HAL_watchdog_refresh();