diff --git a/Marlin/src/HAL/SAMD21/HAL.cpp b/Marlin/src/HAL/SAMD21/HAL.cpp
new file mode 100644
index 00000000..14c439ee
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/HAL.cpp
@@ -0,0 +1,212 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+#ifdef __SAMD21__
+
+#include "../../inc/MarlinConfig.h"
+
+#include
+
+#if USING_HW_SERIALUSB
+ DefaultSerial1 MSerialUSB(false, SerialUSB);
+#endif
+#if USING_HW_SERIAL0
+ DefaultSerial2 MSerial1(false, Serial1);
+#endif
+#if USING_HW_SERIAL1
+ DefaultSerial3 MSerial2(false, Serial2);
+#endif
+
+
+
+#define WDT_CONFIG_PER_7_Val 0x9u
+#define WDT_CONFIG_PER_Pos 0
+#define WDT_CONFIG_PER_7 (WDT_CONFIG_PER_7_Val << WDT_CONFIG_PER_Pos)
+
+#if ENABLED(USE_WATCHDOG)
+
+ #define WDT_TIMEOUT_REG TERN(WATCHDOG_DURATION_8S, WDT_CONFIG_PER_CYC8192, WDT_CONFIG_PER_CYC4096) // 4 or 8 second timeout
+
+ void MarlinHAL::watchdog_init() {
+ // Set up the generic clock (GCLK2) used to clock the watchdog timer at 1.024kHz
+ GCLK->GENDIV.reg = GCLK_GENDIV_DIV(4) | // Divide the 32.768kHz clock source by divisor 32, where 2^(4 + 1): 32.768kHz/32=1.024kHz
+ GCLK_GENDIV_ID(2); // Select Generic Clock (GCLK) 2
+ while (GCLK->STATUS.bit.SYNCBUSY); // Wait for synchronization
+
+ REG_GCLK_GENCTRL = GCLK_GENCTRL_DIVSEL | // Set to divide by 2^(GCLK_GENDIV_DIV(4) + 1)
+ GCLK_GENCTRL_IDC | // Set the duty cycle to 50/50 HIGH/LOW
+ GCLK_GENCTRL_GENEN | // Enable GCLK2
+ GCLK_GENCTRL_SRC_OSCULP32K | // Set the clock source to the ultra low power oscillator (OSCULP32K)
+ GCLK_GENCTRL_ID(2); // Select GCLK2
+ while (GCLK->STATUS.bit.SYNCBUSY); // Wait for synchronization
+
+ // Feed GCLK2 to WDT (Watchdog Timer)
+ REG_GCLK_CLKCTRL = GCLK_CLKCTRL_CLKEN | // Enable GCLK2 to the WDT
+ GCLK_CLKCTRL_GEN_GCLK2 | // Select GCLK2
+ GCLK_CLKCTRL_ID_WDT; // Feed the GCLK2 to the WDT
+ while (GCLK->STATUS.bit.SYNCBUSY); // Wait for synchronization
+
+ WDT->CONFIG.bit.PER = WDT_CONFIG_PER_7; // Set the WDT reset timeout to 4 seconds
+ while (WDT->STATUS.bit.SYNCBUSY); // Wait for synchronization
+ REG_WDT_CTRL = WDT_CTRL_ENABLE; // Enable the WDT in normal mode
+ while (WDT->STATUS.bit.SYNCBUSY); // Wait for synchronization
+ }
+
+ // Reset watchdog. MUST be called at least every 4 seconds after the
+ // first watchdog_init or SAMD will go into emergency procedures.
+ void MarlinHAL::watchdog_refresh() {
+ WDT->CLEAR.reg = WDT_CLEAR_CLEAR_KEY;
+ while (WDT->STATUS.bit.SYNCBUSY);
+ }
+
+#endif
+
+// ------------------------
+// Types
+// ------------------------
+
+// ------------------------
+// Private Variables
+// ------------------------
+
+// ------------------------
+// Private functions
+// ------------------------
+
+void MarlinHAL::dma_init() {}
+
+// ------------------------
+// Public functions
+// ------------------------
+
+// HAL initialization task
+void MarlinHAL::init() {
+ TERN_(DMA_IS_REQUIRED, dma_init());
+ #if ENABLED(SDSUPPORT)
+ #if HAS_SD_DETECT && SD_CONNECTION_IS(ONBOARD)
+ SET_INPUT_PULLUP(SD_DETECT_PIN);
+ #endif
+ OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up
+ #endif
+}
+
+#pragma push_macro("WDT")
+#undef WDT // Required to be able to use '.bit.WDT'. Compiler wrongly replace struct field with WDT define
+uint8_t MarlinHAL::get_reset_source() {
+
+ return 0;
+}
+#pragma pop_macro("WDT")
+
+void MarlinHAL::reboot() { NVIC_SystemReset(); }
+
+extern "C" {
+ void * _sbrk(int incr);
+ extern unsigned int __bss_end__; // end of bss section
+}
+
+// Return free memory between end of heap (or end bss) and whatever is current
+int freeMemory() {
+ int free_memory, heap_end = (int)_sbrk(0);
+ return (int)&free_memory - (heap_end ?: (int)&__bss_end__);
+}
+
+// ------------------------
+// ADC
+// ------------------------
+
+uint16_t MarlinHAL::adc_result;
+
+void MarlinHAL::adc_init() {
+ /* thanks to https://www.eevblog.com/forum/microcontrollers/samd21g18-adc-with-resrdy-interrupts-only-reads-once-or-twice/ */
+
+ ADC->CTRLA.bit.ENABLE = false;
+ while(ADC->STATUS.bit.SYNCBUSY);
+
+ // load chip corrections
+ uint32_t bias = (*((uint32_t *) ADC_FUSES_BIASCAL_ADDR) & ADC_FUSES_BIASCAL_Msk) >> ADC_FUSES_BIASCAL_Pos;
+ uint32_t linearity = (*((uint32_t *) ADC_FUSES_LINEARITY_0_ADDR) & ADC_FUSES_LINEARITY_0_Msk) >> ADC_FUSES_LINEARITY_0_Pos;
+ linearity |= ((*((uint32_t *) ADC_FUSES_LINEARITY_1_ADDR) & ADC_FUSES_LINEARITY_1_Msk) >> ADC_FUSES_LINEARITY_1_Pos) << 5;
+
+ /* Wait for bus synchronization. */
+ while (ADC->STATUS.bit.SYNCBUSY) {};
+
+ ADC->CALIB.reg = ADC_CALIB_BIAS_CAL(bias) | ADC_CALIB_LINEARITY_CAL(linearity);
+
+ /* Wait for bus synchronization. */
+ while (ADC->STATUS.bit.SYNCBUSY) {};
+
+ ADC->CTRLA.bit.SWRST = true;
+ while(ADC->STATUS.bit.SYNCBUSY);
+
+ ADC->REFCTRL.reg = ADC_REFCTRL_REFSEL_INTVCC1;
+ ADC->AVGCTRL.reg = ADC_AVGCTRL_SAMPLENUM_32| ADC_AVGCTRL_ADJRES(4);;
+
+
+ ADC->CTRLB.reg = ADC_CTRLB_PRESCALER_DIV128 |
+ ADC_CTRLB_RESSEL_16BIT |
+ ADC_CTRLB_FREERUN;
+ while(ADC->STATUS.bit.SYNCBUSY);
+
+ ADC->SAMPCTRL.bit.SAMPLEN = 0x00;
+ while(ADC->STATUS.bit.SYNCBUSY);
+
+ ADC->INPUTCTRL.reg = ADC_INPUTCTRL_INPUTSCAN(HAL_ADC_AIN_LEN) // scan (INPUTSCAN + NUM_EXTUDERS - 1) pins
+ | ADC_INPUTCTRL_GAIN_DIV2 |ADC_INPUTCTRL_MUXNEG_GND| HAL_ADC_AIN_START ; /* set to first AIN */
+
+ while(ADC->STATUS.bit.SYNCBUSY);
+
+ ADC->INTENSET.reg |= ADC_INTENSET_RESRDY; // enable Result Ready ADC interrupts
+ while (ADC->STATUS.bit.SYNCBUSY);
+
+ NVIC_EnableIRQ(ADC_IRQn); // enable ADC interrupts
+
+ NVIC_SetPriority(ADC_IRQn, 3);
+
+ ADC->CTRLA.bit.ENABLE = true;
+}
+
+volatile uint32_t adc_results[HAL_ADC_AIN_NUM_SENSORS];
+
+void ADC_Handler() {
+ while(ADC->STATUS.bit.SYNCBUSY == 1);
+ int pos = ADC->INPUTCTRL.bit.INPUTOFFSET;
+
+ adc_results[pos] = ADC->RESULT.reg; /* Read the value. */
+ ADC->INTFLAG.reg = ADC_INTENSET_RESRDY; /* Clear the data ready flag. */
+}
+
+void MarlinHAL::adc_start(const pin_t pin) {
+ /* due to the way INPUTOFFSET works, the last sensor is the first position in the array
+ and we want the ADC_handler interrupt to be as simple possible, so we do the calculation here.
+ */
+ unsigned int pos = PIN_TO_INPUTCTRL(pin) - HAL_ADC_AIN_START + 1;
+ if (pos == HAL_ADC_AIN_NUM_SENSORS) pos = 0;
+ adc_result = adc_results[pos]; // 16-bit resolution
+ //adc_result = 0xFFFF;
+}
+
+#endif // __SAMD21__
diff --git a/Marlin/src/HAL/SAMD21/HAL.h b/Marlin/src/HAL/SAMD21/HAL.h
new file mode 100644
index 00000000..1854e523
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/HAL.h
@@ -0,0 +1,223 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+#pragma once
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+
+#define CPU_32_BIT
+
+#include "../shared/Marduino.h"
+#include "../shared/math_32bit.h"
+#include "../shared/HAL_SPI.h"
+#include "fastio.h"
+
+// ------------------------
+// Serial ports
+// ------------------------
+#include "../../core/serial_hook.h"
+typedef ForwardSerial1Class< decltype(SerialUSB) > DefaultSerial1;
+extern DefaultSerial1 MSerialUSB;
+
+// Serial ports
+typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2;
+typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3;
+
+extern DefaultSerial2 MSerial0;
+extern DefaultSerial3 MSerial1;
+
+
+#define __MSERIAL(X) MSerial##X
+#define _MSERIAL(X) __MSERIAL(X)
+#define MSERIAL(X) _MSERIAL(INCREMENT(X))
+
+#if WITHIN(SERIAL_PORT, 0, 1)
+ #define MYSERIAL1 MSERIAL(SERIAL_PORT)
+#elif SERIAL_PORT == -1
+ #define MYSERIAL1 MSerialUSB
+#else
+ #error "SERIAL_PORT must be -1 (Native USB only)."
+#endif
+
+#ifdef SERIAL_PORT_2
+ #if WITHIN(SERIAL_PORT_2, 0, 1)
+ #define MYSERIAL2 MSERIAL(SERIAL_PORT)
+ #elif SERIAL_PORT_2 == -1
+ #define MYSERIAL2 MSerialUSB
+ #else
+ #error "SERIAL_PORT_2 must be -1 (Native USB only)."
+ #endif
+#endif
+
+#ifdef MMU2_SERIAL_PORT
+ #if WITHIN(MMU2_SERIAL_PORT, 0, 1)
+ #define MMU2_SERIAL MSERIAL(SERIAL_PORT)
+ #elif MMU2_SERIAL_PORT == -1
+ #define MMU2_SERIAL MSerialUSB
+ #else
+ #error "MMU2_SERIAL_PORT must be -1 (Native USB only)."
+ #endif
+#endif
+
+#ifdef LCD_SERIAL_PORT
+ #if WITHIN(LCD_SERIAL_PORT, 0, 1)
+ #define LCD_SERIAL MSERIAL(SERIAL_PORT)
+ #elif LCD_SERIAL_PORT == -1
+ #define LCD_SERIAL MSerialUSB
+ #else
+ #error "LCD_SERIAL_PORT must be -1 (Native USB only)."
+ #endif
+#endif
+
+typedef int8_t pin_t;
+
+#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp
+
+class Servo;
+typedef Servo hal_servo_t;
+
+//
+// Interrupts
+//
+#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq()
+#define CRITICAL_SECTION_END() if (irqon) __enable_irq()
+
+#define cli() __disable_irq() // Disable interrupts
+#define sei() __enable_irq() // Enable interrupts
+
+//
+// ADC
+//
+
+#define HAL_ADC_FILTERED 1 // Disable Marlin's oversampling. The HAL filters ADC values.
+#define HAL_ADC_VREF 3.3
+#define HAL_ADC_RESOLUTION 12
+#define HAL_ADC_AIN_START ADC_INPUTCTRL_MUXPOS_PIN3
+#define HAL_ADC_AIN_NUM_SENSORS 3
+#define HAL_ADC_AIN_LEN HAL_ADC_AIN_NUM_SENSORS-1
+
+//
+// Pin Mapping for M42, M43, M226
+//
+#define GET_PIN_MAP_PIN(index) index
+#define GET_PIN_MAP_INDEX(pin) pin
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
+
+//
+// Tone
+//
+void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0);
+void noTone(const pin_t _pin);
+
+// ------------------------
+// Class Utilities
+// ------------------------
+
+#pragma GCC diagnostic push
+#if GCC_VERSION <= 50000
+ #pragma GCC diagnostic ignored "-Wunused-function"
+#endif
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s);
+
+extern "C" int freeMemory();
+
+#ifdef __cplusplus
+ }
+#endif
+
+#pragma GCC diagnostic pop
+
+// ------------------------
+// MarlinHAL Class
+// ------------------------
+
+class MarlinHAL {
+public:
+
+ // Earliest possible init, before setup()
+ MarlinHAL() {}
+
+ // Watchdog
+ static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {});
+ static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {});
+
+ static void init(); // Called early in setup()
+ static void init_board() {} // Called less early in setup()
+ static void reboot(); // Restart the firmware from 0x0
+
+ // Interrupts
+ static bool isr_state() { return !__get_PRIMASK(); }
+ static void isr_on() { sei(); }
+ static void isr_off() { cli(); }
+
+ static void delay_ms(const int ms) { delay(ms); }
+
+ // Tasks, called from idle()
+ static void idletask() {}
+
+ // Reset
+ static uint8_t get_reset_source();
+ static void clear_reset_source() {}
+
+ // Free SRAM
+ static int freeMemory() { return ::freeMemory(); }
+
+ //
+ // ADC Methods
+ //
+
+ static uint16_t adc_result;
+
+ // Called by Temperature::init once at startup
+ static void adc_init();
+
+ // Called by Temperature::init for each sensor at startup
+ static void adc_enable(const uint8_t ch) {}
+
+ // Begin ADC sampling on the given pin. Called from Temperature::isr!
+ static void adc_start(const pin_t pin);
+
+ // Is the ADC ready for reading?
+ static bool adc_ready() { return true; }
+
+ // The current value of the ADC register
+ static uint16_t adc_value() { return adc_result; }
+
+ /**
+ * Set the PWM duty cycle for the pin to the given value.
+ * No option to invert the duty cycle [default = false]
+ * No option to change the scale of the provided value to enable finer PWM duty control [default = 255]
+ */
+ static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
+ analogWrite(pin, v);
+ }
+
+private:
+ static void dma_init();
+};
diff --git a/Marlin/src/HAL/SAMD21/HAL_SPI.cpp b/Marlin/src/HAL/SAMD21/HAL_SPI.cpp
new file mode 100644
index 00000000..0fc530cd
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/HAL_SPI.cpp
@@ -0,0 +1,148 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+
+/**
+ * Hardware and software SPI implementations are included in this file.
+ *
+ * Control of the slave select pin(s) is handled by the calling routines and
+ * SAMD21 let hardware SPI handling to remove SS from its logic.
+ */
+
+#ifdef __SAMD21__
+
+// --------------------------------------------------------------------------
+// Includes
+// --------------------------------------------------------------------------
+
+#include "../../inc/MarlinConfig.h"
+#include
+
+// --------------------------------------------------------------------------
+// Public functions
+// --------------------------------------------------------------------------
+
+#if EITHER(SOFTWARE_SPI, FORCE_SOFT_SPI)
+
+ // ------------------------
+ // Software SPI
+ // ------------------------
+ #error "Software SPI not supported for SAMD21. Use Hardware SPI."
+
+#else // !SOFTWARE_SPI
+
+ static SPISettings spiConfig;
+
+ // ------------------------
+ // Hardware SPI
+ // ------------------------
+ void spiBegin() {
+ spiInit(SPI_HALF_SPEED);
+ }
+
+ void spiInit(uint8_t spiRate) {
+ // Use datarates Marlin uses
+ uint32_t clock;
+ switch (spiRate) {
+ case SPI_FULL_SPEED: clock = 8000000; break;
+ case SPI_HALF_SPEED: clock = 4000000; break;
+ case SPI_QUARTER_SPEED: clock = 2000000; break;
+ case SPI_EIGHTH_SPEED: clock = 1000000; break;
+ case SPI_SIXTEENTH_SPEED: clock = 500000; break;
+ case SPI_SPEED_5: clock = 250000; break;
+ case SPI_SPEED_6: clock = 125000; break;
+ default: clock = 4000000; break; // Default from the SPI library
+ }
+ spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0);
+ SPI.begin();
+ }
+
+ /**
+ * @brief Receives a single byte from the SPI port.
+ *
+ * @return Byte received
+ *
+ * @details
+ */
+ uint8_t spiRec() {
+ SPI.beginTransaction(spiConfig);
+ uint8_t returnByte = SPI.transfer(0xFF);
+ SPI.endTransaction();
+ return returnByte;
+ }
+
+ /**
+ * @brief Receives 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
+ */
+ void spiRead(uint8_t *buf, uint16_t nbyte) {
+ if (nbyte == 0) return;
+ memset(buf, 0xFF, nbyte);
+
+ SPI.beginTransaction(spiConfig);
+ SPI.transfer(buf, nbyte);
+ SPI.endTransaction();
+
+ }
+
+ /**
+ * @brief Sends a single byte on SPI port
+ *
+ * @param b Byte to send
+ *
+ * @details
+ */
+ void spiSend(uint8_t b) {
+ SPI.beginTransaction(spiConfig);
+ SPI.transfer(b);
+ SPI.endTransaction();
+ }
+
+ /**
+ * @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 Uses DMA
+ */
+ void spiSendBlock(uint8_t token, const uint8_t *buf) {
+ SPI.beginTransaction(spiConfig);
+ SPI.transfer(token);
+ SPI.transfer((uint8_t*)buf, 512);
+ SPI.endTransaction();
+ }
+
+ void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) {
+ spiConfig = SPISettings(spiClock, (BitOrder)bitOrder, dataMode);
+ SPI.beginTransaction(spiConfig);
+ }
+#endif // !SOFTWARE_SPI
+
+#endif // __SAMD21__
diff --git a/Marlin/src/HAL/SAMD21/MarlinSPI.h b/Marlin/src/HAL/SAMD21/MarlinSPI.h
new file mode 100644
index 00000000..7b539279
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/MarlinSPI.h
@@ -0,0 +1,31 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+#pragma once
+
+#include
+
+using MarlinSPI = SPIClass;
diff --git a/Marlin/src/HAL/SAMD21/QSPIFlash.cpp b/Marlin/src/HAL/SAMD21/QSPIFlash.cpp
new file mode 100644
index 00000000..fa54c620
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/QSPIFlash.cpp
@@ -0,0 +1,82 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(QSPI_EEPROM)
+
+#include "QSPIFlash.h"
+
+#define INVALID_ADDR 0xFFFFFFFF
+#define SECTOR_OF(a) (a & ~(SFLASH_SECTOR_SIZE - 1))
+#define OFFSET_OF(a) (a & (SFLASH_SECTOR_SIZE - 1))
+
+Adafruit_SPIFlashBase * QSPIFlash::_flashBase = nullptr;
+uint8_t QSPIFlash::_buf[SFLASH_SECTOR_SIZE];
+uint32_t QSPIFlash::_addr = INVALID_ADDR;
+
+void QSPIFlash::begin() {
+ if (_flashBase) return;
+
+ _flashBase = new Adafruit_SPIFlashBase(new Adafruit_FlashTransport_QSPI());
+ _flashBase->begin(nullptr);
+}
+
+size_t QSPIFlash::size() {
+ return _flashBase->size();
+}
+
+uint8_t QSPIFlash::readByte(const uint32_t address) {
+ if (SECTOR_OF(address) == _addr) return _buf[OFFSET_OF(address)];
+
+ return _flashBase->read8(address);
+}
+
+void QSPIFlash::writeByte(const uint32_t address, const uint8_t value) {
+ uint32_t const sector_addr = SECTOR_OF(address);
+
+ // Page changes, flush old and update new cache
+ if (sector_addr != _addr) {
+ flush();
+ _addr = sector_addr;
+
+ // read a whole page from flash
+ _flashBase->readBuffer(sector_addr, _buf, SFLASH_SECTOR_SIZE);
+ }
+
+ _buf[OFFSET_OF(address)] = value;
+}
+
+void QSPIFlash::flush() {
+ if (_addr == INVALID_ADDR) return;
+
+ _flashBase->eraseSector(_addr / SFLASH_SECTOR_SIZE);
+ _flashBase->writeBuffer(_addr, _buf, SFLASH_SECTOR_SIZE);
+
+ _addr = INVALID_ADDR;
+}
+
+#endif // QSPI_EEPROM
diff --git a/Marlin/src/HAL/SAMD21/QSPIFlash.h b/Marlin/src/HAL/SAMD21/QSPIFlash.h
new file mode 100644
index 00000000..58822fe0
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/QSPIFlash.h
@@ -0,0 +1,49 @@
+/**
+ * @file QSPIFlash.h
+ *
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2019 Ha Thach and Dean Miller for Adafruit Industries LLC
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ *
+ * Derived from Adafruit_SPIFlash class with no SdFat references
+ */
+#pragma once
+
+#include
+
+// This class extends Adafruit_SPIFlashBase by adding caching support.
+//
+// This class will use 4096 Bytes of RAM as a block cache.
+class QSPIFlash {
+ public:
+ static void begin();
+ static size_t size();
+ static uint8_t readByte(const uint32_t address);
+ static void writeByte(const uint32_t address, const uint8_t v);
+ static void flush();
+
+ private:
+ static Adafruit_SPIFlashBase * _flashBase;
+ static uint8_t _buf[SFLASH_SECTOR_SIZE];
+ static uint32_t _addr;
+};
+
+extern QSPIFlash qspi;
diff --git a/Marlin/src/HAL/SAMD21/SAMD21.h b/Marlin/src/HAL/SAMD21/SAMD21.h
new file mode 100644
index 00000000..8e9d17fc
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/SAMD21.h
@@ -0,0 +1,66 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+#pragma once
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+
+#define SYNC(sc) while (sc) { \
+ asm(""); \
+ }
+
+// Get SAMD port/pin from specified arduino pin
+#define GET_SAMD_PORT(P) _GET_SAMD_PORT(PIN_TO_SAMD_PIN(P))
+#define GET_SAMD_PIN(P) _GET_SAMD_PIN(PIN_TO_SAMD_PIN(P))
+
+// Get external interrupt line associated to specified arduino pin
+#define PIN_TO_EILINE(P) _SAMDPORTPIN_TO_EILINE(GET_SAMD_PORT(P), GET_SAMD_PIN(P))
+
+// Get adc/ain associated to specified arduino pin
+#define PIN_TO_ADC(P) (ANAPIN_TO_ADCAIN(P) >> 8)
+
+// Private defines
+#define PIN_TO_SAMD_PIN(P) DIO##P##_PIN
+
+#define _GET_SAMD_PORT(P) ((P) >> 5)
+#define _GET_SAMD_PIN(P) ((P) & 0x1F)
+
+// Get external interrupt line
+#define _SAMDPORTPIN_TO_EILINE(P,B) ((P == 0 && WITHIN(B, 0, 31) && B != 26 && B != 28 && B != 29) ? (B) & 0xF \
+ : (P == 1 && (WITHIN(B, 0, 25) || WITHIN(B, 30, 31))) ? (B) & 0xF \
+ : (P == 1 && WITHIN(B, 26, 29)) ? 12 + (B) - 26 \
+ : (P == 2 && (WITHIN(B, 0, 6) || WITHIN(B, 10, 31)) && B != 29) ? (B) & 0xF \
+ : (P == 2 && B == 7) ? 9 \
+ : (P == 3 && WITHIN(B, 0, 1)) ? (B) \
+ : (P == 3 && WITHIN(B, 8, 12)) ? 3 + (B) - 8 \
+ : (P == 3 && WITHIN(B, 20, 21)) ? 10 + (B) - 20 \
+ : -1)
+
+
+
+#define A2_AIN 3
+#define A3_AIN 4
+#define A4_AIN 5
+#define PIN_TO_AIN(P) A##P##_AIN
+#define AIN_TO_RESULT(P) ( (P - HAL_ADC_AIN_START == HAL_ADC_AIN_NUM_SENSORS-1) ? 0 : (P - HAL_ADC_AIN_START + 1) )
diff --git a/Marlin/src/HAL/SAMD21/Servo.cpp b/Marlin/src/HAL/SAMD21/Servo.cpp
new file mode 100644
index 00000000..38b995fc
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/Servo.cpp
@@ -0,0 +1,220 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+
+/**
+ * This comes from Arduino library which at the moment is buggy and uncompilable
+ */
+
+#ifdef __SAMD21__
+
+#include "../../inc/MarlinConfig.h"
+
+#if HAS_SERVOS
+
+#include "../shared/servo.h"
+#include "../shared/servo_private.h"
+#include "SAMD21.h"
+
+#define __TC_GCLK_ID(t) TC##t##_GCLK_ID
+#define _TC_GCLK_ID(t) __TC_GCLK_ID(t)
+#define TC_GCLK_ID _TC_GCLK_ID(SERVO_TC)
+
+#define _TC_PRESCALER(d) TC_CTRLA_PRESCALER_DIV##d##_Val
+#define TC_PRESCALER(d) _TC_PRESCALER(d)
+
+#define __SERVO_IRQn(t) TC##t##_IRQn
+#define _SERVO_IRQn(t) __SERVO_IRQn(t)
+#define SERVO_IRQn _SERVO_IRQn(SERVO_TC)
+
+#define HAL_SERVO_TIMER_ISR() TC_HANDLER(SERVO_TC)
+
+#define TIMER_TCCHANNEL(t) ((t) & 1)
+#define TC_COUNTER_START_VAL 0xFFFF
+
+
+static volatile int8_t currentServoIndex[_Nbr_16timers]; // index for the servo being pulsed for each timer (or -1 if refresh interval)
+
+FORCE_INLINE static uint16_t getTimerCount() {
+ Tcc * const tc = timer_config[SERVO_TC].pTcc;
+
+ tc->CTRLBSET.reg = TCC_CTRLBCLR_CMD_READSYNC;
+ SYNC(tc->STATUS.reg & TC_STATUS_SYNCBUSY);
+
+ return tc->COUNT.bit.COUNT;
+}
+
+// ----------------------------
+// Interrupt handler for the TC
+// ----------------------------
+HAL_SERVO_TIMER_ISR() {
+ Tcc * const tc = timer_config[SERVO_TC].pTcc;
+ const timer16_Sequence_t timer =
+ #ifndef _useTimer1
+ _timer2
+ #elif !defined(_useTimer2)
+ _timer1
+ #else
+ (tc->INTFLAG.reg & tc->INTENSET.reg & TC_INTFLAG_MC0) ? _timer1 : _timer2
+ #endif
+ ;
+ const uint8_t tcChannel = TIMER_TCCHANNEL(timer);
+
+ int8_t cho = currentServoIndex[timer]; // Handle the prior servo first
+ if (cho < 0) { // Servo -1 indicates the refresh interval completed...
+ #if defined(_useTimer1) && defined(_useTimer2)
+ if (currentServoIndex[timer ^ 1] >= 0) {
+ // Wait for both channels
+ // Clear the interrupt
+ tc->INTFLAG.reg = (tcChannel == 0) ? TC_INTFLAG_MC0 : TC_INTFLAG_MC1;
+ return;
+ }
+ #endif
+ tc->COUNT.reg = TC_COUNTER_START_VAL; // ...so reset the timer
+ SYNC(tc->STATUS.reg & TC_STATUS_SYNCBUSY);
+ }
+ else if (SERVO_INDEX(timer, cho) < ServoCount) // prior channel handled?
+ digitalWrite(SERVO(timer, cho).Pin.nbr, LOW); // pulse the prior channel LOW
+
+ currentServoIndex[timer] = ++cho; // go to the next channel (or 0)
+ if (cho < SERVOS_PER_TIMER && SERVO_INDEX(timer, cho) < ServoCount) {
+ if (SERVO(timer, cho).Pin.isActive) // activated?
+ digitalWrite(SERVO(timer, cho).Pin.nbr, HIGH); // yes: pulse HIGH
+
+ tc->CC[tcChannel].reg = getTimerCount() - (uint16_t)SERVO(timer, cho).ticks;
+ }
+ else {
+ // finished all channels so wait for the refresh period to expire before starting over
+ currentServoIndex[timer] = -1; // reset the timer COUNT.reg on the next call
+ const uint16_t cval = getTimerCount() - 256 / (SERVO_TIMER_PRESCALER), // allow 256 cycles to ensure the next CV not missed
+ ival = (TC_COUNTER_START_VAL) - (uint16_t)usToTicks(REFRESH_INTERVAL); // at least REFRESH_INTERVAL has elapsed
+ tc->CC[tcChannel].reg = min(cval, ival);
+ }
+ if (tcChannel == 0) {
+ SYNC(tc->SYNCBUSY.bit.CC0);
+ tc->INTFLAG.reg = TC_INTFLAG_MC0; // Clear the interrupt
+ }
+ else {
+ SYNC(tc->SYNCBUSY.bit.CC1);
+ tc->INTFLAG.reg = TC_INTFLAG_MC1; // Clear the interrupt
+ }
+}
+
+void initISR(const timer16_Sequence_t timer) {
+ Tcc * const tc = timer_config[SERVO_TC].pTcc;
+ const uint8_t tcChannel = TIMER_TCCHANNEL(timer);
+
+ static bool initialized = false; // Servo TC has been initialized
+ if (!initialized) {
+ NVIC_DisableIRQ(SERVO_IRQn);
+
+ // Disable the timer
+ tc->CTRLA.bit.ENABLE = false;
+ SYNC(tc->STATUS.reg & TC_STATUS_SYNCBUSY);
+
+ // Select GCLK0 as timer/counter input clock source
+ GCLK->CLKCTRL.reg =(GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID(TCC0_GCLK_ID));
+ SYNC (GCLK->STATUS.bit.SYNCBUSY);
+
+ // Reset the timer
+ tc->CTRLA.bit.SWRST = true;
+ SYNC(tc->CTRLA.bit.SWRST);
+
+ // Set timer counter mode to 16 bits
+ tc->CTRLA.reg = TC_CTRLA_MODE_COUNT16;
+
+ // Set timer counter mode as normal PWM
+ tc->WAVE.bit.WAVEGEN = TCC_WAVE_WAVEGEN_NPWM_Val;
+
+ // Set the prescaler factor
+ tc->CTRLA.bit.PRESCALER = TC_PRESCALER(SERVO_TIMER_PRESCALER);
+
+ // Count down
+ tc->CTRLBSET.reg = TCC_CTRLBCLR_DIR;
+ SYNC(tc->SYNCBUSY.bit.CTRLB);
+
+ // Reset all servo indexes
+ memset((void *)currentServoIndex, 0xFF, sizeof(currentServoIndex));
+
+ // Configure interrupt request
+ NVIC_ClearPendingIRQ(SERVO_IRQn);
+ NVIC_SetPriority(SERVO_IRQn, 5);
+ NVIC_EnableIRQ(SERVO_IRQn);
+
+ initialized = true;
+ }
+
+ if (!tc->CTRLA.bit.ENABLE) {
+ // Reset the timer counter
+ tc->COUNT.reg = TC_COUNTER_START_VAL;
+ SYNC(tc->STATUS.reg & TC_STATUS_SYNCBUSY);
+
+ // Enable the timer and start it
+ tc->CTRLA.bit.ENABLE = true;
+ SYNC(tc->STATUS.reg & TC_STATUS_SYNCBUSY);
+ }
+ // First interrupt request after 1 ms
+ tc->CC[tcChannel].reg = getTimerCount() - (uint16_t)usToTicks(1000UL);
+
+ if (tcChannel == 0 ) {
+ SYNC(tc->SYNCBUSY.bit.CC0);
+
+ // Clear pending match interrupt
+ tc->INTFLAG.reg = TC_INTENSET_MC0;
+ // Enable the match channel interrupt request
+ tc->INTENSET.reg = TC_INTENSET_MC0;
+ }
+ else {
+ SYNC(tc->SYNCBUSY.bit.CC1);
+
+ // Clear pending match interrupt
+ tc->INTFLAG.reg = TC_INTENSET_MC1;
+ // Enable the match channel interrupt request
+ tc->INTENSET.reg = TC_INTENSET_MC1;
+ }
+}
+
+void finISR(const timer16_Sequence_t timer_index) {
+ Tcc * const tc = timer_config[SERVO_TC].pTcc;
+ const uint8_t tcChannel = TIMER_TCCHANNEL(timer_index);
+
+ // Disable the match channel interrupt request
+ tc->INTENCLR.reg = (tcChannel == 0) ? TC_INTENCLR_MC0 : TC_INTENCLR_MC1;
+
+ if (true
+ #if defined(_useTimer1) && defined(_useTimer2)
+ && (tc->INTENCLR.reg & (TC_INTENCLR_MC0|TC_INTENCLR_MC1)) == 0
+ #endif
+ ) {
+ // Disable the timer if not used
+ tc->CTRLA.bit.ENABLE = false;
+ SYNC(tc->STATUS.reg & TC_STATUS_SYNCBUSY);
+ }
+}
+
+#endif // HAS_SERVOS
+
+#endif // __SAMD21__
diff --git a/Marlin/src/HAL/SAMD21/ServoTimers.h b/Marlin/src/HAL/SAMD21/ServoTimers.h
new file mode 100644
index 00000000..89805476
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/ServoTimers.h
@@ -0,0 +1,45 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+#pragma once
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+
+#define _useTimer1
+#define _useTimer2
+
+#define TRIM_DURATION 5 // compensation ticks to trim adjust for digitalWrite delays
+#define SERVO_TIMER_PRESCALER 64 // timer prescaler factor to 64 (avoid overflowing 16-bit clock counter, at 120MHz this is 1831 ticks per millisecond
+
+#define SERVO_TC 3
+
+typedef enum {
+ #ifdef _useTimer1
+ _timer1,
+ #endif
+ #ifdef _useTimer2
+ _timer2,
+ #endif
+ _Nbr_16timers
+} timer16_Sequence_t;
diff --git a/Marlin/src/HAL/SAMD21/eeprom_flash.cpp b/Marlin/src/HAL/SAMD21/eeprom_flash.cpp
new file mode 100644
index 00000000..4a4e328d
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/eeprom_flash.cpp
@@ -0,0 +1,141 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+#ifdef __SAMD21__
+
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(FLASH_EEPROM_EMULATION)
+
+#define TOTAL_FLASH_SIZE (MARLIN_EEPROM_SIZE+255)/256*256
+
+/* reserve flash memory */
+static const uint8_t flashdata[TOTAL_FLASH_SIZE] __attribute__((__aligned__(256))) { }; \
+
+#include "../shared/eeprom_api.h"
+
+size_t PersistentStore::capacity() {
+ return MARLIN_EEPROM_SIZE;
+ /* const uint8_t psz = NVMCTRL->SEESTAT.bit.PSZ,
+ sblk = NVMCTRL->SEESTAT.bit.SBLK;
+
+ return (!psz && !sblk) ? 0
+ : (psz <= 2) ? (0x200 << psz)
+ : (sblk == 1 || psz == 3) ? 4096
+ : (sblk == 2 || psz == 4) ? 8192
+ : (sblk <= 4 || psz == 5) ? 16384
+ : (sblk >= 9 && psz == 7) ? 65536
+ : 32768;*/
+}
+
+uint32_t PAGE_SIZE;
+uint32_t ROW_SIZE;
+bool hasWritten = false;
+uint8_t * buffer;
+
+void _erase(const volatile void *flash_ptr) {
+ NVMCTRL->ADDR.reg = ((uint32_t)flash_ptr) / 2;
+ NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_ER;
+ while (!NVMCTRL->INTFLAG.bit.READY) { }
+
+}
+
+void erase(const volatile void *flash_ptr, uint32_t size) {
+ const uint8_t *ptr = (const uint8_t *)flash_ptr;
+ while (size > ROW_SIZE) {
+ _erase(ptr);
+ ptr += ROW_SIZE;
+ size -= ROW_SIZE;
+ }
+ _erase(ptr);
+}
+
+bool PersistentStore::access_start() {
+ /* clear page buffer*/
+ NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_PBC;
+ while (NVMCTRL->INTFLAG.bit.READY == 0) { }
+
+ PAGE_SIZE = pow(2,3 + NVMCTRL->PARAM.bit.PSZ);
+ ROW_SIZE= PAGE_SIZE * 4;
+ /*NVMCTRL->SEECFG.reg = NVMCTRL_SEECFG_WMODE_BUFFERED; // Buffered mode and segment reallocation active
+ if (NVMCTRL->SEESTAT.bit.RLOCK)
+ NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_USEE); */ // Unlock E2P data write access
+ // erase(&flashdata[0], TOTAL_FLASH_SIZE);
+ return true;
+}
+
+bool PersistentStore::access_finish() {
+ if (hasWritten) {
+ erase(&flashdata[0], TOTAL_FLASH_SIZE);
+
+ NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_PBC;
+ while (NVMCTRL->INTFLAG.bit.READY == 0) { }
+
+ NVMCTRL->CTRLB.bit.MANW = 0;
+
+ volatile uint32_t *dst_addr = (volatile uint32_t *) &flashdata;
+
+ uint32_t *pointer = (uint32_t *) buffer;
+ for (uint32_t i = 0; i < TOTAL_FLASH_SIZE; i+=4) {
+
+ *dst_addr = (uint32_t) *pointer;
+ pointer++;
+ dst_addr ++;
+ }
+
+ // Execute "WP" Write Page
+ NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_WP;
+ while (NVMCTRL->INTFLAG.bit.READY == 0) { }
+
+ free(buffer);
+ hasWritten = false;
+ }
+ return true;
+}
+
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ if (!hasWritten) {
+ // init temp buffer
+ buffer = (uint8_t *) malloc(MARLIN_EEPROM_SIZE);
+ hasWritten=true;
+ }
+
+ memcpy(buffer+pos,value,size);
+ pos += size;
+ return false;
+}
+
+bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
+ volatile uint8_t *dst_addr = (volatile uint8_t *) &flashdata;
+ dst_addr += pos;
+
+ memcpy(value,(const void *) dst_addr,size);
+ pos += size;
+ return false;
+}
+
+#endif // FLASH_EEPROM_EMULATION
+#endif // __SAMD21__
diff --git a/Marlin/src/HAL/SAMD21/eeprom_qspi.cpp b/Marlin/src/HAL/SAMD21/eeprom_qspi.cpp
new file mode 100644
index 00000000..587dcb0b
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/eeprom_qspi.cpp
@@ -0,0 +1,79 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+#ifdef __SAMD21__
+
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(QSPI_EEPROM)
+
+#error "QSPI_EEPROM emulation Not implemented on SAMD21"
+
+#include "../shared/eeprom_api.h"
+
+#include "QSPIFlash.h"
+
+static bool initialized;
+
+size_t PersistentStore::capacity() { return qspi.size(); }
+
+bool PersistentStore::access_start() {
+ if (!initialized) {
+ qspi.begin();
+ initialized = true;
+ }
+ return true;
+}
+
+bool PersistentStore::access_finish() {
+ qspi.flush();
+ return true;
+}
+
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ while (size--) {
+ const uint8_t v = *value;
+ qspi.writeByte(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*/) {
+ while (size--) {
+ uint8_t c = qspi.readByte(pos);
+ if (writing) *value = c;
+ crc16(crc, &c, 1);
+ pos++;
+ value++;
+ }
+ return false;
+}
+
+#endif // QSPI_EEPROM
+#endif // __SAMD21__
diff --git a/Marlin/src/HAL/SAMD21/eeprom_wired.cpp b/Marlin/src/HAL/SAMD21/eeprom_wired.cpp
new file mode 100644
index 00000000..ab71e616
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/eeprom_wired.cpp
@@ -0,0 +1,82 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+#ifdef __SAMD21__
+
+#include "../../inc/MarlinConfig.h"
+
+#if USE_WIRED_EEPROM
+
+#error "USE_WIRED_EEPROM emulation Not implemented on SAMD21"
+/**
+ * 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
+ #error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM."
+#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) {
+ uint16_t written = 0;
+ while (size--) {
+ const uint8_t v = *value;
+ uint8_t * const p = (uint8_t * const)pos;
+ if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed!
+ eeprom_write_byte(p, v);
+ if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes
+ 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*/) {
+ while (size--) {
+ uint8_t c = eeprom_read_byte((uint8_t*)pos);
+ if (writing) *value = c;
+ crc16(crc, &c, 1);
+ pos++;
+ value++;
+ }
+ return false;
+}
+
+#endif // USE_WIRED_EEPROM
+#endif // __SAMD21__
diff --git a/Marlin/src/HAL/SAMD21/endstop_interrupts.h b/Marlin/src/HAL/SAMD21/endstop_interrupts.h
new file mode 100644
index 00000000..d8711aa0
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/endstop_interrupts.h
@@ -0,0 +1,253 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+#pragma once
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+
+/**
+ * Endstop interrupts for ATMEL SAMD21 based targets.
+ *
+ * On SAMD21, all pins support external interrupt capability.
+ * Any pin can be used for external interrupts, but there are some restrictions.
+ * At most 16 different external interrupts can be used at one time.
+ * Further, you can’t just pick any 16 pins to use. This is because every pin on the SAMD21
+ * connects to what is called an EXTINT line, and only one pin per EXTINT line can be used for external
+ * interrupts at a time
+ */
+
+/**
+ * Endstop Interrupts
+ *
+ * Without endstop interrupts the endstop pins must be polled continually in
+ * the temperature-ISR via endstops.update(), most of the time finding no change.
+ * With this feature endstops.update() is called only when we know that at
+ * least one endstop has changed state, saving valuable CPU cycles.
+ *
+ * This feature only works when all used endstop pins can generate an 'external interrupt'.
+ *
+ * Test whether pins issue interrupts on your board by flashing 'pin_interrupt_test.ino'.
+ * (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino)
+ */
+
+#include "../../module/endstops.h"
+
+#define MATCH_EILINE(P1,P2) (P1 != P2 && PIN_TO_EILINE(P1) == PIN_TO_EILINE(P2))
+#define MATCH_X_MAX_EILINE(P) TERN0(HAS_X_MAX, DEFER4(MATCH_EILINE)(P, X_MAX_PIN))
+#define MATCH_X_MIN_EILINE(P) TERN0(HAS_X_MIN, DEFER4(MATCH_EILINE)(P, X_MIN_PIN))
+#define MATCH_Y_MAX_EILINE(P) TERN0(HAS_Y_MAX, DEFER4(MATCH_EILINE)(P, Y_MAX_PIN))
+#define MATCH_Y_MIN_EILINE(P) TERN0(HAS_Y_MIN, DEFER4(MATCH_EILINE)(P, Y_MIN_PIN))
+#define MATCH_Z_MAX_EILINE(P) TERN0(HAS_Z_MAX, DEFER4(MATCH_EILINE)(P, Z_MAX_PIN))
+#define MATCH_Z_MIN_EILINE(P) TERN0(HAS_Z_MIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PIN))
+#define MATCH_I_MAX_EILINE(P) TERN0(HAS_I_MAX, DEFER4(MATCH_EILINE)(P, I_MAX_PIN))
+#define MATCH_I_MIN_EILINE(P) TERN0(HAS_I_MIN, DEFER4(MATCH_EILINE)(P, I_MIN_PIN))
+#define MATCH_J_MAX_EILINE(P) TERN0(HAS_J_MAX, DEFER4(MATCH_EILINE)(P, J_MAX_PIN))
+#define MATCH_J_MIN_EILINE(P) TERN0(HAS_J_MIN, DEFER4(MATCH_EILINE)(P, J_MIN_PIN))
+#define MATCH_K_MAX_EILINE(P) TERN0(HAS_K_MAX, DEFER4(MATCH_EILINE)(P, K_MAX_PIN))
+#define MATCH_K_MIN_EILINE(P) TERN0(HAS_K_MIN, DEFER4(MATCH_EILINE)(P, K_MIN_PIN))
+#define MATCH_U_MAX_EILINE(P) TERN0(HAS_U_MAX, DEFER4(MATCH_EILINE)(P, U_MAX_PIN))
+#define MATCH_U_MIN_EILINE(P) TERN0(HAS_U_MIN, DEFER4(MATCH_EILINE)(P, U_MIN_PIN))
+#define MATCH_V_MAX_EILINE(P) TERN0(HAS_V_MAX, DEFER4(MATCH_EILINE)(P, V_MAX_PIN))
+#define MATCH_V_MIN_EILINE(P) TERN0(HAS_V_MIN, DEFER4(MATCH_EILINE)(P, V_MIN_PIN))
+#define MATCH_W_MAX_EILINE(P) TERN0(HAS_W_MAX, DEFER4(MATCH_EILINE)(P, W_MAX_PIN))
+#define MATCH_W_MIN_EILINE(P) TERN0(HAS_W_MIN, DEFER4(MATCH_EILINE)(P, W_MIN_PIN))
+#define MATCH_Z2_MAX_EILINE(P) TERN0(HAS_Z2_MAX, DEFER4(MATCH_EILINE)(P, Z2_MAX_PIN))
+#define MATCH_Z2_MIN_EILINE(P) TERN0(HAS_Z2_MIN, DEFER4(MATCH_EILINE)(P, Z2_MIN_PIN))
+#define MATCH_Z3_MAX_EILINE(P) TERN0(HAS_Z3_MAX, DEFER4(MATCH_EILINE)(P, Z3_MAX_PIN))
+#define MATCH_Z3_MIN_EILINE(P) TERN0(HAS_Z3_MIN, DEFER4(MATCH_EILINE)(P, Z3_MIN_PIN))
+#define MATCH_Z4_MAX_EILINE(P) TERN0(HAS_Z4_MAX, DEFER4(MATCH_EILINE)(P, Z4_MAX_PIN))
+#define MATCH_Z4_MIN_EILINE(P) TERN0(HAS_Z4_MIN, DEFER4(MATCH_EILINE)(P, Z4_MIN_PIN))
+#define MATCH_Z_MIN_PROBE_EILINE(P) TERN0(HAS_Z_MIN_PROBE_PIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PROBE_PIN))
+
+#define AVAILABLE_EILINE(P) ( PIN_TO_EILINE(P) != -1 \
+ && !MATCH_X_MAX_EILINE(P) && !MATCH_X_MIN_EILINE(P) \
+ && !MATCH_Y_MAX_EILINE(P) && !MATCH_Y_MIN_EILINE(P) \
+ && !MATCH_Z_MAX_EILINE(P) && !MATCH_Z_MIN_EILINE(P) \
+ && !MATCH_I_MAX_EILINE(P) && !MATCH_I_MIN_EILINE(P) \
+ && !MATCH_J_MAX_EILINE(P) && !MATCH_J_MIN_EILINE(P) \
+ && !MATCH_K_MAX_EILINE(P) && !MATCH_K_MIN_EILINE(P) \
+ && !MATCH_U_MAX_EILINE(P) && !MATCH_U_MIN_EILINE(P) \
+ && !MATCH_V_MAX_EILINE(P) && !MATCH_V_MIN_EILINE(P) \
+ && !MATCH_W_MAX_EILINE(P) && !MATCH_W_MIN_EILINE(P) \
+ && !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \
+ && !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \
+ && !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P) \
+ && !MATCH_Z_MIN_PROBE_EILINE(P) )
+
+// One ISR for all EXT-Interrupts
+void endstop_ISR() { endstops.update(); }
+
+void setup_endstop_interrupts() {
+ #define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE)
+ #if HAS_X_MAX
+ #if !AVAILABLE_EILINE(X_MAX_PIN)
+ #error "X_MAX_PIN has no EXTINT line available."
+ #endif
+ _ATTACH(X_MAX_PIN);
+ #endif
+ #if HAS_X_MIN
+ #if !AVAILABLE_EILINE(X_MIN_PIN)
+ #error "X_MIN_PIN has no EXTINT line available."
+ #endif
+ _ATTACH(X_MIN_PIN);
+ #endif
+ #if HAS_Y_MAX
+ #if !AVAILABLE_EILINE(Y_MAX_PIN)
+ #error "Y_MAX_PIN has no EXTINT line available."
+ #endif
+ _ATTACH(Y_MAX_PIN);
+ #endif
+ #if HAS_Y_MIN
+ #if !AVAILABLE_EILINE(Y_MIN_PIN)
+ #error "Y_MIN_PIN has no EXTINT line available."
+ #endif
+ _ATTACH(Y_MIN_PIN);
+ #endif
+ #if HAS_Z_MAX
+ #if !AVAILABLE_EILINE(Z_MAX_PIN)
+ #error "Z_MAX_PIN has no EXTINT line available."
+ #endif
+ _ATTACH(Z_MAX_PIN);
+ #endif
+ #if HAS_Z_MIN
+ #if !AVAILABLE_EILINE(Z_MIN_PIN)
+ #error "Z_MIN_PIN has no EXTINT line available."
+ #endif
+ _ATTACH(Z_MIN_PIN);
+ #endif
+ #if HAS_Z2_MAX
+ #if !AVAILABLE_EILINE(Z2_MAX_PIN)
+ #error "Z2_MAX_PIN has no EXTINT line available."
+ #endif
+ _ATTACH(Z2_MAX_PIN);
+ #endif
+ #if HAS_Z2_MIN
+ #if !AVAILABLE_EILINE(Z2_MIN_PIN)
+ #error "Z2_MIN_PIN has no EXTINT line available."
+ #endif
+ _ATTACH(Z2_MIN_PIN);
+ #endif
+ #if HAS_Z3_MAX
+ #if !AVAILABLE_EILINE(Z3_MAX_PIN)
+ #error "Z3_MAX_PIN has no EXTINT line available."
+ #endif
+ _ATTACH(Z3_MAX_PIN);
+ #endif
+ #if HAS_Z3_MIN
+ #if !AVAILABLE_EILINE(Z3_MIN_PIN)
+ #error "Z3_MIN_PIN has no EXTINT line available."
+ #endif
+ _ATTACH(Z3_MIN_PIN);
+ #endif
+ #if HAS_Z4_MAX
+ #if !AVAILABLE_EILINE(Z4_MAX_PIN)
+ #error "Z4_MAX_PIN has no EXTINT line available."
+ #endif
+ _ATTACH(Z4_MAX_PIN);
+ #endif
+ #if HAS_Z4_MIN
+ #if !AVAILABLE_EILINE(Z4_MIN_PIN)
+ #error "Z4_MIN_PIN has no EXTINT line available."
+ #endif
+ _ATTACH(Z4_MIN_PIN);
+ #endif
+ #if HAS_Z_MIN_PROBE_PIN
+ #if !AVAILABLE_EILINE(Z_MIN_PROBE_PIN)
+ #error "Z_MIN_PROBE_PIN has no EXTINT line available."
+ #endif
+ _ATTACH(Z_MIN_PROBE_PIN);
+ #endif
+ #if HAS_I_MAX
+ #if !AVAILABLE_EILINE(I_MAX_PIN)
+ #error "I_MAX_PIN has no EXTINT line available."
+ #endif
+ attachInterrupt(I_MAX_PIN, endstop_ISR, CHANGE);
+ #endif
+ #if HAS_I_MIN
+ #if !AVAILABLE_EILINE(I_MIN_PIN)
+ #error "I_MIN_PIN has no EXTINT line available."
+ #endif
+ attachInterrupt(I_MIN_PIN, endstop_ISR, CHANGE);
+ #endif
+ #if HAS_J_MAX
+ #if !AVAILABLE_EILINE(J_MAX_PIN)
+ #error "J_MAX_PIN has no EXTINT line available."
+ #endif
+ attachInterrupt(J_MAX_PIN, endstop_ISR, CHANGE);
+ #endif
+ #if HAS_J_MIN
+ #if !AVAILABLE_EILINE(J_MIN_PIN)
+ #error "J_MIN_PIN has no EXTINT line available."
+ #endif
+ attachInterrupt(J_MIN_PIN, endstop_ISR, CHANGE);
+ #endif
+ #if HAS_K_MAX
+ #if !AVAILABLE_EILINE(K_MAX_PIN)
+ #error "K_MAX_PIN has no EXTINT line available."
+ #endif
+ attachInterrupt(K_MAX_PIN, endstop_ISR, CHANGE);
+ #endif
+ #if HAS_K_MIN
+ #if !AVAILABLE_EILINE(K_MIN_PIN)
+ #error "K_MIN_PIN has no EXTINT line available."
+ #endif
+ attachInterrupt(K_MIN_PIN, endstop_ISR, CHANGE);
+ #endif
+ #if HAS_U_MAX
+ #if !AVAILABLE_EILINE(U_MAX_PIN)
+ #error "U_MAX_PIN has no EXTINT line available."
+ #endif
+ attachInterrupt(U_MAX_PIN, endstop_ISR, CHANGE);
+ #endif
+ #if HAS_U_MIN
+ #if !AVAILABLE_EILINE(U_MIN_PIN)
+ #error "U_MIN_PIN has no EXTINT line available."
+ #endif
+ attachInterrupt(U_MIN_PIN, endstop_ISR, CHANGE);
+ #endif
+ #if HAS_V_MAX
+ #if !AVAILABLE_EILINE(V_MAX_PIN)
+ #error "V_MAX_PIN has no EXTINT line available."
+ #endif
+ attachInterrupt(V_MAX_PIN, endstop_ISR, CHANGE);
+ #endif
+ #if HAS_V_MIN
+ #if !AVAILABLE_EILINE(V_MIN_PIN)
+ #error "V_MIN_PIN has no EXTINT line available."
+ #endif
+ attachInterrupt(V_MIN_PIN, endstop_ISR, CHANGE);
+ #endif
+ #if HAS_W_MAX
+ #if !AVAILABLE_EILINE(W_MAX_PIN)
+ #error "W_MAX_PIN has no EXTINT line available."
+ #endif
+ attachInterrupt(W_MAX_PIN, endstop_ISR, CHANGE);
+ #endif
+ #if HAS_W_MIN
+ #if !AVAILABLE_EILINE(W_MIN_PIN)
+ #error "W_MIN_PIN has no EXTINT line available."
+ #endif
+ attachInterrupt(W_MIN_PIN, endstop_ISR, CHANGE);
+ #endif
+}
diff --git a/Marlin/src/HAL/SAMD21/fastio.h b/Marlin/src/HAL/SAMD21/fastio.h
new file mode 100644
index 00000000..db64f216
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/fastio.h
@@ -0,0 +1,216 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+#pragma once
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+
+/**
+ * Fast IO functions for SAMD21
+ */
+
+#include "SAMD21.h"
+
+/**
+ * Utility functions
+ */
+
+#ifndef MASK
+ #define MASK(PIN) _BV(PIN)
+#endif
+
+/**
+ * Magic I/O routines
+ *
+ * Now you can simply SET_OUTPUT(IO); WRITE(IO, HIGH); WRITE(IO, LOW);
+ */
+
+// Read a pin
+#define READ(IO) ((PORT->Group[(EPortType)GET_SAMD_PORT(IO)].IN.reg & MASK(GET_SAMD_PIN(IO))) != 0)
+
+// Write to a pin
+#define WRITE(IO,V) do{ \
+ const EPortType port = (EPortType)GET_SAMD_PORT(IO); \
+ const uint32_t mask = MASK(GET_SAMD_PIN(IO)); \
+ \
+ if (V) PORT->Group[port].OUTSET.reg = mask; \
+ else PORT->Group[port].OUTCLR.reg = mask; \
+ }while(0)
+
+// Toggle a pin
+#define TOGGLE(IO) PORT->Group[(EPortType)GET_SAMD_PORT(IO)].OUTTGL.reg = MASK(GET_SAMD_PIN(IO));
+
+// Set pin as input
+#define SET_INPUT(IO) do{ \
+ const EPortType port = (EPortType)GET_SAMD_PORT(IO); \
+ const uint32_t pin = GET_SAMD_PIN(IO); \
+ \
+ PORT->Group[port].PINCFG[pin].reg = (uint8_t)(PORT_PINCFG_INEN); \
+ PORT->Group[port].DIRCLR.reg = MASK(pin); \
+ }while(0)
+// Set pin as input with pullup
+#define SET_INPUT_PULLUP(IO) do{ \
+ const EPortType port = (EPortType)GET_SAMD_PORT(IO); \
+ const uint32_t pin = GET_SAMD_PIN(IO); \
+ const uint32_t mask = MASK(pin); \
+ \
+ PORT->Group[port].PINCFG[pin].reg = (uint8_t)(PORT_PINCFG_INEN | PORT_PINCFG_PULLEN); \
+ PORT->Group[port].DIRCLR.reg = mask; \
+ PORT->Group[port].OUTSET.reg = mask; \
+ }while(0)
+// Set pin as input with pulldown
+#define SET_INPUT_PULLDOWN(IO) do{ \
+ const EPortType port = (EPortType)GET_SAMD_PORT(IO); \
+ const uint32_t pin = GET_SAMD_PIN(IO); \
+ const uint32_t mask = MASK(pin); \
+ \
+ PORT->Group[port].PINCFG[pin].reg = (uint8_t)(PORT_PINCFG_INEN | PORT_PINCFG_PULLEN); \
+ PORT->Group[port].DIRCLR.reg = mask; \
+ PORT->Group[port].OUTCLR.reg = mask; \
+ }while(0)
+// Set pin as output (push pull)
+#define SET_OUTPUT(IO) do{ \
+ const EPortType port = (EPortType)GET_SAMD_PORT(IO); \
+ const uint32_t pin = GET_SAMD_PIN(IO); \
+ \
+ PORT->Group[port].DIRSET.reg = MASK(pin); \
+ PORT->Group[port].PINCFG[pin].reg = 0; \
+ }while(0)
+// Set pin as output (open drain)
+#define SET_OUTPUT_OD(IO) do{ \
+ const EPortType port = (EPortType)GET_SAMD_PORT(IO); \
+ const uint32_t pin = GET_SAMD_PIN(IO); \
+ \
+ PORT->Group[port].PINCFG[pin].reg = (uint8_t)(PORT_PINCFG_PULLEN); \
+ PORT->Group[port].DIRCLR.reg = MASK(pin); \
+ }while(0)
+// Set pin as PWM (push pull)
+#define SET_PWM SET_OUTPUT
+// Set pin as PWM (open drain)
+#define SET_PWM_OD SET_OUTPUT_OD
+
+// check if pin is an output
+#define IS_OUTPUT(IO) ((PORT->Group[(EPortType)GET_SAMD_PORT(IO)].DIR.reg & MASK(GET_SAMD_PIN(IO))) \
+ || (PORT->Group[(EPortType)GET_SAMD_PORT(IO)].PINCFG[GET_SAMD_PIN(IO)].reg & (PORT_PINCFG_INEN | PORT_PINCFG_PULLEN)) == PORT_PINCFG_PULLEN)
+// check if pin is an input
+#define IS_INPUT(IO) !IS_OUTPUT(IO)
+
+// Shorthand
+#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)
+
+// digitalRead/Write wrappers
+#define extDigitalRead(IO) digitalRead(IO)
+#define extDigitalWrite(IO,V) digitalWrite(IO,V)
+
+/**
+ * Ports and functions
+ * Added as necessary or if I feel like it- not a comprehensive list!
+ */
+
+/*
+ * Some of these share the same source and so can't be used in the same time
+ */
+#define PWM_PIN(P) (WITHIN(P, 2, 13) || WITHIN(P, 22, 23) || WITHIN(P, 44, 45) || P == 48)
+
+// Return fulfilled ADCx->INPUTCTRL.reg
+#define PIN_TO_INPUTCTRL(P) ( (P == 0) ? ADC_INPUTCTRL_MUXPOS_PIN0 \
+ : ((P) == 1) ? ADC_INPUTCTRL_MUXPOS_PIN1 \
+ : ((P) == 2) ? ADC_INPUTCTRL_MUXPOS_PIN3 \
+ : ((P) == 3) ? ADC_INPUTCTRL_MUXPOS_PIN4 \
+ : ((P) == 4) ? ADC_INPUTCTRL_MUXPOS_PIN5 \
+ : ((P) == 5) ? ADC_INPUTCTRL_MUXPOS_PIN5 \
+ : ((P) == 6) ? ADC_INPUTCTRL_MUXPOS_PIN6 \
+ : ((P) == 7) ? ADC_INPUTCTRL_MUXPOS_PIN7 \
+ : ((P) == 8) ? ADC_INPUTCTRL_MUXPOS_PIN8 \
+ : ((P) == 9) ? ADC_INPUTCTRL_MUXPOS_PIN9 \
+ : ((P) == 10) ? ADC_INPUTCTRL_MUXPOS_PIN10 \
+ : ((P) == 11) ? ADC_INPUTCTRL_MUXPOS_PIN11 \
+ : ((P) == 12) ? ADC_INPUTCTRL_MUXPOS_PIN12 \
+ : ((P) == 13) ? ADC_INPUTCTRL_MUXPOS_PIN13 \
+ : ((P) == 14) ? ADC_INPUTCTRL_MUXPOS_PIN14 \
+ : ADC_INPUTCTRL_MUXPOS_PIN15)
+
+#define digitalPinToAnalogInput(P) (WITHIN(P, 67, 74) ? (P) - 67 : WITHIN(P, 54, 61) ? 8 + (P) - 54 : WITHIN(P, 12, 13) ? 16 + (P) - 12 : P == 9 ? 18 : -1)
+
+/**
+ * pins
+ */
+
+// PORTA
+#define DIO28_PIN PIN_PA02 // A0
+#define DIO56_PIN PIN_PA03 // A13
+#define DIO31_PIN PIN_PA04 // A13
+#define DIO32_PIN PIN_PA05 // A1
+#define DIO8_PIN PIN_PA06 // A14
+#define DIO9_PIN PIN_PA07 // A15
+#define DIO4_PIN PIN_PA08 // A15
+#define DIO3_PIN PIN_PA09 // A15
+#define DIO1_PIN PIN_PA10
+#define DIO0_PIN PIN_PA11
+#define DIO18_PIN PIN_PA12
+#define DIO52_PIN PIN_PA13
+#define DIO2_PIN PIN_PA14
+#define DIO5_PIN PIN_PA15
+#define DIO11_PIN PIN_PA16
+#define DIO13_PIN PIN_PA17
+#define DIO10_PIN PIN_PA18
+#define DIO12_PIN PIN_PA19
+#define DIO6_PIN PIN_PA20
+#define DIO07_PIN PIN_PA21
+#define DIO34_PIN PIN_PA22
+#define DIO35_PIN PIN_PA23
+#define DIO42_PIN PIN_PA24
+#define DIO43_PIN PIN_PA25
+
+#define DIO40_PIN PIN_PA27
+
+#define DIO26_PIN PIN_PB00
+#define DIO27_PIN PIN_PB01 // A0
+#define DIO33_PIN PIN_PB02
+#define DIO39_PIN PIN_PB03
+#define DIO14_PIN PIN_PB04
+#define DIO15_PIN PIN_PB05
+#define DIO16_PIN PIN_PB06
+#define DIO17_PIN PIN_PB07
+#define DIO29_PIN PIN_PB08
+#define DIO30_PIN PIN_PB09
+#define DIO37_PIN PIN_PB10
+#define DIO38_PIN PIN_PB11
+#define DIO36_PIN PIN_PB12
+#define DIO19_PIN PIN_PB13
+#define DIO20_PIN PIN_PB14
+#define DIO21_PIN PIN_PB15
+#define DIO22_PIN PIN_PB16
+#define DIO23_PIN PIN_PB17
+
+#define DIO44_PIN PIN_PB22
+#define DIO45_PIN PIN_PB23
+#define DIO24_PIN PIN_PB30
+#define DIO25_PIN PIN_PB31
+
+#define DIO53_PIN PIN_PA21
+#define DIO54_PIN PIN_PA06
+#define DIO55_PIN PIN_PA07
+
diff --git a/Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h b/Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h
new file mode 100644
index 00000000..ca467937
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h
@@ -0,0 +1,31 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+#pragma once
+
+#if HAS_SPI_TFT || HAS_FSMC_TFT
+ #error "Sorry! TFT displays are not available for HAL/SAMD21."
+#endif
diff --git a/Marlin/src/HAL/SAMD21/inc/Conditionals_adv.h b/Marlin/src/HAL/SAMD21/inc/Conditionals_adv.h
new file mode 100644
index 00000000..d6a3c4fe
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/inc/Conditionals_adv.h
@@ -0,0 +1,27 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+#pragma once
diff --git a/Marlin/src/HAL/SAMD21/inc/Conditionals_post.h b/Marlin/src/HAL/SAMD21/inc/Conditionals_post.h
new file mode 100644
index 00000000..7315dc12
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/inc/Conditionals_post.h
@@ -0,0 +1,33 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+#pragma once
+
+#if USE_FALLBACK_EEPROM
+ #define FLASH_EEPROM_EMULATION
+#elif EITHER(I2C_EEPROM, SPI_EEPROM)
+ #define USE_SHARED_EEPROM 1
+#endif
diff --git a/Marlin/src/HAL/SAMD21/inc/SanityCheck.h b/Marlin/src/HAL/SAMD21/inc/SanityCheck.h
new file mode 100644
index 00000000..95fa5e59
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/inc/SanityCheck.h
@@ -0,0 +1,50 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+
+/**
+ * Test SAMD21 specific configuration values for errors at compile-time.
+ */
+
+#if SERVO_TC == MF_TIMER_RTC
+ #error "Servos can't use RTC timer"
+#endif
+
+#if ENABLED(EMERGENCY_PARSER)
+ #error "EMERGENCY_PARSER is not yet implemented for SAMD21. Disable EMERGENCY_PARSER to continue."
+#endif
+
+#if ENABLED(SDIO_SUPPORT)
+ #error "SDIO_SUPPORT is not supported on SAMD21."
+#endif
+
+#if ENABLED(FAST_PWM_FAN)
+ #error "Features requiring Hardware PWM (FAST_PWM_FAN) are not yet supported on SAMD21."
+#endif
+
+#if ENABLED(POSTMORTEM_DEBUGGING)
+ #error "POSTMORTEM_DEBUGGING is not yet supported on SAMD21."
+#endif
diff --git a/Marlin/src/HAL/SAMD21/pinsDebug.h b/Marlin/src/HAL/SAMD21/pinsDebug.h
new file mode 100644
index 00000000..f94315cd
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/pinsDebug.h
@@ -0,0 +1,160 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+#pragma once
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+
+#define NUMBER_PINS_TOTAL PINS_COUNT
+
+#define digitalRead_mod(p) extDigitalRead(p)
+#define PRINT_PORT(p) do{ SERIAL_ECHOPGM(" Port: "); sprintf_P(buffer, PSTR("%c%02ld"), 'A' + g_APinDescription[p].ulPort, g_APinDescription[p].ulPin); SERIAL_ECHO(buffer); }while (0)
+#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 PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
+#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
+#define GET_ARRAY_PIN(p) pin_array[p].pin
+#define GET_ARRAY_IS_DIGITAL(p) pin_array[p].is_digital
+#define VALID_PIN(pin) (pin >= 0 && pin < (int8_t)NUMBER_PINS_TOTAL)
+#define DIGITAL_PIN_TO_ANALOG_PIN(p) digitalPinToAnalogInput(p)
+#define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P)!=-1)
+#define pwm_status(pin) digitalPinHasPWM(pin)
+#define MULTI_NAME_PAD 27 // space needed to be pretty if not first name assigned to a pin
+
+// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities
+// uses pin index
+#define M43_NEVER_TOUCH(Q) ((Q) >= 75)
+
+bool GET_PINMODE(int8_t pin) { // 1: output, 0: input
+ const EPortType samdport = g_APinDescription[pin].ulPort;
+ const uint32_t samdpin = g_APinDescription[pin].ulPin;
+ return PORT->Group[samdport].DIR.reg & MASK(samdpin) || (PORT->Group[samdport].PINCFG[samdpin].reg & (PORT_PINCFG_INEN | PORT_PINCFG_PULLEN)) == PORT_PINCFG_PULLEN;
+}
+
+void pwm_details(int32_t pin) {
+ if (pwm_status(pin)) {
+ //uint32_t chan = g_APinDescription[pin].ulPWMChannel TODO when fast pwm is operative;
+ //SERIAL_ECHOPGM("PWM = ", duty);
+ }
+}
+
+/**
+ * SAMD21 Board pin| PORT | Label
+ * ----------------+--------+-------
+ * 0 | PB25 | "RX0"
+ * 1 | PB24 | "TX0"
+ * 2 | PC18 |
+ * 3 | PC19 |
+ * 4 | PC20 |
+ * 5 | PC21 |
+ * 6 | PD20 |
+ * 7 | PD21 |
+ * 8 | PB18 |
+ * 9 | PB2 |
+ * 10 | PB22 |
+ * 11 | PB23 |
+ * 12 | PB0 | "A16"
+ * 13 | PB1 | LED AMBER "L" / "A17"
+ * 14 | PB16 | "TX3"
+ * 15 | PB17 | "RX3"
+ * 16 | PC22 | "TX2"
+ * 17 | PC23 | "RX2"
+ * 18 | PB12 | "TX1" / "A18"
+ * 19 | PB13 | "RX1"
+ * 20 | PB20 | "SDA"
+ * 21 | PB21 | "SCL"
+ * 22 | PD12 |
+ * 23 | PA15 |
+ * 24 | PC17 |
+ * 25 | PC16 |
+ * 26 | PA12 |
+ * 27 | PA13 |
+ * 28 | PA14 |
+ * 29 | PB19 |
+ * 30 | PA23 |
+ * 31 | PA22 |
+ * 32 | PA21 |
+ * 33 | PA20 |
+ * 34 | PA19 |
+ * 35 | PA18 |
+ * 36 | PA17 |
+ * 37 | PA16 |
+ * 38 | PB15 |
+ * 39 | PB14 |
+ * 40 | PC13 |
+ * 41 | PC12 |
+ * 42 | PC15 |
+ * 43 | PC14 |
+ * 44 | PC11 |
+ * 45 | PC10 |
+ * 46 | PC6 |
+ * 47 | PC7 |
+ * 48 | PC4 |
+ * 49 | PC5 |
+ * 50 | PD11 |
+ * 51 | PD8 |
+ * 52 | PD9 |
+ * 53 | PD10 |
+ * 54 | PB5 | "A8"
+ * 55 | PB6 | "A9"
+ * 56 | PB7 | "A10"
+ * 57 | PB8 | "A11"
+ * 58 | PB9 | "A12"
+ * 69 | PA4 | "A13"
+ * 60 | PA6 | "A14"
+ * 61 | PA7 | "A15"
+ * 62 | PB17 |
+ * 63 | PB20 |
+ * 64 | PD11 |
+ * 65 | PD8 |
+ * 66 | PD9 |
+ * 67 | PA2 | "A0" / "DAC0"
+ * 68 | PA5 | "A1" / "DAC1"
+ * 69 | PB3 | "A2"
+ * 70 | PC0 | "A3"
+ * 71 | PC1 | "A4"
+ * 72 | PC2 | "A5"
+ * 73 | PC3 | "A6"
+ * 74 | PB4 | "A7"
+ * 75 | PC31 | LED GREEN "RX"
+ * 76 | PC30 | LED GREEN "TX"
+ * 77 | PA27 | USB: Host enable
+ * 78 | PA24 | USB: D-
+ * 79 | PA25 | USB: D+
+ * 80 | PB29 | SD: MISO
+ * 81 | PB27 | SD: SCK
+ * 82 | PB26 | SD: MOSI
+ * 83 | PB28 | SD: CS
+ * 84 | PA3 | AREF
+ * 85 | PA2 | DAC0 (Duplicate)
+ * 86 | PA5 | DAC1 (Duplicate)
+ * 87 | PB1 | LED AMBER "L" (Duplicate)
+ * 88 | PC24 | NeoPixel
+ * 89 | PB10 | QSPI: SCK
+ * 90 | PB11 | QSPI: CS
+ * 91 | PA8 | QSPI: IO0
+ * 92 | PA9 | QSPI: IO1
+ * 93 | PA10 | QSPI: IO2
+ * 94 | PA11 | QSPI: IO3
+ * 95 | PB31 | SD: DETECT
+ */
diff --git a/Marlin/src/HAL/SAMD21/spi_pins.h b/Marlin/src/HAL/SAMD21/spi_pins.h
new file mode 100644
index 00000000..8c25b84d
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/spi_pins.h
@@ -0,0 +1,54 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+#pragma once
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+
+/**
+ * SAMD21 Default SPI Pins
+ *
+ * SS SCK MISO MOSI
+ * +-------------------------+
+ * SPI | 53 52 50 51 |
+ * SPI1 | 83 81 80 82 |
+ * +-------------------------+
+ * Any pin can be used for Chip Select (SD_SS_PIN)
+ */
+#ifndef SD_SCK_PIN
+ #define SD_SCK_PIN 38
+#endif
+#ifndef SD_MISO_PIN
+ #define SD_MISO_PIN 36
+#endif
+#ifndef SD_MOSI_PIN
+ #define SD_MOSI_PIN 37
+#endif
+#ifndef SDSS
+ #define SDSS 18
+#endif
+
+#ifndef SD_SS_PIN
+ #define SD_SS_PIN SDSS
+#endif
diff --git a/Marlin/src/HAL/SAMD21/timers.cpp b/Marlin/src/HAL/SAMD21/timers.cpp
new file mode 100644
index 00000000..bd26ba07
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/timers.cpp
@@ -0,0 +1,217 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+#ifdef __SAMD21__
+
+// --------------------------------------------------------------------------
+// Includes
+// --------------------------------------------------------------------------
+
+#include "../../inc/MarlinConfig.h"
+#include "ServoTimers.h" // for SERVO_TC
+
+// --------------------------------------------------------------------------
+// Local defines
+// --------------------------------------------------------------------------
+
+#define NUM_HARDWARE_TIMERS 9
+
+// --------------------------------------------------------------------------
+// Private Variables
+// --------------------------------------------------------------------------
+
+const tTimerConfig timer_config[NUM_HARDWARE_TIMERS] = {
+ { {.pTcc=TCC0}, TimerType::tcc, TCC0_IRQn, TC_PRIORITY(0) }, // 0 - stepper (assigned priority 2)
+ { {.pTcc=TCC1}, TimerType::tcc, TCC1_IRQn, TC_PRIORITY(1) }, // 1 - stepper (needed by 32 bit timers)
+ { {.pTcc=TCC2}, TimerType::tcc, TCC2_IRQn, 5 }, // 2 - tone (reserved by framework and fixed assigned priority 5)
+ { {.pTc=TC3}, TimerType::tc, TC3_IRQn, TC_PRIORITY(3) }, // 3 - servo (assigned priority 1)
+ { {.pTc=TC4}, TimerType::tc, TC4_IRQn, TC_PRIORITY(4) }, // 4 - software serial (no interrupts used)
+ { {.pTc=TC5}, TimerType::tc, TC5_IRQn, TC_PRIORITY(5) },
+ { {.pTc=TC6}, TimerType::tc, TC6_IRQn, TC_PRIORITY(6) },
+ { {.pTc=TC7}, TimerType::tc, TC7_IRQn, TC_PRIORITY(7) },
+ { {.pRtc=RTC}, TimerType::rtc, RTC_IRQn, TC_PRIORITY(8) } // 8 - temperature (assigned priority 6)
+};
+
+// --------------------------------------------------------------------------
+// Private functions
+// --------------------------------------------------------------------------
+
+FORCE_INLINE void Disable_Irq(IRQn_Type irq) {
+ NVIC_DisableIRQ(irq);
+
+ // We NEED memory barriers to ensure Interrupts are actually disabled!
+ // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
+ __DSB();
+ __ISB();
+}
+
+static bool tcIsSyncing(Tc * tc) {
+ return tc->COUNT32.STATUS.reg & TC_STATUS_SYNCBUSY;
+}
+
+static void tcReset( Tc * tc) {
+ tc->COUNT32.CTRLA.reg = TC_CTRLA_SWRST;
+ while (tcIsSyncing(tc)) {}
+ while (tc->COUNT32.CTRLA.bit.SWRST) {}
+}
+
+// --------------------------------------------------------------------------
+// Public functions
+// --------------------------------------------------------------------------
+
+void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
+ IRQn_Type irq = timer_config[timer_num].IRQ_Id;
+
+ // Disable interrupt, just in case it was already enabled
+ NVIC_DisableIRQ(irq);
+ NVIC_ClearPendingIRQ(irq);
+
+ if (timer_num == MF_TIMER_RTC) {
+
+ // https://github.com/arduino-libraries/RTCZero
+ Rtc * const rtc = timer_config[timer_num].pRtc;
+ PM->APBAMASK.reg |= PM_APBAMASK_RTC;
+
+ GCLK->CLKCTRL.reg = (uint32_t)((GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK4 | (RTC_GCLK_ID << GCLK_CLKCTRL_ID_Pos)));
+ while (GCLK->STATUS.bit.SYNCBUSY) {}
+
+ GCLK->GENCTRL.reg = (GCLK_GENCTRL_GENEN | GCLK_GENCTRL_SRC_OSCULP32K | GCLK_GENCTRL_ID(4) | GCLK_GENCTRL_DIVSEL );
+ while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY) {}
+
+ GCLK->GENDIV.reg = GCLK_GENDIV_ID(4);
+ GCLK->GENDIV.bit.DIV=4;
+ while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY) {}
+
+ // Disable timer interrupt
+ rtc->MODE0.INTENCLR.reg = RTC_MODE0_INTENCLR_CMP0;
+ SYNC(rtc->MODE0.STATUS.bit.SYNCBUSY);
+
+ while(rtc->MODE0.STATUS.bit.SYNCBUSY) {}
+
+ // Stop timer, just in case, to be able to reconfigure it
+ rtc->MODE0.CTRL.reg =
+ RTC_MODE0_CTRL_MODE_COUNT32 | // Mode 0 = 32-bits counter
+ RTC_MODE0_CTRL_PRESCALER_DIV1024; // Divisor = 1024
+
+ while(rtc->MODE0.STATUS.bit.SYNCBUSY) {}
+
+ // Mode, reset counter on match
+ rtc->MODE0.CTRL.reg = RTC_MODE0_CTRL_MODE_COUNT32 | RTC_MODE0_CTRL_MATCHCLR;
+
+ // Set compare value
+ rtc->MODE0.COMP[0].reg = (32768 + frequency / 2) / frequency;
+ SYNC(rtc->MODE0.STATUS.bit.SYNCBUSY);
+
+ // Enable interrupt on compare
+ rtc->MODE0.INTFLAG.reg = RTC_MODE0_INTFLAG_CMP0; // reset pending interrupt
+ rtc->MODE0.INTENSET.reg = RTC_MODE0_INTENSET_CMP0; // enable compare 0 interrupt
+
+ // And start timer
+ rtc->MODE0.CTRL.bit.ENABLE = true;
+ SYNC(rtc->MODE0.STATUS.bit.SYNCBUSY);
+
+ }
+ else if (timer_config[timer_num].type==TimerType::tcc) {
+
+ Tcc * const tc = timer_config[timer_num].pTcc;
+
+ PM->APBCMASK.reg |= PM_APBCMASK_TCC0;
+ GCLK->CLKCTRL.reg =(GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID(TCC0_GCLK_ID));
+ SYNC (GCLK->STATUS.bit.SYNCBUSY);
+
+ tc->CTRLA.reg = TCC_CTRLA_SWRST;
+ SYNC (tc->SYNCBUSY.reg & TCC_SYNCBUSY_SWRST) {}
+
+ SYNC (tc->CTRLA.bit.SWRST);
+
+ tc->CTRLA.reg &= ~(TCC_CTRLA_ENABLE); // disable TC module
+
+ tc->CTRLA.reg |= TCC_WAVE_WAVEGEN_MFRQ;
+ tc->CTRLA.reg |= TCC_CTRLA_PRESCALER_DIV2;
+ tc->CC[0].reg = (HAL_TIMER_RATE) / frequency;
+ tc->INTENSET.reg = TCC_INTFLAG_MC0;
+ tc->CTRLA.reg |= TCC_CTRLA_ENABLE;
+ tc->INTFLAG.reg = 0xFF;
+ SYNC ( tc->STATUS.reg & TC_STATUS_SYNCBUSY);
+
+ }
+ else {
+ Tc * const tc = timer_config[timer_num].pTc;
+
+ // Disable timer interrupt
+ tc->COUNT32.INTENCLR.reg = TC_INTENCLR_OVF; // disable overflow interrupt
+
+ // TCn clock setup
+ GCLK->CLKCTRL.reg = (uint16_t) (GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID(GCM_TC4_TC5)) ;
+ SYNC (GCLK->STATUS.bit.SYNCBUSY);
+
+ tcReset(tc); // reset TC
+
+ // Set Timer counter 5 Mode to 16 bits, it will become a 16bit counter ('mode1' in the datasheet)
+ tc->COUNT32.CTRLA.reg |= TC_CTRLA_MODE_COUNT32;
+ // Set TC waveform generation mode to 'match frequency'
+ tc->COUNT32.CTRLA.reg |= TC_CTRLA_WAVEGEN_MFRQ;
+ //set prescaler
+ //the clock normally counts at the GCLK_TC frequency, but we can set it to divide that frequency to slow it down
+ //you can use different prescaler divisons here like TC_CTRLA_PRESCALER_DIV1 to get a different range
+ tc->COUNT32.CTRLA.reg |= TC_CTRLA_PRESCALER_DIV1 | TC_CTRLA_ENABLE; //it will divide GCLK_TC frequency by 1024
+ //set the compare-capture register.
+ //The counter will count up to this value (it's a 16bit counter so we use uint16_t)
+ //this is how we fine-tune the frequency, make it count to a lower or higher value
+ //system clock should be 1MHz (8MHz/8) at Reset by default
+ tc->COUNT32.CC[0].reg = (uint16_t) (HAL_TIMER_RATE / frequency);
+ while (tcIsSyncing(tc)) {}
+
+ // Enable the TC interrupt request
+ tc->COUNT32.INTENSET.bit.MC0 = 1;
+ while (tcIsSyncing(tc)) {}
+ }
+
+ NVIC_SetPriority(irq, timer_config[timer_num].priority);
+ NVIC_EnableIRQ(irq);
+}
+
+void HAL_timer_enable_interrupt(const uint8_t timer_num) {
+ const IRQn_Type irq = timer_config[timer_num].IRQ_Id;
+ NVIC_EnableIRQ(irq);
+}
+
+void HAL_timer_disable_interrupt(const uint8_t timer_num) {
+ const IRQn_Type irq = timer_config[timer_num].IRQ_Id;
+ Disable_Irq(irq);
+}
+
+// missing from CMSIS: Check if interrupt is enabled or not
+static bool NVIC_GetEnabledIRQ(IRQn_Type IRQn) {
+ return TEST(NVIC->ISER[uint32_t(IRQn) >> 5], uint32_t(IRQn) & 0x1F);
+}
+
+bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
+ const IRQn_Type irq = timer_config[timer_num].IRQ_Id;
+ return NVIC_GetEnabledIRQ(irq);
+}
+
+#endif // __SAMD21__
diff --git a/Marlin/src/HAL/SAMD21/timers.h b/Marlin/src/HAL/SAMD21/timers.h
new file mode 100644
index 00000000..303ccbdc
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/timers.h
@@ -0,0 +1,160 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+#pragma once
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+
+#include
+
+// --------------------------------------------------------------------------
+// Defines
+// --------------------------------------------------------------------------
+
+typedef uint32_t hal_timer_t;
+#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
+
+#define HAL_TIMER_RATE F_CPU // frequency of timers peripherals
+
+#define MF_TIMER_RTC 8 // This is not a TC but a RTC
+
+#ifndef MF_TIMER_STEP
+ #define MF_TIMER_STEP 4 // Timer Index for Stepper
+#endif
+#ifndef MF_TIMER_PULSE
+ #define MF_TIMER_PULSE MF_TIMER_STEP
+#endif
+#ifndef MF_TIMER_TEMP
+ #define MF_TIMER_TEMP MF_TIMER_RTC // Timer Index for Temperature
+#endif
+
+#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
+
+#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
+#define STEPPER_TIMER_TICKS_PER_US (STEPPER_TIMER_RATE / 1000000) // stepper timer ticks per µs
+#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
+
+#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(MF_TIMER_STEP)
+#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP)
+#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP)
+
+#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
+#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
+
+#define TC_PRIORITY(t) ( t == SERVO_TC ? 1 \
+ : (t == MF_TIMER_STEP || t == MF_TIMER_PULSE) ? 2 \
+ : (t == MF_TIMER_TEMP) ? 6 : 7 )
+
+#define _TC_HANDLER(t) void TC##t##_Handler()
+#define TC_HANDLER(t) _TC_HANDLER(t)
+#ifndef HAL_STEP_TIMER_ISR
+ #define HAL_STEP_TIMER_ISR() TC_HANDLER(MF_TIMER_STEP)
+#endif
+#if MF_TIMER_STEP != MF_TIMER_PULSE
+ #define HAL_PULSE_TIMER_ISR() TC_HANDLER(MF_TIMER_PULSE)
+#endif
+#if MF_TIMER_TEMP == MF_TIMER_RTC
+ #define HAL_TEMP_TIMER_ISR() void RTC_Handler()
+#else
+ #define HAL_TEMP_TIMER_ISR() TC_HANDLER(MF_TIMER_TEMP)
+#endif
+
+// --------------------------------------------------------------------------
+// Types
+// --------------------------------------------------------------------------
+typedef enum { tcc, tc, rtc } TimerType;
+
+typedef struct {
+ union {
+ Tc *pTc;
+ Tcc *pTcc;
+ Rtc *pRtc;
+ };
+ TimerType type;
+ IRQn_Type IRQ_Id;
+ uint8_t priority;
+} tTimerConfig;
+
+// --------------------------------------------------------------------------
+// Public Variables
+// --------------------------------------------------------------------------
+
+extern const tTimerConfig timer_config[];
+
+// --------------------------------------------------------------------------
+// Public functions
+// --------------------------------------------------------------------------
+
+void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
+
+FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
+ // Should never be called with timer MF_TIMER_RTC
+ Tc * const tc = timer_config[timer_num].pTc;
+ tc->COUNT32.CC[0].reg = compare;
+}
+
+FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
+ // Should never be called with timer MF_TIMER_RTC
+ Tc * const tc = timer_config[timer_num].pTc;
+ return (hal_timer_t)tc->COUNT32.CC[0].reg;
+}
+
+FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
+ // Should never be called with timer MF_TIMER_RTC
+ Tc * const tc = timer_config[timer_num].pTc;
+ tc->COUNT32.READREQ.reg = TC_READREQ_RREQ;
+ // Request a read synchronization
+ SYNC (tc->COUNT32.STATUS.bit.SYNCBUSY);
+ //SYNC(tc->COUNT32.STATUS.bit.SYNCBUSY );
+ return tc->COUNT32.COUNT.reg;
+}
+
+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);
+
+FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
+ if (timer_num == MF_TIMER_RTC) {
+ Rtc * const rtc = timer_config[timer_num].pRtc;
+ // Clear interrupt flag
+ rtc->MODE0.INTFLAG.reg = RTC_MODE0_INTFLAG_CMP0| RTC_MODE0_INTFLAG_OVF;
+
+ }
+ else if (timer_config[timer_num].type == TimerType::tcc){
+ Tcc * const tc = timer_config[timer_num].pTcc;
+ // Clear interrupt flag
+ tc->INTFLAG.reg = TCC_INTFLAG_OVF;
+ }
+ else {
+ Tc * const tc = timer_config[timer_num].pTc;
+ // Clear interrupt flag
+ tc->COUNT32.INTFLAG.bit.MC0 = 1;
+ }
+}
+
+#define HAL_timer_isr_epilogue(timer_num)
diff --git a/Marlin/src/HAL/SAMD21/u8g/LCD_I2C_routines.cpp b/Marlin/src/HAL/SAMD21/u8g/LCD_I2C_routines.cpp
new file mode 100644
index 00000000..41da7c10
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/u8g/LCD_I2C_routines.cpp
@@ -0,0 +1,32 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+// adapted from I2C/master/master.c example
+// https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
+
+#ifdef __SAMD21__
+
+#endif // __SAMD21__
diff --git a/Marlin/src/HAL/SAMD21/u8g/LCD_I2C_routines.h b/Marlin/src/HAL/SAMD21/u8g/LCD_I2C_routines.h
new file mode 100644
index 00000000..d6a3c4fe
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/u8g/LCD_I2C_routines.h
@@ -0,0 +1,27 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+#pragma once
diff --git a/Marlin/src/HAL/SAMD21/u8g/LCD_defines.h b/Marlin/src/HAL/SAMD21/u8g/LCD_defines.h
new file mode 100644
index 00000000..fa98725d
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/u8g/LCD_defines.h
@@ -0,0 +1,41 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+#pragma once
+
+/**
+ * SAMD21 LCD-specific defines
+ */
+
+// The following are optional depending on the platform.
+
+// definitions of HAL specific com and device drivers.
+uint8_t u8g_com_samd21_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr);
+uint8_t u8g_com_samd21_st7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr);
+
+// connect U8g com generic com names to the desired driver
+#define U8G_COM_HW_SPI u8g_com_samd21_st7920_hw_spi_fn // use SAMD21 specific hardware SPI routine
+#define U8G_COM_ST7920_HW_SPI u8g_com_samd21_st7920_hw_spi_fn
diff --git a/Marlin/src/HAL/SAMD21/u8g/LCD_pin_routines.c b/Marlin/src/HAL/SAMD21/u8g/LCD_pin_routines.c
new file mode 100644
index 00000000..f9f77825
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/u8g/LCD_pin_routines.c
@@ -0,0 +1,42 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+
+/**
+ * Low level pin manipulation routines - used by all the drivers.
+ *
+ * These are based on the SAMD51 pinMode, digitalRead & digitalWrite routines.
+ *
+ * Couldn't just call exact copies because the overhead killed the LCD update speed
+ * With an intermediate level the softspi was running in the 10-20kHz range which
+ * resulted in using about about 25% of the CPU's time.
+ */
+
+#ifdef __SAMD21__
+
+#include
+
+#endif // __SAMD21__
diff --git a/Marlin/src/HAL/SAMD21/u8g/LCD_pin_routines.h b/Marlin/src/HAL/SAMD21/u8g/LCD_pin_routines.h
new file mode 100644
index 00000000..92626552
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/u8g/LCD_pin_routines.h
@@ -0,0 +1,42 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+#pragma once
+
+/**
+ * Low level pin manipulation routines - used by all the drivers.
+ *
+ * These are based on the SAMD51 pinMode, digitalRead & digitalWrite routines.
+ *
+ * Couldn't just call exact copies because the overhead killed the LCD update speed
+ * With an intermediate level the softspi was running in the 10-20kHz range which
+ * resulted in using about about 25% of the CPU's time.
+ */
+
+void u8g_SetPinOutput(uint8_t internal_pin_number);
+void u8g_SetPinInput(uint8_t internal_pin_number);
+void u8g_SetPinLevel(uint8_t pin, uint8_t pin_status);
+uint8_t u8g_GetPinLevel(uint8_t pin);
diff --git a/Marlin/src/HAL/SAMD21/u8g/u8g_com_HAL_samd21_shared_hw_spi.cpp b/Marlin/src/HAL/SAMD21/u8g/u8g_com_HAL_samd21_shared_hw_spi.cpp
new file mode 100644
index 00000000..02dc7722
--- /dev/null
+++ b/Marlin/src/HAL/SAMD21/u8g/u8g_com_HAL_samd21_shared_hw_spi.cpp
@@ -0,0 +1,154 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+/**
+ * SAMD21 HAL developed by Bart Meijer (brupje)
+ * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ */
+
+/**
+ * Based on u8g_com_msp430_hw_spi.c
+ *
+ * Universal 8bit Graphics Library
+ *
+ * Copyright (c) 2012, olikraus@gmail.com
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ *
+ * * Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * * Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or other
+ * materials provided with the distribution.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
+ * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
+ * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
+ * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
+ * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
+ * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifdef __SAMD21__
+
+#include
+#include "SPI.h"
+
+#include "../../shared/HAL_SPI.h"
+
+#ifndef LCD_SPI_SPEED
+ #define LCD_SPI_SPEED SPI_QUARTER_SPEED
+#endif
+
+void u8g_SetPIOutput(u8g_t *u8g, uint8_t pin_index) {
+ if (u8g->pin_list[pin_index]!= U8G_PIN_NONE)
+ pinMode(u8g->pin_list[pin_index],OUTPUT);
+}
+
+void u8g_SetPILevel(u8g_t *u8g, uint8_t pin_index, uint8_t level) {
+ if (u8g->pin_list[pin_index]!= U8G_PIN_NONE)
+ digitalWrite(u8g->pin_list[pin_index],level);
+}
+
+uint8_t u8g_com_samd21_st7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {
+
+ static SPISettings lcdSPIConfig;
+
+ switch (msg) {
+ case U8G_COM_MSG_STOP:
+ break;
+
+ case U8G_COM_MSG_INIT:
+ u8g_SetPIOutput(u8g, U8G_PI_CS);
+ u8g_SetPIOutput(u8g, U8G_PI_A0);
+ u8g_SetPIOutput(u8g, U8G_PI_RESET);
+
+ u8g_SetPILevel(u8g, U8G_PI_CS, LOW);
+
+ spiBegin();
+ lcdSPIConfig = SPISettings(900000, MSBFIRST, SPI_MODE0);
+ u8g->pin_list[U8G_PI_A0_STATE] = 0;
+ break;
+
+ case U8G_COM_MSG_ADDRESS: // define cmd (arg_val = 0) or data mode (arg_val = 1)
+ u8g_SetPILevel(u8g, U8G_PI_A0, arg_val);
+ u8g->pin_list[U8G_PI_A0_STATE] = arg_val;
+ break;
+
+ case U8G_COM_MSG_CHIP_SELECT: // arg_val == 1 means chip selected, but ST7920 is active high, so needs inverting
+ u8g_SetPILevel(u8g, U8G_PI_CS, arg_val ? HIGH : LOW);
+ break;
+
+ case U8G_COM_MSG_RESET:
+ u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val);
+ break;
+
+ case U8G_COM_MSG_WRITE_BYTE:
+ SPI.beginTransaction(lcdSPIConfig);
+
+ if (u8g->pin_list[U8G_PI_A0_STATE] == 0) { // command
+ SPI.transfer(0x0f8); u8g->pin_list[U8G_PI_A0_STATE] = 2;
+ }
+ else if (u8g->pin_list[U8G_PI_A0_STATE] == 1) { // data
+ SPI.transfer(0x0fa); u8g->pin_list[U8G_PI_A0_STATE] = 2;
+ }
+
+ SPI.transfer(arg_val & 0x0f0);
+ SPI.transfer(arg_val << 4);
+ SPI.endTransaction();
+ break;
+
+ case U8G_COM_MSG_WRITE_SEQ:
+ SPI.beginTransaction(lcdSPIConfig);
+
+ if (u8g->pin_list[U8G_PI_A0_STATE] == 0 ) { // command
+ SPI.transfer(0x0f8); u8g->pin_list[U8G_PI_A0_STATE] = 2;
+ }
+ else if (u8g->pin_list[U8G_PI_A0_STATE] == 1) { // data
+ SPI.transfer(0x0fa); u8g->pin_list[U8G_PI_A0_STATE] = 2;
+ }
+
+ uint8_t *ptr = (uint8_t*)arg_ptr;
+ while (arg_val > 0) {
+ SPI.transfer((*ptr) & 0x0f0);
+ SPI.transfer((*ptr) << 4);
+ ptr++;
+ arg_val--;
+ }
+
+ SPI.endTransaction();
+ break;
+ }
+ return 1;
+}
+
+#endif // __SAMD21__
diff --git a/Marlin/src/gcode/feature/input_shaping/M593.cpp b/Marlin/src/gcode/feature/input_shaping/M593.cpp
new file mode 100644
index 00000000..aafabb3c
--- /dev/null
+++ b/Marlin/src/gcode/feature/input_shaping/M593.cpp
@@ -0,0 +1,85 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+
+#include "../../../inc/MarlinConfig.h"
+
+#if HAS_SHAPING
+
+#include "../../gcode.h"
+#include "../../../module/stepper.h"
+
+void GcodeSuite::M593_report(const bool forReplay/*=true*/) {
+ report_heading_etc(forReplay, F("Input Shaping"));
+ #if ENABLED(INPUT_SHAPING_X)
+ SERIAL_ECHOLNPGM(" M593 X"
+ " F", stepper.get_shaping_frequency(X_AXIS),
+ " D", stepper.get_shaping_damping_ratio(X_AXIS)
+ );
+ #endif
+ #if ENABLED(INPUT_SHAPING_Y)
+ TERN_(INPUT_SHAPING_X, report_echo_start(forReplay));
+ SERIAL_ECHOLNPGM(" M593 Y"
+ " F", stepper.get_shaping_frequency(Y_AXIS),
+ " D", stepper.get_shaping_damping_ratio(Y_AXIS)
+ );
+ #endif
+}
+
+/**
+ * M593: Get or Set Input Shaping Parameters
+ * D Set the zeta/damping factor. If axes (X, Y, etc.) are not specified, set for all axes.
+ * F Set the frequency. If axes (X, Y, etc.) are not specified, set for all axes.
+ * T[map] Input Shaping type, 0:ZV, 1:EI, 2:2H EI (not implemented yet)
+ * X<1> Set the given parameters only for the X axis.
+ * Y<1> Set the given parameters only for the Y axis.
+ */
+void GcodeSuite::M593() {
+ if (!parser.seen_any()) return M593_report();
+
+ const bool seen_X = TERN0(INPUT_SHAPING_X, parser.seen_test('X')),
+ seen_Y = TERN0(INPUT_SHAPING_Y, parser.seen_test('Y')),
+ for_X = seen_X || TERN0(INPUT_SHAPING_X, (!seen_X && !seen_Y)),
+ for_Y = seen_Y || TERN0(INPUT_SHAPING_Y, (!seen_X && !seen_Y));
+
+ if (parser.seen('D')) {
+ const float zeta = parser.value_float();
+ if (WITHIN(zeta, 0, 1)) {
+ if (for_X) stepper.set_shaping_damping_ratio(X_AXIS, zeta);
+ if (for_Y) stepper.set_shaping_damping_ratio(Y_AXIS, zeta);
+ }
+ else
+ SERIAL_ECHO_MSG("?Zeta (D) value out of range (0-1)");
+ }
+
+ if (parser.seen('F')) {
+ const float freq = parser.value_float();
+ constexpr float min_freq = float(uint32_t(STEPPER_TIMER_RATE) / 2) / shaping_time_t(-2);
+ if (freq == 0.0f || freq > min_freq) {
+ if (for_X) stepper.set_shaping_frequency(X_AXIS, freq);
+ if (for_Y) stepper.set_shaping_frequency(Y_AXIS, freq);
+ }
+ else
+ SERIAL_ECHOLNPGM("?Frequency (F) must be greater than ", min_freq, " or 0 to disable");
+ }
+}
+
+#endif
diff --git a/Marlin/src/module/thermistor/thermistor_1022.h b/Marlin/src/module/thermistor/thermistor_1022.h
new file mode 100644
index 00000000..1db928fb
--- /dev/null
+++ b/Marlin/src/module/thermistor/thermistor_1022.h
@@ -0,0 +1,45 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+#pragma once
+
+#define REVERSE_TEMP_SENSOR_RANGE_1022 1
+
+// Pt1000 with 1k0 pullup
+constexpr temp_entry_t temptable_1022[] PROGMEM = {
+ PtLine( 0, 1000, 2200),
+ PtLine( 25, 1000, 2200),
+ PtLine( 50, 1000, 2200),
+ PtLine( 75, 1000, 2200),
+ PtLine(100, 1000, 2200),
+ PtLine(125, 1000, 2200),
+ PtLine(150, 1000, 2200),
+ PtLine(175, 1000, 2200),
+ PtLine(200, 1000, 2200),
+ PtLine(225, 1000, 2200),
+ PtLine(250, 1000, 2200),
+ PtLine(275, 1000, 2200),
+ PtLine(300, 1000, 2200),
+ PtLine(350, 1000, 2200),
+ PtLine(400, 1000, 2200),
+ PtLine(450, 1000, 2200),
+ PtLine(500, 1000, 2200)
+};
diff --git a/Marlin/src/pins/ramps/pins_TENLOG_MB1_V23.h b/Marlin/src/pins/ramps/pins_TENLOG_MB1_V23.h
new file mode 100644
index 00000000..b3f7d5f2
--- /dev/null
+++ b/Marlin/src/pins/ramps/pins_TENLOG_MB1_V23.h
@@ -0,0 +1,155 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+#pragma once
+
+/**
+ * Tenlog pin assignments
+ */
+
+#define REQUIRE_MEGA2560
+#include "env_validate.h"
+
+#if HOTENDS > 2 || E_STEPPERS > 2
+ #error "Tenlog supports up to 2 hotends / E steppers."
+#endif
+
+#define BOARD_INFO_NAME "Tenlog MB1 V2.3"
+#define DEFAULT_MACHINE_NAME BOARD_INFO_NAME
+
+//
+// Limit Switches
+//
+#define X_MIN_PIN 3
+#define X_MAX_PIN 2
+#define Y_MIN_PIN 14
+//#define Y_MAX_PIN 15 // Connected to "DJ" plug on extruder heads
+#define Z_MIN_PIN 18
+#if ENABLED(BLTOUCH)
+ #define SERVO0_PIN 19
+#else
+ #define Z_MAX_PIN 19
+#endif
+
+//
+// Steppers
+//
+#define X_STEP_PIN 54
+#define X_DIR_PIN 55
+#define X_ENABLE_PIN 38
+
+#define X2_STEP_PIN 36
+#define X2_DIR_PIN 34
+#define X2_ENABLE_PIN 30
+
+#define Y_STEP_PIN 60
+#define Y_DIR_PIN 61
+#define Y_ENABLE_PIN 56
+
+#define Z_STEP_PIN 46
+#define Z_DIR_PIN 48
+#define Z_ENABLE_PIN 62
+
+#define Z2_STEP_PIN 65
+#define Z2_DIR_PIN 66
+#define Z2_ENABLE_PIN 64
+
+#define E0_STEP_PIN 57
+#define E0_DIR_PIN 58
+#define E0_ENABLE_PIN 59
+
+#define E1_STEP_PIN 26
+#define E1_DIR_PIN 28
+#define E1_ENABLE_PIN 24
+
+//
+// Temperature Sensors
+//
+#define TEMP_0_PIN 15 // Analog Input
+#define TEMP_1_PIN 13 // Analog Input
+#define TEMP_BED_PIN 14 // Analog Input
+
+//
+// Heaters / Fans
+//
+#define HEATER_0_PIN 11
+#define HEATER_1_PIN 10
+#define HEATER_BED_PIN 8
+
+#define FAN_PIN 9
+#define FAN2_PIN 5 // Normally this would be a servo pin
+
+//#define NUM_RUNOUT_SENSORS 0
+#define FIL_RUNOUT_PIN 15
+//#define FIL_RUNOUT2_PIN 21
+
+//
+// PSU and Powerloss Recovery
+//
+#if ENABLED(PSU_CONTROL)
+ #define PS_ON_PIN 40 // The M80/M81 PSU pin for boards v2.1-2.3
+#endif
+
+//
+// Misc. Functions
+//
+//#define CASE_LIGHT_PIN 5
+//#ifndef LED_PIN
+// #define LED_PIN 13
+//#endif
+
+#if HAS_CUTTER
+ //#define SPINDLE_LASER_PWM_PIN -1 // Hardware PWM
+ //#define SPINDLE_LASER_ENA_PIN 4 // Pullup!
+#endif
+
+// Use the RAMPS 1.4 Analog input 5 on the AUX2 connector
+//#define FILWIDTH_PIN 5 // Analog Input
+
+#define SDSS 53
+#define SD_DETECT_PIN 49
+
+//
+// LCD / Controller
+//
+
+//#if IS_RRD_SC
+
+//#ifndef BEEPER_PIN
+// #define BEEPER_PIN -1
+//#endif
+
+#define LCD_PINS_RS -1
+#define LCD_PINS_ENABLE -1
+#define LCD_PINS_D4 -1
+#define LCD_PINS_D5 -1
+#define LCD_PINS_D6 -1
+#define LCD_PINS_D7 -1
+
+//#define BTN_EN1 31
+//#define BTN_EN2 33
+//#define BTN_ENC 35
+
+//#ifndef KILL_PIN
+// #define KILL_PIN 41
+//#endif
+
+//#endif // IS_RRD_SC
diff --git a/Marlin/src/pins/samd/pins_MINITRONICS20.h b/Marlin/src/pins/samd/pins_MINITRONICS20.h
new file mode 100644
index 00000000..02d806b3
--- /dev/null
+++ b/Marlin/src/pins/samd/pins_MINITRONICS20.h
@@ -0,0 +1,556 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+#pragma once
+
+/**
+ * ReprapWorld's Minitronics v2.0
+ */
+
+#if NOT_TARGET(__SAMD21__)
+ #error "Oops! Select 'Minitronics v2.0' in 'Tools > Board.'"
+#endif
+
+#ifndef BOARD_INFO_NAME
+ #define BOARD_INFO_NAME "Minitronics V2.0"
+#endif
+
+/**
+ * NOTE: We need the Serial port on the -1 to make it work!!. Remember to change it on configuration.h #define SERIAL_PORT -1
+ */
+
+/**
+ * EEPROM EMULATION: Works with some bugs already, but the board needs an I2C EEPROM memory soldered on.
+ */
+//#define FLASH_EEPROM_EMULATION
+//#define I2C_EEPROM // EEPROM on I2C-0
+#define MARLIN_EEPROM_SIZE 500 // 4000 bytes
+
+//This its another option to emulate an EEPROM, but its more efficient to dont loose the data the first One.
+//#define SDCARD_EEPROM_EMULATION
+
+//
+// BLTouch
+//
+#define SERVO0_PIN 33 // BLTouch PWM
+
+//
+// Limit Switches
+//
+#define X_STOP_PIN 54
+#define Y_STOP_PIN 55
+#define Z_STOP_PIN 4
+
+/**
+ * NOTE: Useful if extra TMC2209 are to be used as independent axes.
+ * We need to configure the new digital PIN, for this we could configure on the board the extra pin of this stepper, for example as a MIN_PIN/MAX_PIN. This pin is the D14.
+ */
+//#define Z2_STOP_PIN 14
+//#define X2_STOP_PIN 14
+//#define Y2_STOP_PIN 14
+
+//
+// Z Probe (when not Z_MIN_PIN)
+//
+#ifndef Z_MIN_PROBE_PIN
+ #define Z_MIN_PROBE_PIN 12
+#endif
+
+//
+// Steppers
+//
+#define X_STEP_PIN 1
+#define X_DIR_PIN 3
+#define X_ENABLE_PIN 0
+
+#define Y_STEP_PIN 29
+#define Y_DIR_PIN 28
+#define Y_ENABLE_PIN 0
+
+#define Z_STEP_PIN 16
+#define Z_DIR_PIN 17
+#define Z_ENABLE_PIN 0
+
+#define E0_STEP_PIN 14
+#define E0_DIR_PIN 15
+#define E0_ENABLE_PIN 0
+
+#define E1_STEP_PIN 20
+#define E1_DIR_PIN 13
+#define E1_ENABLE_PIN 21
+
+// Filament runout. You may choose to use this pin for some other purpose. It's a normal GPIO that can be configured as I/O.
+// For example, a switch to detect any kind of behavior, Power supply pin .... etc.
+#ifndef FIL_RUNOUT_PIN
+ #define FIL_RUNOUT_PIN 44
+#endif
+
+// This board have the option to use an extra TMC2209 stepper, one of the use could be as a second extruder.
+#if EXTRUDERS < 2
+ // TODO: Corregir aquí que cuando tenemos dos extrusores o lo que sea, utiliza los endstop que le sobran, osea los max, no hay Z2_endstop
+ #if NUM_Z_STEPPERS > 1
+ #define Z2_STOP_PIN 14
+ #endif
+#else
+ // If we want to configure the extra stepper as a Extruder, we should have undef all of the extra motors.
+ #undef X2_DRIVER_TYPE
+ #undef Y2_DRIVER_TYPE
+ #undef Z2_DRIVER_TYPE
+ #undef Z3_DRIVER_TYPE
+ #undef Z4_DRIVER_TYPE
+
+ // Si tenemos más de un extrusor lo que hacemos es definir el nuevo extrusor así como sus pines
+ // Acordarse de definir el #define TEMP_SENSOR_1, ya que este contiene el tipo de sonda del extrusor E1
+
+ #define FIL_RUNOUT2_PIN 14
+
+#endif
+
+//
+// Extruder / Bed
+//
+
+// Temperature Sensors
+#define TEMP_0_PIN 4 // T1
+
+// You could use one of the ADC for a temp chamber if you don't use the second extruder, for example.
+#if TEMP_SENSOR_CHAMBER > 0
+ #define TEMP_CHAMBER_PIN 3
+#else
+ #define TEMP_1_PIN 2 // T3
+#endif
+
+#define TEMP_BED_PIN 3 // T2
+
+//
+// Heaters / Fans
+//
+#define HEATER_0_PIN 10
+#define HEATER_1_PIN 11
+#define HEATER_BED_PIN 6
+#define SPINDLE_LASER_PWM_PIN 6
+
+// The board has 4 PWM fans, use and configure as desired
+#define FAN_PIN 24
+
+//
+// LCD / Controller
+//
+
+#if ENABLED(CR10_STOCKDISPLAY)
+ #define EXP3_01_PIN EXP1_01_PIN
+ #define EXP3_02_PIN EXP1_02_PIN
+ #define EXP3_03_PIN EXP1_03_PIN
+ #define EXP3_04_PIN EXP1_04_PIN
+ #define EXP3_05_PIN EXP1_05_PIN
+ #define EXP3_06_PIN EXP1_06_PIN
+ #define EXP3_07_PIN EXP1_07_PIN
+ #define EXP3_08_PIN EXP1_08_PIN
+#endif
+
+/************************************/
+/***** Configurations Section ******/
+/************************************/
+
+/**
+ * This sections starts with the pins_RAMPS_144.h as example, after if you need any new
+ * display, you could use normal duponts and connect it with with the scheme showed before.
+ * Tested:
+ * - Ender 3 Old display (Character LCD)
+ * - Ender 3 New Serial DWING Display
+ * - Reprap Display
+ * - Ender 5 New Serial Display
+ * - Any Reprap character display like
+ */
+
+#if HAS_WIRED_LCD
+
+ //
+ // LCD Display output pins
+ //
+
+ #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD)
+
+ #define LCD_PINS_RS 18 // CS chip select /SS chip slave select
+ #define LCD_PINS_ENABLE MOSI // SID (MOSI)
+ #define LCD_PINS_D4 SCK // SCK (CLK) clock
+
+ #define BTN_ENC 23
+ #define BTN_EN1 27
+ #define BTN_EN2 33
+
+ #elif BOTH(IS_NEWPANEL, PANEL_ONE)
+
+ // TO TEST
+ //#define LCD_PINS_RS EXP1_02_PIN
+ //#define LCD_PINS_ENABLE EXP2_05_PIN
+ //#define LCD_PINS_D4 57 // Mega/Due:65 - AGCM4:57
+ //#define LCD_PINS_D5 58 // Mega/Due:66 - AGCM4:58
+ //#define LCD_PINS_D6 EXP2_07_PIN
+ //#define LCD_PINS_D7 56 // Mega/Due:64 - AGCM4:56
+
+ #else
+
+ #if ENABLED(CR10_STOCKDISPLAY)
+
+ // TO TEST
+ //#define LCD_PINS_RS EXP3_04_PIN
+ //#define LCD_PINS_ENABLE EXP3_03_PIN
+ //#define LCD_PINS_D4 EXP3_05_PIN
+
+ #if !IS_NEWPANEL
+ // TO TEST
+ //#define BEEPER_PIN EXP3_05_PIN
+ #endif
+
+ #elif ENABLED(ZONESTAR_LCD)
+
+ // TO TEST
+ //#define LCD_PINS_RS 56 // Mega/Due:64 - AGCM4:56
+ //#define LCD_PINS_ENABLE EXP2_07_PIN
+ //#define LCD_PINS_D4 55 // Mega/Due:63 - AGCM4:55
+ //#define LCD_PINS_D5 EXP1_02_PIN
+ //#define LCD_PINS_D6 EXP2_05_PIN
+ //#define LCD_PINS_D7 57 // Mega/Due:65 - AGCM4:57
+
+ #else
+
+ #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306)
+ // TO TEST
+ //#define LCD_PINS_DC 25 // Set as output on init
+ //#define LCD_PINS_RS 27 // Pull low for 1s to init
+ // DOGM SPI LCD Support
+ //#define DOGLCD_CS 16
+ //#define DOGLCD_MOSI 17
+ //#define DOGLCD_SCK 23
+ //#define DOGLCD_A0 LCD_PINS_DC
+
+ #else
+ // Definitions for any standard Display
+ #define LCD_PINS_RS EXP1_04_PIN
+ #define LCD_PINS_ENABLE EXP1_03_PIN
+ #define LCD_PINS_D4 EXP1_05_PIN
+ #define LCD_PINS_D5 EXP1_06_PIN
+ #define LCD_PINS_D6 EXP1_07_PIN
+ #endif
+
+ #define LCD_PINS_D7 EXP1_08_PIN
+
+ #if !IS_NEWPANEL
+ #define BEEPER_PIN EXP1_01_PIN
+ #endif
+
+ #endif
+
+ #if !IS_NEWPANEL
+ // Buttons attached to a shift register
+ // Not wired yet
+ //#define SHIFT_CLK_PIN EXP1_07_PIN
+ //#define SHIFT_LD_PIN EXP2_05_PIN
+ //#define SHIFT_OUT_PIN EXP1_02_PIN
+ //#define SHIFT_EN_PIN 17
+ #endif
+
+ #endif
+
+ //
+ // LCD Display input pins
+ //
+ #if IS_NEWPANEL
+
+ #if IS_RRD_SC
+
+ //#define BEEPER_PIN EXP1_01_PIN
+
+ #if ENABLED(CR10_STOCKDISPLAY)
+ // TO TEST
+ #define BTN_EN1 EXP1_03_PIN
+ #define BTN_EN2 EXP1_05_PIN
+ #else
+ // Definitions fpr any standard Display
+ #define BTN_EN1 EXP2_05_PIN
+ #define BTN_EN2 EXP2_03_PIN
+ #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
+ #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder
+ #endif
+ #endif
+
+ #define BTN_ENC EXP1_02_PIN
+ #ifndef SD_DETECT_PIN
+ #define SD_DETECT_PIN EXP2_07_PIN
+ #endif
+ //#define KILL_PIN EXP2_10_PIN
+
+ #if ENABLED(BQ_LCD_SMART_CONTROLLER)
+ //#define LCD_BACKLIGHT_PIN EXP1_08_PIN // TO TEST
+ #endif
+
+ #elif ENABLED(LCD_I2C_PANELOLU2)
+
+ // TO TEST
+ //#define BTN_EN1 47
+ //#define BTN_EN2 EXP2_03_PIN
+ //#define BTN_ENC 32
+ //#define LCD_SDSS SDSS
+ //#define KILL_PIN EXP1_01_PIN
+
+ #elif ENABLED(LCD_I2C_VIKI)
+
+ // TO TEST
+ //#define BTN_EN1 EXP1_02_PIN // https://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42.
+ //#define BTN_EN2 EXP2_05_PIN
+ //#define BTN_ENC -1
+
+ //#define LCD_SDSS SDSS
+ //#define SD_DETECT_PIN EXP2_10_PIN
+
+ #elif EITHER(VIKI2, miniVIKI)
+
+ // TO TEST
+ //#define DOGLCD_CS 45
+ //#define DOGLCD_A0 EXP2_07_PIN
+ //#define LCD_SCREEN_ROT_180
+
+ //#define BEEPER_PIN 33
+ //#define STAT_LED_RED_PIN 32
+ //#define STAT_LED_BLUE_PIN EXP1_03_PIN
+
+ //#define BTN_EN1 22
+ //#define BTN_EN2 7
+ //#define BTN_ENC EXP1_08_PIN
+
+ //#define SD_DETECT_PIN -1 // Pin 49 for display SD interface, 72 for easy adapter board
+ //#define KILL_PIN 31
+
+ #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER)
+
+ // TO TEST
+ //#define DOGLCD_CS 29
+ //#define DOGLCD_A0 27
+
+ //#define BEEPER_PIN 23
+ //#define LCD_BACKLIGHT_PIN 33
+
+ //#define BTN_EN1 EXP1_03_PIN
+ //#define BTN_EN2 EXP1_06_PIN
+ //#define BTN_ENC 31
+
+ //#define LCD_SDSS SDSS
+ //#define SD_DETECT_PIN EXP2_10_PIN
+ //#define KILL_PIN EXP1_01_PIN
+
+ #elif EITHER(MKS_MINI_12864, FYSETC_MINI_12864)
+
+ // TO TEST
+ //#define BEEPER_PIN EXP1_06_PIN
+ //#define BTN_ENC EXP1_03_PIN
+ //#define SD_DETECT_PIN EXP2_10_PIN
+
+ //#ifndef KILL_PIN
+ // #define KILL_PIN EXP1_01_PIN
+ //#endif
+
+ #if ENABLED(MKS_MINI_12864)
+
+ // TO TEST
+ //#define DOGLCD_A0 27
+ //#define DOGLCD_CS 25
+
+ // GLCD features
+ // Uncomment screen orientation
+ //#define LCD_SCREEN_ROT_90
+ //#define LCD_SCREEN_ROT_180
+ //#define LCD_SCREEN_ROT_270
+
+ // not connected to a pin
+ //#define LCD_BACKLIGHT_PIN 57 // backlight LED on A11/D? (Mega/Due:65 - AGCM4:57)
+
+ //#define BTN_EN1 31
+ //#define BTN_EN2 33
+
+ #elif ENABLED(FYSETC_MINI_12864)
+
+ // From https://wiki.fysetc.com/Mini12864_Panel/
+
+ // TO TEST
+ //#define DOGLCD_A0 16
+ //#define DOGLCD_CS 17
+
+ //#define BTN_EN1 33
+ //#define BTN_EN2 31
+
+ //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems
+ // results in LCD soft SPI mode 3, SD soft SPI mode 0
+
+ //#define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally.
+
+ #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0)
+ #ifndef RGB_LED_R_PIN
+ // TO TEST
+ //#define RGB_LED_R_PIN 25
+ #endif
+ #ifndef RGB_LED_G_PIN
+ // TO TEST
+ //#define RGB_LED_G_PIN 27
+ #endif
+ #ifndef RGB_LED_B_PIN
+ // TO TEST
+ //#define RGB_LED_B_PIN 29
+ #endif
+ #elif ENABLED(FYSETC_MINI_12864_2_1)
+ // TO TEST
+ //#define NEOPIXEL_PIN 25
+ #endif
+
+ #endif
+
+ #elif ENABLED(MINIPANEL)
+
+ // TO TEST
+ //#define BEEPER_PIN EXP2_05_PIN
+ // not connected to a pin
+ //#define LCD_BACKLIGHT_PIN 57 // backlight LED on A11/D? (Mega/Due:65 - AGCM4:57)
+
+ //#define DOGLCD_A0 EXP2_07_PIN
+ //#define DOGLCD_CS 58 // Mega/Due:66 - AGCM4:58
+
+ // GLCD features
+ // Uncomment screen orientation
+ //#define LCD_SCREEN_ROT_90
+ //#define LCD_SCREEN_ROT_180
+ //#define LCD_SCREEN_ROT_270
+
+ //#define BTN_EN1 EXP1_02_PIN
+ //#define BTN_EN2 55 // Mega/Due:63 - AGCM4:55
+ //#define BTN_ENC 72 // Mega/Due:59 - AGCM4:72
+
+ //#define SD_DETECT_PIN EXP2_10_PIN
+ //#define KILL_PIN 56 // Mega/Due:64 - AGCM4:56
+
+ #elif ENABLED(ZONESTAR_LCD)
+
+ // TO TEST
+ //#define ADC_KEYPAD_PIN 12
+
+ #elif ENABLED(AZSMZ_12864)
+
+ // TO TEST
+
+ #else
+
+ // Beeper on AUX-4
+ //#define BEEPER_PIN 33
+
+ // Buttons are directly attached to AUX-2
+ #if IS_RRW_KEYPAD
+ // TO TEST
+ //#define SHIFT_OUT_PIN EXP1_02_PIN
+ //#define SHIFT_CLK_PIN EXP2_07_PIN
+ //#define SHIFT_LD_PIN EXP2_05_PIN
+ //#define BTN_EN1 56 // Mega/Due:64 - AGCM4:56
+ //#define BTN_EN2 72 // Mega/Due:59 - AGCM4:72
+ //#define BTN_ENC 55 // Mega/Due:63 - AGCM4:55
+ #elif ENABLED(PANEL_ONE)
+ // TO TEST
+ //#define BTN_EN1 72 // AUX2 PIN 3 (Mega/Due:59 - AGCM4:72)
+ //#define BTN_EN2 55 // AUX2 PIN 4 (Mega/Due:63 - AGCM4:55)
+ //#define BTN_ENC EXP2_10_PIN // AUX3 PIN 7
+ #else
+ // TO TEST
+ //#define BTN_EN1 EXP1_06_PIN
+ //#define BTN_EN2 EXP1_03_PIN
+ //#define BTN_ENC 31
+ #endif
+
+ #if ENABLED(G3D_PANEL)
+ // TO TEST
+ //#define SD_DETECT_PIN EXP2_10_PIN
+ //#define KILL_PIN EXP1_01_PIN
+ #endif
+
+ #endif
+ #endif // IS_NEWPANEL
+
+#endif // HAS_WIRED_LCD
+
+//
+// SD Support
+//
+
+#define SDSS 2
+#undef SD_DETECT_PIN
+#define SD_DETECT_PIN 22
+
+#if HAS_TMC_UART
+
+ /**
+ * Address for the UART Configuration of the TMC2209. Override in Configuration files.
+ * To test TMC2209 Steppers enable TMC_DEBUG in Configuration_adv.h and test the M122 command with voltage on the steppers.
+ */
+ #ifndef X_SLAVE_ADDRESS
+ #define X_SLAVE_ADDRESS 0b00
+ #endif
+ #ifndef Y_SLAVE_ADDRESS
+ #define Y_SLAVE_ADDRESS 0b01
+ #endif
+ #ifndef Z_SLAVE_ADDRESS
+ #define Z_SLAVE_ADDRESS 0b10
+ #endif
+ #ifndef E0_SLAVE_ADDRESS
+ #define E0_SLAVE_ADDRESS 0b11
+ #endif
+ #ifndef E1_SLAVE_ADDRESS
+ #define E1_SLAVE_ADDRESS 0b00
+ #endif
+
+ /**
+ * TMC2208/TMC2209 stepper drivers
+ * It seems to work perfectly fine on Software Serial, if an advanced user wants to test, you could use the SAMD51 Serial1 and Serial 2. Be careful with the Sercom configurations.
+ * Steppers 1,2,3,4 (X,Y,Z,E0) are on the Serial1, Sercom (RX = 0, TX = 1), extra stepper 5 (E1 or any axis you want) is on Serial2, Sercom (RX = 17, TX = 16)
+ */
+
+ //#define X_HARDWARE_SERIAL Serial1
+ //#define Y_HARDWARE_SERIAL Serial1
+ //#define Z_HARDWARE_SERIAL Serial1
+ //#define E0_HARDWARE_SERIAL Serial1
+ //#define E1_HARDWARE_SERIAL Serial2
+
+ #define TMC_BAUD_RATE 250000
+
+ //
+ // Software serial
+ //
+ #define X_SERIAL_TX_PIN 0
+ #define X_SERIAL_RX_PIN 1
+
+ #define Y_SERIAL_TX_PIN X_SERIAL_TX_PIN
+ #define Y_SERIAL_RX_PIN X_SERIAL_RX_PIN
+
+ #define Z_SERIAL_TX_PIN X_SERIAL_TX_PIN
+ #define Z_SERIAL_RX_PIN X_SERIAL_RX_PIN
+
+ #define E0_SERIAL_TX_PIN X_SERIAL_TX_PIN
+ #define E0_SERIAL_RX_PIN X_SERIAL_RX_PIN
+
+ #define E1_SERIAL_TX_PIN 17
+ #define E1_SERIAL_RX_PIN 16
+
+#endif
diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V521.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V521.h
new file mode 100644
index 00000000..d3d36855
--- /dev/null
+++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V521.h
@@ -0,0 +1,226 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+#pragma once
+
+/**
+ * Creality 5.2.1 (STM32F103RE) board pin assignments
+ */
+
+#include "env_validate.h"
+
+#if HOTENDS > 2 || E_STEPPERS > 2
+ #error "Creality v5.2.1 supports up to 2 hotends / E steppers."
+#endif
+
+#ifndef BOARD_INFO_NAME
+ #define BOARD_INFO_NAME "Creality V521"
+#endif
+#ifndef DEFAULT_MACHINE_NAME
+ #define DEFAULT_MACHINE_NAME "Creality V5.2.1"
+#endif
+
+//
+// EEPROM
+//
+#if NO_EEPROM_SELECTED
+ // FLASH
+ //#define FLASH_EEPROM_EMULATION
+
+ // I2C
+ #define IIC_BL24CXX_EEPROM // EEPROM on I2C-0 used only for display settings
+ #if ENABLED(IIC_BL24CXX_EEPROM)
+ #define IIC_EEPROM_SDA PC2
+ #define IIC_EEPROM_SCL PC3
+ #define MARLIN_EEPROM_SIZE 0x800 // 2K (24C16)
+ #else
+ #define SDCARD_EEPROM_EMULATION // SD EEPROM until all EEPROM is BL24CXX
+ #define MARLIN_EEPROM_SIZE 0x800 // 2K
+ #endif
+
+ #undef NO_EEPROM_SELECTED
+#endif
+
+//
+// Servos
+//
+#define SERVO0_PIN PD13 // BLTouch OUT
+
+//
+// Limit Switches
+//
+#define X_STOP_PIN PD10 // X
+#define X2_STOP_PIN PE15 // X2
+#define Y_STOP_PIN PE0 // Y
+#define Z_STOP_PIN PE1 // Z
+#define Z2_STOP_PIN PE2 // Z2
+
+#ifndef Z_MIN_PROBE_PIN
+ #define Z_MIN_PROBE_PIN PD12 // BLTouch IN
+#endif
+
+//
+// Filament Runout Sensor
+//
+#define FIL_RUNOUT_PIN PE5 // "Pulled-high"
+#define FIL_RUNOUT2_PIN PE6 // "Pulled-high"
+
+//
+// Steppers
+//
+#define X_ENABLE_PIN PC7
+#define X_STEP_PIN PD15
+#define X_DIR_PIN PD14
+
+#define Y_ENABLE_PIN PB9
+#define Y_STEP_PIN PB7
+#define Y_DIR_PIN PB6
+
+#define Z_ENABLE_PIN PB5
+#define Z_STEP_PIN PB3
+#define Z_DIR_PIN PD7
+
+#define E0_ENABLE_PIN PD4
+#define E0_STEP_PIN PD1
+#define E0_DIR_PIN PD0
+
+#define E1_ENABLE_PIN PE7
+#define E1_STEP_PIN PB1
+#define E1_DIR_PIN PB0
+
+#define X2_ENABLE_PIN PE11
+#define X2_STEP_PIN PE9
+#define X2_DIR_PIN PE8
+
+#define Z2_ENABLE_PIN PC5
+#define Z2_STEP_PIN PA7
+#define Z2_DIR_PIN PA6
+
+//
+// Release PB4 (Y_ENABLE_PIN) from JTAG NRST role
+//
+#define DISABLE_JTAG
+
+//
+// Temperature Sensors
+//
+#define TEMP_0_PIN PA4 // TH0
+#define TEMP_1_PIN PA5 // TH1
+#define TEMP_BED_PIN PA3 // TB1
+
+//
+// Heaters / Fans
+//
+#define HEATER_0_PIN PA1 // HEATER0
+#define HEATER_1_PIN PA0 // HEATER1
+#define HEATER_BED_PIN PA2 // HOT BED
+
+#define FAN_PIN PB14 // FAN
+#define FAN1_PIN PB12 // FAN
+#define FAN_SOFT_PWM
+
+//
+// SD Card
+//
+#define SD_DETECT_PIN PA8
+#define SDCARD_CONNECTION ONBOARD
+#define ONBOARD_SPI_DEVICE 1
+#define ONBOARD_SD_CS_PIN PC11 // SDSS
+#define SDIO_SUPPORT
+#define NO_SD_HOST_DRIVE // This board's SD is only seen by the printer
+
+#if ANY(RET6_12864_LCD, HAS_DWIN_E3V2, IS_DWIN_MARLINUI)
+
+ /**
+ * RET6 12864 LCD
+ * ------
+ * PC6 | 1 2 | PB2
+ * PB10 | 3 4 | PE8
+ * PB14 5 6 | PB13
+ * PB12 | 7 8 | PB15
+ * GND | 9 10 | 5V
+ * ------
+ */
+ #define EXP3_01_PIN PC6
+ #define EXP3_02_PIN PB2
+ #define EXP3_03_PIN PB10
+ #define EXP3_04_PIN PE8
+ #define EXP3_05_PIN PB14
+ #define EXP3_06_PIN PB13
+ #define EXP3_07_PIN PB12
+ #define EXP3_08_PIN PB15
+
+#elif EITHER(VET6_12864_LCD, DWIN_VET6_CREALITY_LCD)
+
+ /**
+ * VET6 12864 LCD
+ * ------
+ * ? | 1 2 | PC5
+ * PB10 | 3 4 | ?
+ * PA6 5 6 | PA5
+ * PA4 | 7 8 | PA7
+ * GND | 9 10 | 5V
+ * ------
+ */
+ #define EXP3_01_PIN -1
+ #define EXP3_02_PIN PC5
+ #define EXP3_03_PIN PB10
+ #define EXP3_04_PIN -1
+ #define EXP3_05_PIN PA6
+ #define EXP3_06_PIN PA5
+ #define EXP3_07_PIN PA4
+ #define EXP3_08_PIN PA7
+
+#endif
+
+#if ENABLED(CR10_STOCKDISPLAY)
+ #if NONE(RET6_12864_LCD, VET6_12864_LCD)
+ #error "Define RET6_12864_LCD or VET6_12864_LCD to select pins for CR10_STOCKDISPLAY with the Creality V4 controller."
+ #endif
+
+ #define LCD_PINS_RS EXP3_07_PIN
+ #define LCD_PINS_ENABLE EXP3_08_PIN
+ #define LCD_PINS_D4 EXP3_06_PIN
+
+ #define BTN_ENC EXP3_02_PIN
+ #define BTN_EN1 EXP3_03_PIN
+ #define BTN_EN2 EXP3_05_PIN
+
+ #define BEEPER_PIN EXP3_01_PIN
+
+#elif ANY(DWIN_VET6_CREALITY_LCD, HAS_DWIN_E3V2, IS_DWIN_MARLINUI)
+
+ // RET6 / VET6 DWIN ENCODER LCD
+ #define BTN_ENC EXP3_05_PIN
+ #define BTN_EN1 EXP3_08_PIN
+ #define BTN_EN2 EXP3_07_PIN
+
+ //#define LCD_LED_PIN EXP3_02_PIN
+ #ifndef BEEPER_PIN
+ #define BEEPER_PIN EXP3_06_PIN
+ #endif
+
+#endif
+
+// DGUS LCDs
+#if HAS_DGUS_LCD
+ #define LCD_SERIAL_PORT 3
+#endif
diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_MINI_E3_V3_0_1.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_MINI_E3_V3_0_1.h
new file mode 100644
index 00000000..31551f6f
--- /dev/null
+++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_MINI_E3_V3_0_1.h
@@ -0,0 +1,350 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+#pragma once
+
+//#define BOARD_CUSTOM_BUILD_FLAGS -DTONE_CHANNEL=4 -DTONE_TIMER=4 -DTIMER_TONE=4
+
+#include "env_validate.h"
+
+#if HOTENDS > 1 || E_STEPPERS > 1
+ #error "BTT SKR Mini E3 V3.0.1 supports up to 1 hotend / E stepper."
+#endif
+
+#ifndef BOARD_INFO_NAME
+ #define BOARD_INFO_NAME "BTT SKR Mini E3 V3.0.1"
+#endif
+
+#define USES_DIAG_JUMPERS
+
+// Ignore temp readings during development.
+//#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000
+
+#ifndef NEOPIXEL_LED
+ #define LED_PIN PA14
+#endif
+
+// Onboard I2C EEPROM
+#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM)
+ #undef NO_EEPROM_SELECTED
+ #define I2C_EEPROM
+ #define SOFT_I2C_EEPROM // Force the use of Software I2C
+ #define I2C_SCL_PIN PB8
+ #define I2C_SDA_PIN PB9
+ #define MARLIN_EEPROM_SIZE 0x1000 // 4K
+#endif
+
+//
+// Servos
+//
+#define SERVO0_PIN PA0 // SERVOS
+
+//
+// Limit Switches
+//
+#define X_STOP_PIN PB5 // X-STOP
+#define Y_STOP_PIN PB6 // Y-STOP
+#define Z_STOP_PIN PB7 // Z-STOP
+
+//
+// Z Probe must be this pin
+//
+#define Z_MIN_PROBE_PIN PA1 // PROBE
+
+//
+// Filament Runout Sensor
+//
+#ifndef FIL_RUNOUT_PIN
+ #define FIL_RUNOUT_PIN PC15 // E0-STOP
+#endif
+
+//
+// Power-loss Detection
+//
+#ifndef POWER_LOSS_PIN
+ #define POWER_LOSS_PIN PC13 // Power Loss Detection: PWR-DET
+#endif
+
+#ifndef NEOPIXEL_PIN
+ #define NEOPIXEL_PIN PA14 // LED driving pin
+#endif
+
+#ifndef PS_ON_PIN
+ #define PS_ON_PIN PC14 // Power Supply Control
+#endif
+
+//
+// Steppers
+//
+#define X_ENABLE_PIN PC10
+#define X_STEP_PIN PC11
+#define X_DIR_PIN PC12
+
+#define Y_ENABLE_PIN PB13
+#define Y_STEP_PIN PB12
+#define Y_DIR_PIN PB10
+
+#define Z_ENABLE_PIN PB2
+#define Z_STEP_PIN PB1
+#define Z_DIR_PIN PB0
+
+#define E0_ENABLE_PIN PC3
+#define E0_STEP_PIN PC2
+#define E0_DIR_PIN PC1
+
+#if HAS_TMC_UART
+ /**
+ * TMC220x stepper drivers
+ * Hardware serial communication ports
+ */
+ #define X_HARDWARE_SERIAL MSerial6
+ #define Y_HARDWARE_SERIAL MSerial6
+ #define Z_HARDWARE_SERIAL MSerial6
+ #define E0_HARDWARE_SERIAL MSerial6
+
+ // Default TMC slave addresses
+ #ifndef X_SLAVE_ADDRESS
+ #define X_SLAVE_ADDRESS 0
+ #endif
+ #ifndef Y_SLAVE_ADDRESS
+ #define Y_SLAVE_ADDRESS 2
+ #endif
+ #ifndef Z_SLAVE_ADDRESS
+ #define Z_SLAVE_ADDRESS 1
+ #endif
+ #ifndef E0_SLAVE_ADDRESS
+ #define E0_SLAVE_ADDRESS 3
+ #endif
+#endif
+
+//
+// Temperature Sensors
+//
+#define TEMP_0_PIN PC5 // Analog Input "TH0"
+#define TEMP_BED_PIN PC4 // Analog Input "TB0"
+
+//
+// Heaters / Fans
+//
+#define HEATER_0_PIN PA15 // "HE"
+#define HEATER_BED_PIN PB3 // "HB"
+#define FAN_PIN PC9 // "FAN0"
+#define FAN1_PIN PA8 // "FAN1"
+#define FAN2_PIN PC8 // "FAN2"
+
+/**
+ * SKR Mini E3 V3.0.1
+ * ------
+ * (BEEPER) PB15 | 1 2 | PB14 (BTN_ENC)
+ * (BTN_EN1) PA9 | 3 4 | RESET
+ * (BTN_EN2) PA10 5 6 | PB4 (LCD_D4)
+ * (LCD_RS) PD2 | 7 8 | PC0 (LCD_EN)
+ * GND | 9 10 | 5V
+ * ------
+ * EXP1
+ */
+#define EXP1_01_PIN PB15
+#define EXP1_02_PIN PB14
+#define EXP1_03_PIN PA9
+#define EXP1_04_PIN -1 // RESET
+#define EXP1_05_PIN PA10
+#define EXP1_06_PIN PB4
+#define EXP1_07_PIN PD2
+#define EXP1_08_PIN PC0
+
+#if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI
+ /**
+ * ------ ------ ------
+ * (ENT) | 1 2 | (BEEP) |10 9 | |10 9 |
+ * (RX) | 3 4 | (RX) | 8 7 | (TX) RX | 8 7 | TX
+ * (TX) 5 6 | (ENT) 6 5 | (BEEP) ENT | 6 5 | BEEP
+ * (B) | 7 8 | (A) (B) | 4 3 | (A) B | 4 3 | A
+ * GND | 9 10 | (VCC) GND | 2 1 | VCC GND | 2 1 | VCC
+ * ------ ------ ------
+ * EXP1 DWIN DWIN (plug)
+ *
+ * All pins are labeled as printed on DWIN PCB. Connect TX-TX, A-A and so on.
+ */
+
+ #error "DWIN_CREALITY_LCD requires a custom cable, see diagram above this line. Comment out this line to continue."
+
+ #define BEEPER_PIN EXP1_02_PIN
+ #define BTN_EN1 EXP1_08_PIN
+ #define BTN_EN2 EXP1_07_PIN
+ #define BTN_ENC EXP1_01_PIN
+
+#elif HAS_WIRED_LCD
+
+ #if ENABLED(CR10_STOCKDISPLAY)
+
+ #define BEEPER_PIN EXP1_01_PIN
+ #define BTN_ENC EXP1_02_PIN
+
+ #define BTN_EN1 EXP1_03_PIN
+ #define BTN_EN2 EXP1_05_PIN
+
+ #define LCD_PINS_RS EXP1_07_PIN
+ #define LCD_PINS_ENABLE EXP1_08_PIN
+ #define LCD_PINS_D4 EXP1_06_PIN
+
+ #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD!
+
+ #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING
+ #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)"
+ #endif
+
+ #define LCD_PINS_RS EXP1_06_PIN
+ #define LCD_PINS_ENABLE EXP1_02_PIN
+ #define LCD_PINS_D4 EXP1_07_PIN
+ #define LCD_PINS_D5 EXP1_05_PIN
+ #define LCD_PINS_D6 EXP1_03_PIN
+ #define LCD_PINS_D7 EXP1_01_PIN
+ #define ADC_KEYPAD_PIN PA1 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD!
+
+ #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY)
+
+ #define BTN_ENC EXP1_02_PIN
+ #define BTN_EN1 EXP1_03_PIN
+ #define BTN_EN2 EXP1_05_PIN
+
+ #define DOGLCD_CS EXP1_07_PIN
+ #define DOGLCD_A0 EXP1_06_PIN
+ #define DOGLCD_SCK EXP1_01_PIN
+ #define DOGLCD_MOSI EXP1_08_PIN
+
+ #define FORCE_SOFT_SPI
+ #define LCD_BACKLIGHT_PIN -1
+
+ #elif IS_TFTGLCD_PANEL
+
+ #if ENABLED(TFTGLCD_PANEL_SPI)
+
+ #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING
+ #error "CAUTION! TFTGLCD_PANEL_SPI requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)"
+ #endif
+
+ /**
+ * TFTGLCD_PANEL_SPI display pinout
+ *
+ * Board Display
+ * ------ ------
+ * (BEEPER) PB6 | 1 2 | PB15 (SD_DET) 5V |10 9 | GND
+ * RESET | 3 4 | PA9 (MOD_RESET) -- | 8 7 | (SD_DET)
+ * PB4 5 6 | PA10 (SD_CS) (MOSI) | 6 5 | --
+ * PB7 | 7 8 | PD2 (LCD_CS) (SD_CS) | 4 3 | (LCD_CS)
+ * GND | 9 10 | 5V (SCK) | 2 1 | (MISO)
+ * ------ ------
+ * EXP1 EXP1
+ *
+ * Needs custom cable:
+ *
+ * Board Display
+ *
+ * EXP1-10 ---------- EXP1-10
+ * EXP1-9 ----------- EXP1-9
+ * SPI1-4 ----------- EXP1-6
+ * EXP1-7 ----------- FREE
+ * SPI1-3 ----------- EXP1-2
+ * EXP1-5 ----------- EXP1-4
+ * EXP1-4 ----------- FREE
+ * EXP1-3 ----------- EXP1-3
+ * SPI1-1 ----------- EXP1-1
+ * EXP1-1 ----------- EXP1-7
+ */
+
+ #define TFTGLCD_CS EXP1_03_PIN
+
+ #endif
+
+ #else
+ #error "Only CR10_STOCKDISPLAY, ZONESTAR_LCD, ENDER2_STOCKDISPLAY, MKS_MINI_12864, and TFTGLCD_PANEL_(SPI|I2C) are currently supported on the BIGTREE_SKR_MINI_E3."
+ #endif
+
+#endif // HAS_WIRED_LCD
+
+#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050)
+
+ #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING
+ #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)"
+ #endif
+
+ /**
+ * FYSETC TFT TFT81050 display pinout
+ *
+ * Board Display
+ * ------ ------
+ * (SD_DET) PB15 | 1 2 | PB6 (BEEPER) 5V |10 9 | GND
+ * (MOD_RESET) PA9 | 3 4 | RESET (RESET) | 8 7 | (SD_DET)
+ * (SD_CS) PA10 5 6 | PB4 (FREE) (MOSI) | 6 5 | (LCD_CS)
+ * (LCD_CS) PD2 | 7 8 | PB7 (FREE) (SD_CS) | 4 3 | (MOD_RESET)
+ * 5V | 9 10 | GND (SCK) | 2 1 | (MISO)
+ * ------ ------
+ * EXP1 EXP1
+ *
+ * Needs custom cable:
+ *
+ * Board Adapter Display
+ * _________
+ * EXP1-10 ---------- EXP1-10
+ * EXP1-9 ----------- EXP1-9
+ * SPI1-4 ----------- EXP1-6
+ * EXP1-7 ----------- EXP1-5
+ * SPI1-3 ----------- EXP1-2
+ * EXP1-5 ----------- EXP1-4
+ * EXP1-4 ----------- EXP1-8
+ * EXP1-3 ----------- EXP1-3
+ * SPI1-1 ----------- EXP1-1
+ * EXP1-1 ----------- EXP1-7
+ */
+
+ #define CLCD_SPI_BUS 1 // SPI1 connector
+
+ #define BEEPER_PIN EXP1_02_PIN
+
+ #define CLCD_MOD_RESET EXP1_03_PIN
+ #define CLCD_SPI_CS EXP1_07_PIN
+
+#endif // TOUCH_UI_FTDI_EVE && LCD_FYSETC_TFT81050
+
+//
+// SD Support
+//
+
+#ifndef SDCARD_CONNECTION
+ #define SDCARD_CONNECTION ONBOARD
+#endif
+
+#if SD_CONNECTION_IS(LCD) && (BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL)
+ #define SD_DETECT_PIN EXP1_01_PIN
+ #define SD_SS_PIN EXP1_05_PIN
+#elif SD_CONNECTION_IS(CUSTOM_CABLE)
+ #error "SD CUSTOM_CABLE is not compatible with SKR Mini E3."
+#endif
+
+#define ONBOARD_SPI_DEVICE 1 // SPI1 -> used only by HAL/STM32F1...
+#define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card
+
+#define ENABLE_SPI1
+#define SDSS ONBOARD_SD_CS_PIN
+#define SD_SS_PIN ONBOARD_SD_CS_PIN
+#define SD_SCK_PIN PA5
+#define SD_MISO_PIN PA6
+#define SD_MOSI_PIN PA7
diff --git a/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h b/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h
new file mode 100644
index 00000000..d00b21c3
--- /dev/null
+++ b/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h
@@ -0,0 +1,381 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+#pragma once
+
+#include "env_validate.h"
+
+#if HOTENDS > 4 || E_STEPPERS > 4
+ #error "MKS SKIPR supports up to 4 hotends / E steppers."
+#endif
+
+#define BOARD_INFO_NAME "MKS SKIPR V1.0"
+
+// Valid SERIAL_PORT values: -1 (USB-C), 1 (direct to RK3328), 3 (USART3 header)
+
+#define USES_DIAG_JUMPERS
+
+// Onboard I2C EEPROM
+#define I2C_EEPROM
+#define MARLIN_EEPROM_SIZE 0x1000 // 4K (AT24C32)
+#define I2C_SCL_PIN PB8
+#define I2C_SDA_PIN PB9
+
+//
+// Servos
+//
+#define SERVO0_PIN PA8
+
+//
+// Trinamic Stallguard pins // Connector labels
+#define X_DIAG_PIN PA14 // X-
+#define Y_DIAG_PIN PA15 // Y-
+#define Z_DIAG_PIN PB15 // Z-
+#define E0_DIAG_PIN PA13 // MT-DET
+#define E1_DIAG_PIN PC5 // NEOPIXEL
+#define E2_DIAG_PIN PB14 // Z+
+
+//
+// Check for additional used endstop pins
+//
+#if HAS_EXTRA_ENDSTOPS
+ #define _ENDSTOP_IS_ANY(ES) X2_USE_ENDSTOP == ES || Y2_USE_ENDSTOP == ES || Z2_USE_ENDSTOP == ES || Z3_USE_ENDSTOP == ES || Z4_USE_ENDSTOP == ES
+ #if _ENDSTOP_IS_ANY(_XMIN_) || _ENDSTOP_IS_ANY(_XMAX_)
+ #define NEEDS_X_MINMAX 1
+ #endif
+ #if _ENDSTOP_IS_ANY(_YMIN_) || _ENDSTOP_IS_ANY(_YMAX_)
+ #define NEEDS_Y_MINMAX 1
+ #endif
+ #if _ENDSTOP_IS_ANY(_ZMIN_) || _ENDSTOP_IS_ANY(_ZMAX_)
+ #define NEEDS_Z_MINMAX 1
+ #endif
+ #undef _ENDSTOP_IS_ANY
+#endif
+
+//
+// Limit Switches
+//
+#ifdef X_STALL_SENSITIVITY
+ #define X_STOP_PIN X_DIAG_PIN // X-
+#elif EITHER(DUAL_X_CARRIAGE, NEEDS_X_MINMAX)
+ #ifndef X_MIN_PIN
+ #define X_MIN_PIN X_DIAG_PIN // X-
+ #endif
+ #ifndef X_MAX_PIN
+ #define X_MAX_PIN E0_DIAG_PIN // MT-DET
+ #endif
+#else
+ #define X_STOP_PIN X_DIAG_PIN // X-
+#endif
+
+#ifdef Y_STALL_SENSITIVITY
+ #define Y_STOP_PIN Y_DIAG_PIN // Y-
+#elif NEEDS_Y_MINMAX
+ #ifndef Y_MIN_PIN
+ #define Y_MIN_PIN Y_DIAG_PIN // Y-
+ #endif
+ #ifndef Y_MAX_PIN
+ #define Y_MAX_PIN E1_DIAG_PIN // NEOPIXEL
+ #endif
+#else
+ #define Y_STOP_PIN Y_DIAG_PIN // Y-
+#endif
+
+#ifdef Z_STALL_SENSITIVITY
+ #define Z_STOP_PIN Z_DIAG_PIN // Z-
+#elif NEEDS_Z_MINMAX
+ #ifndef Z_MIN_PIN
+ #define Z_MIN_PIN Z_DIAG_PIN // Z-
+ #endif
+ #ifndef Z_MAX_PIN
+ #define Z_MAX_PIN E2_DIAG_PIN // Z+
+ #endif
+#else
+ #define Z_STOP_PIN Z_DIAG_PIN // Z-
+#endif
+
+#if DISABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) || ENABLED(USE_PROBE_FOR_Z_HOMING)
+ #ifndef Z_MIN_PROBE
+ #define Z_MIN_PROBE_PIN E2_DIAG_PIN // defaults to 'Z+' connector
+ #endif
+#endif
+
+#undef NEEDS_X_MINMAX
+#undef NEEDS_Y_MINMAX
+#undef NEEDS_Z_MINMAX
+
+//
+// Steppers
+//
+#define X_STEP_PIN PC14
+#define X_DIR_PIN PC13
+#define X_ENABLE_PIN PC15
+#ifndef X_CS_PIN
+ #define X_CS_PIN PE6
+#endif
+
+#define Y_STEP_PIN PE5
+#define Y_DIR_PIN PE4
+#define Y_ENABLE_PIN PD14
+#ifndef Y_CS_PIN
+ #define Y_CS_PIN PE3
+#endif
+
+#define Z_STEP_PIN PE1 // "Z1"
+#define Z_DIR_PIN PE0
+#define Z_ENABLE_PIN PE2
+#ifndef Z_CS_PIN
+ #define Z_CS_PIN PB7
+#endif
+
+#define E0_STEP_PIN PB5
+#define E0_DIR_PIN PB4
+#define E0_ENABLE_PIN PB6
+#ifndef E0_CS_PIN
+ #define E0_CS_PIN PB3
+#endif
+
+#define E1_STEP_PIN PD6 // "Z2"
+#define E1_DIR_PIN PD5
+#define E1_ENABLE_PIN PD7
+#ifndef E1_CS_PIN
+ #define E1_CS_PIN PD4
+#endif
+
+#define E2_STEP_PIN PD2 // "Z3"
+#define E2_DIR_PIN PD1
+#define E2_ENABLE_PIN PD3
+#ifndef E2_CS_PIN
+ #define E2_CS_PIN PD0
+#endif
+
+#define E3_STEP_PIN PC7 // "Z4"
+#define E3_DIR_PIN PC6
+#define E3_ENABLE_PIN PC8
+#ifndef E3_CS_PIN
+ #define E3_CS_PIN PD15
+#endif
+
+//
+// Temperature Sensors
+//
+#define TEMP_BED_PIN PC0 // TB
+#define TEMP_0_PIN PC1 // TH0
+#define TEMP_1_PIN PC2 // TH1
+#define TEMP_2_PIN PC3 // TH2
+
+//
+// Heaters / Fans
+//
+#define HEATER_BED_PIN PD12 // Hotbed
+#define HEATER_0_PIN PB1 // Heater0
+#define HEATER_1_PIN PB0 // Heater1
+#define HEATER_2_PIN PA3 // Heater2
+
+#define FAN_PIN PA2 // Fan0
+#define FAN1_PIN PA1 // Fan1
+#define FAN2_PIN PA0 // Fan2
+
+//
+// Software SPI pins for TMC2130 stepper drivers
+// This board doesn't support hardware SPI there
+//
+#if HAS_TMC_SPI
+ #define TMC_USE_SW_SPI
+ #define TMC_SW_MOSI PE14
+ #define TMC_SW_MISO PE13
+ #define TMC_SW_SCK PE12
+#endif
+
+//
+// TMC2208/TMC2209 stepper drivers
+// This board is routed for one-wire software serial
+//
+#if HAS_TMC_UART
+ #define X_SERIAL_TX_PIN PE6
+ #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
+
+ #define Y_SERIAL_TX_PIN PE3
+ #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
+
+ #define Z_SERIAL_TX_PIN PB7
+ #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
+
+ #define E0_SERIAL_TX_PIN PB3
+ #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
+
+ #define E1_SERIAL_TX_PIN PD4
+ #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
+
+ #define E2_SERIAL_TX_PIN PD0
+ #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN
+
+ #define E3_SERIAL_TX_PIN PD15
+ #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN
+
+ // Reduce baud rate to improve software serial reliability
+ #define TMC_BAUD_RATE 19200
+#endif
+
+/** ------ ------
+ * (BEEPER) PB2 | 1 2 | PE10 (BTN_ENC) (MISO) PA6 | 1 2 | PA5 (SCK)
+ * (LCD_EN) PE11 | 3 4 | PD10 (LCD_RS) (BTN_EN1) PE9 | 3 4 | PA4 (SD_SS)
+ * (LCD_D4) PD9 | 5 6 PD8 (LCD_D5) (BTN_EN2) PE8 | 5 6 PA7 (MOSI)
+ * (LCD_D6) PE15 | 7 8 | PE7 (LCD_D7) (SD_DETECT) PD13 | 7 8 | RESET
+ * GND | 9 10 | 5V GND | 9 10 | --
+ * ------ ------
+ * EXP1 EXP2
+ */
+#define EXP1_01_PIN PB2
+#define EXP1_02_PIN PE10
+#define EXP1_03_PIN PE11
+#define EXP1_04_PIN PD10
+#define EXP1_05_PIN PD9
+#define EXP1_06_PIN PD8
+#define EXP1_07_PIN PE15
+#define EXP1_08_PIN PE7
+
+#define EXP2_01_PIN PA6
+#define EXP2_02_PIN PA5
+#define EXP2_03_PIN PE9
+#define EXP2_04_PIN PA4
+#define EXP2_05_PIN PE8
+#define EXP2_06_PIN PA7
+#define EXP2_07_PIN PD13
+#define EXP2_08_PIN -1 // connected to MCU reset
+
+//
+// SD Support
+// Onboard SD card use hardware SPI3 (defined in variant), LCD SD card use hardware SPI1
+//
+#if ENABLED(SDSUPPORT)
+ #ifndef SDCARD_CONNECTION
+ #define SDCARD_CONNECTION LCD
+ #endif
+ #if SD_CONNECTION_IS(ONBOARD)
+ //#define SOFTWARE_SPI
+ //#define SD_SPI_SPEED SPI_HALF_SPEED
+ #undef SD_DETECT_STATE
+ #define SD_DETECT_STATE LOW
+ #define SD_DETECT_PIN PC4
+ #elif SD_CONNECTION_IS(LCD)
+ //#define SOFTWARE_SPI
+ //#define SD_SPI_SPEED SPI_QUARTER_SPEED
+ #define SD_SS_PIN EXP2_04_PIN
+ #define SD_SCK_PIN EXP2_02_PIN
+ #define SD_MISO_PIN EXP2_01_PIN
+ #define SD_MOSI_PIN EXP2_06_PIN
+ #define SD_DETECT_PIN EXP2_07_PIN
+ #elif SD_CONNECTION_IS(CUSTOM_CABLE)
+ #error "CUSTOM_CABLE is not a supported SDCARD_CONNECTION for this board"
+ #endif
+ #define SDSS SD_SS_PIN
+#endif
+
+//
+// LCDs and Controllers
+//
+#if IS_TFTGLCD_PANEL
+
+ #if ENABLED(TFTGLCD_PANEL_SPI)
+ #define TFTGLCD_CS EXP2_03_PIN
+ #endif
+
+#elif HAS_WIRED_LCD
+
+ #define BEEPER_PIN EXP1_01_PIN
+ #define BTN_ENC EXP1_02_PIN
+
+ #if ENABLED(CR10_STOCKDISPLAY)
+
+ #define LCD_PINS_RS EXP1_07_PIN
+
+ #define BTN_EN1 EXP1_03_PIN
+ #define BTN_EN2 EXP1_05_PIN
+
+ #define LCD_PINS_ENABLE EXP1_08_PIN
+ #define LCD_PINS_D4 EXP1_06_PIN
+
+ #else
+
+ #define LCD_PINS_RS EXP1_04_PIN
+
+ #define BTN_EN1 EXP2_03_PIN
+ #define BTN_EN2 EXP2_05_PIN
+
+ #define LCD_PINS_ENABLE EXP1_03_PIN
+ #define LCD_PINS_D4 EXP1_05_PIN
+
+ #if ENABLED(FYSETC_MINI_12864)
+ #define DOGLCD_CS EXP1_03_PIN
+ #define DOGLCD_A0 EXP1_04_PIN
+ //#define LCD_BACKLIGHT_PIN -1
+ #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally.
+ #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0)
+ #ifndef RGB_LED_R_PIN
+ #define RGB_LED_R_PIN EXP1_06_PIN
+ #endif
+ #ifndef RGB_LED_G_PIN
+ #define RGB_LED_G_PIN EXP1_07_PIN
+ #endif
+ #ifndef RGB_LED_B_PIN
+ #define RGB_LED_B_PIN EXP1_08_PIN
+ #endif
+ #elif ENABLED(FYSETC_MINI_12864_2_1)
+ #define NEOPIXEL_PIN EXP1_06_PIN
+ #endif
+ #endif // !FYSETC_MINI_12864
+
+ #if IS_ULTIPANEL
+ #define LCD_PINS_D5 EXP1_06_PIN
+ #define LCD_PINS_D6 EXP1_07_PIN
+ #define LCD_PINS_D7 EXP1_08_PIN
+ #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
+ #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder
+ #endif
+ #endif
+
+ #endif
+#endif // HAS_WIRED_LCD
+
+// Alter timing for graphical display
+#if IS_U8GLIB_ST7920
+ #define BOARD_ST7920_DELAY_1 120
+ #define BOARD_ST7920_DELAY_2 80
+ #define BOARD_ST7920_DELAY_3 580
+#endif
+
+//
+// NeoPixel LED
+//
+#ifndef NEOPIXEL_PIN
+ #define NEOPIXEL_PIN PC5
+#endif
+
+//
+// MAX31865
+//
+#if HAS_MAX31865
+ #define TEMP_0_CS_PIN PD11
+ #define TEMP_0_SCK_PIN PE12
+ #define TEMP_0_MISO_PIN PE13
+ #define TEMP_0_MOSI_PIN PE14
+#endif
diff --git a/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h
new file mode 100644
index 00000000..d16d7b20
--- /dev/null
+++ b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h
@@ -0,0 +1,206 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+#pragma once
+
+/**
+ * STM32F407VET6 on Opulo Lumen PnP Rev3
+ * Website - https://opulo.io/
+ */
+
+#define ALLOW_STM32DUINO
+#include "env_validate.h"
+
+#define BOARD_INFO_NAME "LumenPnP Motherboard REV04"
+#define DEFAULT_MACHINE_NAME "LumenPnP"
+
+/**
+ * By default, the extra stepper motor configuration is:
+ * I = Left Head
+ * J = Right Head
+ * K = Auxiliary (Conveyor belt)
+ */
+
+#define SRAM_EEPROM_EMULATION
+#define MARLIN_EEPROM_SIZE 0x2000 // 8K
+
+// I2C MCP3426 (16-Bit, 240SPS, dual-channel ADC)
+#define HAS_MCP3426_ADC
+
+//
+// Servos
+//
+#define SERVO0_PIN PB10
+#define SERVO1_PIN PB11
+
+//
+// Limit Switches
+//
+#define X_STOP_PIN PC6
+#define Y_STOP_PIN PD15
+#define Z_STOP_PIN PD14
+
+// None of these require limit switches by default, so we leave these commented
+// here for your reference.
+//#define I_MIN_PIN PA8
+//#define I_MAX_PIN PA8
+//#define J_MIN_PIN PD13
+//#define J_MAX_PIN PD13
+//#define K_MIN_PIN PC9
+//#define K_MAX_PIN PC9
+
+//
+// Steppers
+//
+#define X_STEP_PIN PB15
+#define X_DIR_PIN PB14
+#define X_ENABLE_PIN PD9
+
+#define Y_STEP_PIN PE15
+#define Y_DIR_PIN PE14
+#define Y_ENABLE_PIN PB13
+
+#define Z_STEP_PIN PE7
+#define Z_DIR_PIN PB1
+#define Z_ENABLE_PIN PE9
+
+#define I_STEP_PIN PC4
+#define I_DIR_PIN PA4
+#define I_ENABLE_PIN PB0
+
+#define J_STEP_PIN PE11
+#define J_DIR_PIN PE10
+#define J_ENABLE_PIN PE13
+
+#define K_STEP_PIN PD6
+#define K_DIR_PIN PD7
+#define K_ENABLE_PIN PA3
+
+#if HAS_TMC_SPI
+ /**
+ * Make sure to configure the jumpers on the back side of the Mobo according to
+ * this diagram: https://github.com/MarlinFirmware/Marlin/pull/23851
+ */
+ #error "SPI drivers require a custom jumper configuration, see comment above! Comment out this line to continue."
+
+ #if AXIS_HAS_SPI(X)
+ #define X_CS_PIN PD8
+ #endif
+ #if AXIS_HAS_SPI(Y)
+ #define Y_CS_PIN PB12
+ #endif
+ #if AXIS_HAS_SPI(Z)
+ #define Z_CS_PIN PE8
+ #endif
+ #if AXIS_HAS_SPI(I)
+ #define I_CS_PIN PC5
+ #endif
+ #if AXIS_HAS_SPI(J)
+ #define J_CS_PIN PE12
+ #endif
+ #if AXIS_HAS_SPI(K)
+ #define K_CS_PIN PA2
+ #endif
+
+#elif HAS_TMC_UART
+
+ #define X_SERIAL_TX_PIN PD8
+ #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
+
+ #define Y_SERIAL_TX_PIN PB12
+ #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
+
+ #define Z_SERIAL_TX_PIN PE8
+ #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
+
+ #define I_SERIAL_TX_PIN PC5
+ #define I_SERIAL_RX_PIN I_SERIAL_TX_PIN
+
+ #define J_SERIAL_TX_PIN PE12
+ #define J_SERIAL_RX_PIN J_SERIAL_TX_PIN
+
+ #define K_SERIAL_TX_PIN PA2
+ #define K_SERIAL_RX_PIN K_SERIAL_TX_PIN
+
+ // Reduce baud rate to improve software serial reliability
+ #define TMC_BAUD_RATE 19200
+
+#endif
+
+//
+// Heaters / Fans
+//
+#define FAN_PIN PE2
+#define FAN1_PIN PE3
+#define FAN2_PIN PE4
+#define FAN3_PIN PE5
+
+#define FAN_SOFT_PWM_REQUIRED
+
+//
+// Neopixel
+//
+#define NEOPIXEL_PIN PC7
+#define NEOPIXEL2_PIN PC8
+
+//
+// SPI
+//
+#define MISO_PIN PB4
+#define MOSI_PIN PB5
+#define SCK_PIN PB3
+
+#define TMC_SW_MISO MISO_PIN
+#define TMC_SW_MOSI MOSI_PIN
+#define TMC_SW_SCK SCK_PIN
+
+//
+// I2C
+//
+#define I2C_SDA_PIN PB7
+#define I2C_SCL_PIN PB6
+
+/**
+ * The index mobo rev03 has 3 aux ports. We define them here so they may be used
+ * in other places and to make sure someone doesn't have to go look up the pinout
+ * in the board files. Each 12 pin aux port has this pinout:
+ *
+ * VDC 1 2 GND
+ * 3.3V 3 4 SCL (I2C_SCL_PIN)
+ * PWM1 5 6 SDA (I2C_SDA_PIN)
+ * PWM2 7 8 CIPO (MISO_PIN)
+ * A1 9 10 COPI (MOSI_PIN)
+ * A2 11 12 SCK (SCK_PIN)
+ */
+#define LUMEN_AUX1_PWM1 PA15
+#define LUMEN_AUX1_PWM2 PA5
+#define LUMEN_AUX1_A1 PC0
+#define LUMEN_AUX1_A2 PC1
+
+#define LUMEN_AUX2_PWM1 PA6
+#define LUMEN_AUX2_PWM2 PA7
+#define LUMEN_AUX2_A1 PC2
+#define LUMEN_AUX2_A2 PC3
+
+#define LUMEN_AUX3_PWM1 PB8
+#define LUMEN_AUX3_PWM2 PB9
+#define LUMEN_AUX3_A1 PA0
+#define LUMEN_AUX3_A2 PA1
diff --git a/Marlin/src/pins/stm32f4/pins_TRONXY_V10.h b/Marlin/src/pins/stm32f4/pins_TRONXY_V10.h
new file mode 100644
index 00000000..e3b9f7ef
--- /dev/null
+++ b/Marlin/src/pins/stm32f4/pins_TRONXY_V10.h
@@ -0,0 +1,266 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+#pragma once
+
+#include "env_validate.h"
+
+#if HOTENDS > 3 || E_STEPPERS > 3
+ #error "Tronxy V10 supports up to 3 hotends / E steppers."
+#endif
+
+#define BOARD_INFO_NAME "Tronxy V10"
+#define DEFAULT_MACHINE_NAME BOARD_INFO_NAME
+
+#define STEP_TIMER 6
+#define TEMP_TIMER 14
+
+//
+// Servos
+//
+//#define SERVO0_PIN PB10
+
+//
+// EEPROM
+//
+#if NO_EEPROM_SELECTED
+ #undef NO_EEPROM_SELECTED
+ #if TRONXY_UI > 0
+ #define EEPROM_AT24CXX
+ #else
+ #define FLASH_EEPROM_EMULATION
+ #endif
+#endif
+
+#if ENABLED(FLASH_EEPROM_EMULATION)
+ // SoC Flash (framework-arduinoststm32-maple/STM32F1/libraries/EEPROM/EEPROM.h)
+ #define EEPROM_START_ADDRESS (0x8000000UL + (512 * 1024) - 2 * EEPROM_PAGE_SIZE)
+ #define EEPROM_PAGE_SIZE (0x800U) // 2KB, but will use 2x more (4KB)
+ #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE
+#else
+ #if ENABLED(EEPROM_AT24CXX)
+ #define AT24CXX_SCL PB8
+ #define AT24CXX_SDA PB9
+ #define AT24CXX_WP PB7
+ #else
+ #define I2C_EEPROM // AT24C32
+ #endif
+ #define MARLIN_EEPROM_SIZE 0x1000 // 4K
+#endif
+
+//
+// SPI Flash
+//
+//#define SPI_FLASH
+#if ENABLED(SPI_FLASH)
+ #define SPI_FLASH_SIZE 0x200000 // 2MB
+ #define W25QXX_CS_PIN PG15 // SPI2
+ #define W25QXX_MOSI_PIN PB5
+ #define W25QXX_MISO_PIN PB4
+ #define W25QXX_SCK_PIN PB3
+#endif
+
+//
+// Limit Switches
+//
+#define X_MIN_PIN PC15
+#define X_MAX_PIN PB0
+#define Y_STOP_PIN PC14
+
+#ifndef Z_MIN_PROBE_PIN
+ #define Z_MIN_PROBE_PIN PE3
+#endif
+
+#if ENABLED(DUAL_Z_ENDSTOP_PROBE)
+ #if NUM_Z_STEPPERS > 1 && Z_HOME_TO_MAX // Swap Z1/Z2 for dual Z with max homing
+ #define Z_MIN_PIN PF11
+ #define Z_MAX_PIN PC13
+ #else
+ #define Z_MIN_PIN PC13
+ #define Z_MAX_PIN PF11
+ #endif
+#else
+ #ifndef Z_STOP_PIN
+ #define Z_STOP_PIN PC13
+ #endif
+#endif
+//
+// Filament Sensors
+//
+#ifndef FIL_RUNOUT_PIN
+ #define FIL_RUNOUT_PIN PE6 // MT_DET
+#endif
+#ifndef FIL_RUNOUT2_PIN
+ #define FIL_RUNOUT2_PIN PF12
+#endif
+
+//
+// Steppers
+//
+#define X_ENABLE_PIN PF0
+#define X_STEP_PIN PE5
+#define X_DIR_PIN PF1
+
+#define Y_ENABLE_PIN PF5
+#define Y_STEP_PIN PF9
+#define Y_DIR_PIN PF3
+
+#define Z_ENABLE_PIN PA5
+#define Z_STEP_PIN PA6
+#define Z_DIR_PIN PF15
+
+#define E0_ENABLE_PIN PF14
+#define E0_STEP_PIN PB1
+#define E0_DIR_PIN PF13
+
+#define E1_ENABLE_PIN PG5
+#define E1_STEP_PIN PD12
+#define E1_DIR_PIN PG4
+
+#define E2_ENABLE_PIN PF7
+#define E2_STEP_PIN PF6
+#define E2_DIR_PIN PF4
+
+//
+// Temperature Sensors
+//
+#define TEMP_0_PIN PC3 // TH1
+#define TEMP_BED_PIN PC2 // TB1
+
+//
+// Heaters / Fans
+//
+#define HEATER_0_PIN PG7 // HEATER1
+#define HEATER_BED_PIN PE2 // HOT BED
+//#define HEATER_BED_INVERTING true
+
+#define FAN_PIN PG0 // FAN0
+#define FAN1_PIN PB6 // FAN1
+#define FAN2_PIN PG9 // FAN2
+#define FAN3_PIN PF10 // FAN3
+#define CONTROLLER_FAN_PIN PD7 // BOARD FAN
+#define FAN_SOFT_PWM
+
+//
+// Laser / Spindle
+//
+#if HAS_CUTTER
+ #define SPINDLE_LASER_ENA_PIN PB11 // wifi:TX
+ #if ENABLED(SPINDLE_LASER_USE_PWM)
+ #define SPINDLE_LASER_PWM_PIN PB10 // wifi:RX-TIM2_CH3
+ // The PWM pin definition const PinMap PinMap_PWM[] in PeripheralPins.c must be compounded here
+ // See PWM_PIN(x) definition for details
+ #endif
+#endif
+
+//
+// Misc
+//
+#define BEEPER_PIN PA8
+
+//#define LED_PIN PG10
+#define PS_ON_PIN PG10 // Temporarily switch the machine with LED simulation
+
+#if ENABLED(TRONXY_BACKUP_POWER)
+ #define POWER_LOSS_PIN PF11 // Configure as drop-down input
+#else
+ #define POWER_LOSS_PIN PE1 // Output of LM393 comparator, configured as pullup
+#endif
+//#define POWER_LM393_PIN PE0 // +V for the LM393 comparator, configured as output high
+
+#if ENABLED(TFT_TRONXY_X5SA)
+ #error "TFT_TRONXY_X5SA is not yet supported."
+#endif
+
+#if 0
+
+//
+// TFT with FSMC interface
+//
+#if HAS_FSMC_TFT
+ #define TFT_RESET_PIN PB12
+ #define TFT_BACKLIGHT_PIN PG8
+
+ #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT
+ #define FSMC_DMA_DEV DMA2
+ #define FSMC_DMA_CHANNEL DMA_CH5
+
+ #define TFT_CS_PIN PG12
+ #define TFT_RS_PIN PG2
+
+ //#define TFT_WIDTH 480
+ //#define TFT_HEIGHT 320
+ //#define TFT_PIXEL_OFFSET_X 48
+ //#define TFT_PIXEL_OFFSET_Y 32
+ //#define TFT_DRIVER ILI9488
+ //#define TFT_BUFFER_SIZE 14400
+
+ #if NEED_TOUCH_PINS
+ #define TOUCH_CS_PIN PD11 // SPI1_NSS
+ #define TOUCH_SCK_PIN PB13 // SPI1_SCK
+ #define TOUCH_MISO_PIN PB14 // SPI1_MISO
+ #define TOUCH_MOSI_PIN PB15 // SPI1_MOSI
+ #endif
+
+ #if (LCD_CHIP_INDEX == 1 && (TRONXY_UI == 1 || TRONXY_UI == 2)) || LCD_CHIP_INDEX == 3
+ #define TOUCH_CALIBRATION_X -17181
+ #define TOUCH_CALIBRATION_Y 11434
+ #define TOUCH_OFFSET_X 501
+ #define TOUCH_OFFSET_Y -9
+ #elif LCD_CHIP_INDEX == 1 && TRONXY_UI == 4
+ #define TOUCH_CALIBRATION_X 11166
+ #define TOUCH_CALIBRATION_Y 17162
+ #define TOUCH_OFFSET_X -10
+ #define TOUCH_OFFSET_Y -16
+ #elif LCD_CHIP_INDEX == 4 && TRONXY_UI == 3
+ //#define TOUCH_CALIBRATION_X 8781
+ //#define TOUCH_CALIBRATION_Y 11773
+ //#define TOUCH_OFFSET_X -17
+ //#define TOUCH_OFFSET_Y -16
+ // Upside-down
+ #define TOUCH_CALIBRATION_X -8553
+ #define TOUCH_CALIBRATION_Y -11667
+ #define TOUCH_OFFSET_X 253
+ #define TOUCH_OFFSET_Y 331
+ #elif LCD_CHIP_INDEX == 2
+ #define TOUCH_CALIBRATION_X 17184
+ #define TOUCH_CALIBRATION_Y 10604
+ #define TOUCH_OFFSET_X -31
+ #define TOUCH_OFFSET_Y -29
+ #endif
+#endif
+
+#endif
+
+//
+// SD Card
+//
+#define SDIO_SUPPORT
+#define SD_DETECT_PIN -1 // PF0, but not connected
+#define SDIO_CLOCK 4500000
+#define SDIO_READ_RETRIES 16
+
+#define SDIO_D0_PIN PC8
+#define SDIO_D1_PIN PC9
+#define SDIO_D2_PIN PC10
+#define SDIO_D3_PIN PC11
+#define SDIO_CK_PIN PC12
+#define SDIO_CMD_PIN PD2
diff --git a/Marlin/src/pins/stm32g0/pins_BTT_EBB42_V1_1.h b/Marlin/src/pins/stm32g0/pins_BTT_EBB42_V1_1.h
new file mode 100644
index 00000000..fc2be540
--- /dev/null
+++ b/Marlin/src/pins/stm32g0/pins_BTT_EBB42_V1_1.h
@@ -0,0 +1,153 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2022 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 .
+ *
+ */
+#pragma once
+
+/** CAUTION **
+ * This board definition is to facilitate support for a Filament Extrusion
+ * devices, used to convert waste plastic into 3D printable filament.
+ * This board is NOT a general 3D printing controller; it is NOT supported
+ * as a toolboard via CANBUS (as it was originally designed) or any device
+ * that requires kinematics.
+ */
+
+#ifndef BOARD_INFO_NAME
+ #define BOARD_INFO_NAME "BTT EBB42 V1.1"
+#endif
+
+//
+// EEPROM
+//
+#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION)
+ #undef NO_EEPROM_SELECTED
+ #ifndef FLASH_EEPROM_EMULATION
+ #define FLASH_EEPROM_EMULATION
+ #endif
+ #define EEPROM_PAGE_SIZE (0x800UL) // 2K
+ #define EEPROM_START_ADDRESS (0x0801F800UL)
+ #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE
+#endif
+
+//#define USES_DIAG_JUMPERS
+
+// Ignore temp readings during development.
+//#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000
+
+#define LED_PIN PA13
+
+#define I2C_SDA_PIN PB4
+#define I2C_SCL_PIN PB3
+
+//
+// Servos
+//
+#define SERVO0_PIN PB9 // SERVOS
+
+//
+// Limit Switches
+//
+#if !HAS_WIRED_LCD
+ #define X_STOP_PIN PB6
+ #define Y_STOP_PIN PB5
+ #define Z_STOP_PIN PB7
+#endif
+
+//
+// Z Probe must be this pin
+//
+#define Z_MIN_PROBE_PIN PB8 // PROBE
+
+//
+// Steppers
+//
+#define X_ENABLE_PIN -1
+#define X_STEP_PIN PA10 // Unused. Assigned so Marlin will compile
+#define X_DIR_PIN -1
+
+#define Y_ENABLE_PIN -1
+#define Y_STEP_PIN PA10 // Unused. Assigned so Marlin will compile
+#define Y_DIR_PIN -1
+
+#define Z_ENABLE_PIN -1
+#define Z_STEP_PIN PA10 // Unused. Assigned so Marlin will compile
+#define Z_DIR_PIN -1
+
+#define E0_ENABLE_PIN PD2
+#define E0_STEP_PIN PD0
+#define E0_DIR_PIN PD1
+
+#if HAS_TMC_UART
+ /**
+ * TMC220x stepper drivers
+ * Hardware serial communication ports
+ */
+ //#define E0_HARDWARE_SERIAL MSerial4
+
+ // This is the stable default value after testing, but, higher UART rates could be configured, remeber to test the Steppers with the M122 command to check if everything works.
+ //#define TMC_BAUD_RATE 250000
+
+ #define E0_SERIAL_TX_PIN PA15
+ #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
+
+ // Reduce baud rate to improve software serial reliability
+ #define TMC_BAUD_RATE 19200
+
+ // Default TMC slave addresses
+ #ifndef E0_SLAVE_ADDRESS
+ #define E0_SLAVE_ADDRESS 0b00
+ #endif
+#endif
+
+//
+// Temperature Sensors
+//
+#define TEMP_0_PIN PA3 // Analog Input "TH0"
+
+// SPI for MAX Thermocouple
+// Uses a separate SPI bus
+
+#define TEMP_0_CS_PIN PA4 // GTR K-TEMP
+#define TEMP_0_SCK_PIN PA5 // SCK
+#define TEMP_0_MISO_PIN PA6 // MISO
+#define TEMP_0_MOSI_PIN PA7 // For MAX31865
+
+//
+// Heaters / Fans
+//
+#define HEATER_0_PIN PA2 // "HE"
+#define FAN_PIN PA0 // "FAN0"
+#define FAN1_PIN PA1 // "FAN1"
+
+//
+// Default NEOPIXEL_PIN
+//
+#ifndef NEOPIXEL_PIN
+ #define NEOPIXEL_PIN PD3 // LED driving pin
+#endif
+
+//
+// LCD / Controller
+//
+#if HAS_WIRED_LCD
+ #define BTN_EN1 PB7
+ #define BTN_EN2 PB5
+ #define BTN_ENC PB6
+#endif
diff --git a/buildroot/share/PlatformIO/boards/marlin_BTT_EBB42_V1_1.json b/buildroot/share/PlatformIO/boards/marlin_BTT_EBB42_V1_1.json
new file mode 100644
index 00000000..51b6b998
--- /dev/null
+++ b/buildroot/share/PlatformIO/boards/marlin_BTT_EBB42_V1_1.json
@@ -0,0 +1,47 @@
+{
+ "build": {
+ "core": "stm32",
+ "cpu": "cortex-m0plus",
+ "extra_flags": "-DSTM32G0xx -DSTM32G0B1xx",
+ "f_cpu": "64000000L",
+ "framework_extra_flags": {
+ "arduino": "-D__CORTEX_SC=0"
+ },
+ "mcu": "stm32g0b1cbt6",
+ "product_line": "STM32G0B1xx",
+ "variant": "MARLIN_BTT_EBB42_V1_1"
+ },
+ "debug": {
+ "default_tools": [
+ "stlink"
+ ],
+ "jlink_device": "STM32G0B1CB",
+ "onboard_tools": [
+ "stlink"
+ ],
+ "openocd_target": "stm32g0x",
+ "svd_path": "STM32G0B1.svd"
+ },
+ "frameworks": [
+ "arduino",
+ "cmsis",
+ "libopencm3",
+ "stm32cube",
+ "zephyr"
+ ],
+ "name": "STM32G0B1CB",
+ "upload": {
+ "maximum_ram_size": 147456,
+ "maximum_size": 131072,
+ "protocol": "stlink",
+ "protocols": [
+ "stlink",
+ "jlink",
+ "cmsis-dap",
+ "blackmagic",
+ "mbed"
+ ]
+ },
+ "url": "https://www.st.com/content/st_com/en/products/microcontrollers-microprocessors/stm32-32-bit-arm-cortex-mcus/stm32-mainstream-mcus/stm32g0-series/stm32g0x1.html",
+ "vendor": "ST"
+}
diff --git a/buildroot/share/PlatformIO/boards/marlin_MKS_SKIPR_V1.json b/buildroot/share/PlatformIO/boards/marlin_MKS_SKIPR_V1.json
new file mode 100644
index 00000000..7ca62db0
--- /dev/null
+++ b/buildroot/share/PlatformIO/boards/marlin_MKS_SKIPR_V1.json
@@ -0,0 +1,55 @@
+{
+ "build": {
+ "core": "stm32",
+ "cpu": "cortex-m4",
+ "extra_flags": "-DSTM32F4 -DSTM32F407xx",
+ "f_cpu": "168000000L",
+ "offset": "0xC000",
+ "hwids": [
+ [
+ "0x1EAF",
+ "0x0003"
+ ],
+ [
+ "0x0483",
+ "0x3748"
+ ]
+ ],
+ "mcu": "stm32f407vet6",
+ "product_line": "STM32F407xx",
+ "variant": "MARLIN_MKS_SKIPR_V1"
+ },
+ "debug": {
+ "default_tools": [
+ "stlink"
+ ],
+ "jlink_device": "STM32F407VE",
+ "openocd_extra_args": [
+ "-c",
+ "reset_config none"
+ ],
+ "openocd_target": "stm32f4x",
+ "svd_path": "STM32F40x.svd"
+ },
+ "frameworks": [
+ "arduino"
+ ],
+ "name": "STM32F407VE (128k RAM, 64k CCM RAM, 512k Flash",
+ "upload": {
+ "disable_flushing": false,
+ "maximum_ram_size": 131072,
+ "maximum_size": 524288,
+ "protocol": "stlink",
+ "protocols": [
+ "stlink",
+ "dfu",
+ "jlink"
+ ],
+ "offset_address": "0x0800C000",
+ "require_upload_port": false,
+ "use_1200bps_touch": false,
+ "wait_for_upload_port": false
+ },
+ "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f407ve.html",
+ "vendor": "ST"
+}
diff --git a/buildroot/share/PlatformIO/boards/marlin_STM32F401RC.json b/buildroot/share/PlatformIO/boards/marlin_STM32F401RC.json
new file mode 100644
index 00000000..f4242ccc
--- /dev/null
+++ b/buildroot/share/PlatformIO/boards/marlin_STM32F401RC.json
@@ -0,0 +1,38 @@
+{
+ "build": {
+ "core": "stm32",
+ "cpu": "cortex-m4",
+ "extra_flags": "-DSTM32F401xC -DSTM32F4xx",
+ "f_cpu": "84000000L",
+ "mcu": "stm32f401rct6",
+ "product_line": "STM32F401xC",
+ "variant": "MARLIN_F401RC"
+ },
+ "debug": {
+ "jlink_device": "STM32F401RC",
+ "openocd_target": "stm32f4x",
+ "svd_path": "STM32F401x.svd"
+ },
+ "frameworks": [
+ "arduino",
+ "cmsis",
+ "spl",
+ "stm32cube",
+ "libopencm3"
+ ],
+ "name": "STM32F401RC (64k RAM. 256k Flash)",
+ "upload": {
+ "maximum_ram_size": 65536,
+ "maximum_size": 262144,
+ "protocol": "serial",
+ "protocols": [
+ "blackmagic",
+ "dfu",
+ "jlink",
+ "serial",
+ "stlink"
+ ]
+ },
+ "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f401rc.html",
+ "vendor": "Generic"
+}
diff --git a/buildroot/share/PlatformIO/boards/marlin_STM32F407ZE.json b/buildroot/share/PlatformIO/boards/marlin_STM32F407ZE.json
new file mode 100644
index 00000000..ce09de53
--- /dev/null
+++ b/buildroot/share/PlatformIO/boards/marlin_STM32F407ZE.json
@@ -0,0 +1,50 @@
+{
+ "build": {
+ "cpu": "cortex-m4",
+ "extra_flags": "-DSTM32F4 -DSTM32F407xx",
+ "f_cpu": "168000000L",
+ "mcu": "stm32f407zgt6",
+ "product_line": "STM32F407xx",
+ "variant": "MARLIN_F407ZE"
+ },
+ "connectivity": [
+ "can"
+ ],
+ "debug": {
+ "default_tools": [
+ "stlink"
+ ],
+ "jlink_device": "STM32F407ZE",
+ "onboard_tools": [
+ "stlink"
+ ],
+ "openocd_board": "stm32f407",
+ "openocd_target": "stm32f4x",
+ "svd_path": "STM32F407x.svd"
+ },
+ "frameworks": [
+ "arduino",
+ "cmsis",
+ "mbed",
+ "stm32cube",
+ "libopencm3",
+ "zephyr"
+ ],
+ "name": "STM32F407ZE (128k RAM, 64k CCM RAM, 512k Flash",
+ "upload": {
+ "disable_flushing": false,
+ "maximum_ram_size": 131072,
+ "maximum_size": 524288,
+ "protocol": "stlink",
+ "protocols": [
+ "stlink",
+ "dfu",
+ "jlink"
+ ],
+ "require_upload_port": true,
+ "use_1200bps_touch": false,
+ "wait_for_upload_port": false
+ },
+ "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f407-417.html",
+ "vendor": "ST"
+}
diff --git a/buildroot/share/PlatformIO/boards/marlin_STM32F446ZET_tronxy.json b/buildroot/share/PlatformIO/boards/marlin_STM32F446ZET_tronxy.json
new file mode 100644
index 00000000..bd129a70
--- /dev/null
+++ b/buildroot/share/PlatformIO/boards/marlin_STM32F446ZET_tronxy.json
@@ -0,0 +1,35 @@
+{
+ "build": {
+ "cpu": "cortex-m4",
+ "extra_flags": "-DSTM32F446xx",
+ "f_cpu": "180000000L",
+ "mcu": "stm32f446zet6",
+ "variant": "MARLIN_F446Zx_TRONXY"
+ },
+ "connectivity": [
+ "can"
+ ],
+ "debug": {
+ "jlink_device": "STM32F446ZE",
+ "openocd_target": "stm32f4x",
+ "svd_path": "STM32F446x.svd"
+ },
+ "frameworks": [
+ "arduino",
+ "stm32cube"
+ ],
+ "name": "STM32F446ZE (128k RAM. 512k Flash)",
+ "upload": {
+ "maximum_ram_size": 131072,
+ "maximum_size": 524288,
+ "protocol": "stlink",
+ "protocols": [
+ "jlink",
+ "stlink",
+ "blackmagic",
+ "serial"
+ ]
+ },
+ "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f446.html",
+ "vendor": "Generic"
+}
diff --git a/buildroot/share/PlatformIO/boards/marlin_opulo_lumen_rev4.json b/buildroot/share/PlatformIO/boards/marlin_opulo_lumen_rev4.json
new file mode 100644
index 00000000..ef5ebfa5
--- /dev/null
+++ b/buildroot/share/PlatformIO/boards/marlin_opulo_lumen_rev4.json
@@ -0,0 +1,51 @@
+{
+ "build": {
+ "core": "stm32",
+ "cpu": "cortex-m4",
+ "extra_flags": "-DSTM32F407xx",
+ "f_cpu": "168000000L",
+ "hwids": [
+ [
+ "0x0483",
+ "0xdf11"
+ ],
+ [
+ "0x1EAF",
+ "0x0003"
+ ],
+ [
+ "0x0483",
+ "0x3748"
+ ]
+ ],
+ "mcu": "stm32f407vet6",
+ "variant": "MARLIN_F407VE"
+ },
+ "debug": {
+ "jlink_device": "STM32F407VE",
+ "openocd_target": "stm32f4x",
+ "svd_path": "STM32F40x.svd"
+ },
+ "frameworks": [
+ "arduino",
+ "stm32cube"
+ ],
+ "name": "STM32F407VE (192k RAM. 512k Flash)",
+ "upload": {
+ "disable_flushing": false,
+ "maximum_ram_size": 131072,
+ "maximum_size": 524288,
+ "protocol": "dfu",
+ "protocols": [
+ "stlink",
+ "dfu",
+ "jlink",
+ "blackmagic"
+ ],
+ "require_upload_port": true,
+ "use_1200bps_touch": false,
+ "wait_for_upload_port": false
+ },
+ "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f407ve.html",
+ "vendor": "Generic"
+}
diff --git a/buildroot/share/PlatformIO/scripts/SAMD21_minitronics20.py b/buildroot/share/PlatformIO/scripts/SAMD21_minitronics20.py
new file mode 100644
index 00000000..81099f58
--- /dev/null
+++ b/buildroot/share/PlatformIO/scripts/SAMD21_minitronics20.py
@@ -0,0 +1,19 @@
+#
+# SAMD21_minitronics20.py
+# Customizations for env:SAMD21_minitronics20
+#
+import pioutil
+if pioutil.is_pio_build():
+ from os.path import join, isfile
+ import shutil
+
+ Import("env")
+
+ mf = env["MARLIN_FEATURES"]
+ rxBuf = mf["RX_BUFFER_SIZE"] if "RX_BUFFER_SIZE" in mf else "0"
+ txBuf = mf["TX_BUFFER_SIZE"] if "TX_BUFFER_SIZE" in mf else "0"
+
+ serialBuf = str(max(int(rxBuf), int(txBuf), 350))
+
+ build_flags = env.get('BUILD_FLAGS')
+ env.Replace(BUILD_FLAGS=build_flags)
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BTT_EBB42_V1_1/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_BTT_EBB42_V1_1/PeripheralPins.c
new file mode 100644
index 00000000..a8a98fc6
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_BTT_EBB42_V1_1/PeripheralPins.c
@@ -0,0 +1,377 @@
+/*
+ *******************************************************************************
+ * Copyright (c) 2020, STMicroelectronics
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ *******************************************************************************
+ */
+/*
+ * Automatically generated from STM32G0B1C(B-C-E)Tx.xml, STM32G0B1C(B-C-E)Ux.xml
+ * STM32G0C1C(C-E)Tx.xml, STM32G0C1C(C-E)Ux.xml
+ * CubeMX DB release 6.0.60
+ */
+#if !defined(CUSTOM_PERIPHERAL_PINS)
+#include "Arduino.h"
+#include "PeripheralPins.h"
+
+/* =====
+ * Notes:
+ * - The pins mentioned Px_y_ALTz are alternative possibilities which use other
+ * HW peripheral instances. You can use them the same way as any other "normal"
+ * pin (i.e. analogWrite(PA7_ALT1, 128);).
+ *
+ * - Commented lines are alternative possibilities which are not used per default.
+ * If you change them, you will have to know what you do
+ * =====
+ */
+
+//*** ADC ***
+
+#ifdef HAL_ADC_MODULE_ENABLED
+WEAK const PinMap PinMap_ADC[] = {
+ {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0
+ {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1
+ {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2
+ {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3
+ {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4
+ {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5
+ {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6
+ {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7
+ {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8
+ {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9
+ {PB_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10
+ {PB_10, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11
+ {PB_11, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15
+ {PB_12, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 16, 0)}, // ADC1_IN16
+ {NC, NP, 0}
+};
+#endif
+
+//*** DAC ***
+
+#ifdef HAL_DAC_MODULE_ENABLED
+WEAK const PinMap PinMap_DAC[] = {
+ {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC1_OUT1
+ {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC1_OUT2
+ {NC, NP, 0}
+};
+#endif
+
+//*** I2C ***
+
+#ifdef HAL_I2C_MODULE_ENABLED
+WEAK const PinMap PinMap_I2C_SDA[] = {
+ {PA_6, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF8_I2C2)},
+ {PA_6_ALT1, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF9_I2C3)},
+ {PA_10, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C1)},
+ {PA_10_ALT1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF8_I2C2)},
+ {PA_10_R, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C1)},
+ {PA_10_R_ALT1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF8_I2C2)},
+ {PA_12, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C2)},
+ {PB_4, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF8_I2C2)},
+ {PB_4_ALT1, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C3)},
+ {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C1)},
+ {PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C1)},
+ {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C2)},
+ {PB_14, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C2)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_I2C_MODULE_ENABLED
+WEAK const PinMap PinMap_I2C_SCL[] = {
+ {PA_7, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF8_I2C2)},
+ {PA_7_ALT1, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF9_I2C3)},
+ {PA_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C1)},
+ {PA_9_ALT1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF8_I2C2)},
+ {PA_9_R, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C1)},
+ {PA_9_R_ALT1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF8_I2C2)},
+ {PA_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C2)},
+ {PB_3, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF8_I2C2)},
+ {PB_3_ALT1, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C3)},
+ {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C1)},
+ {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C1)},
+ {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C2)},
+ {PB_13, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C2)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** TIM ***
+
+#ifdef HAL_TIM_MODULE_ENABLED
+WEAK const PinMap PinMap_TIM[] = {
+ {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 1, 0)}, // TIM2_CH1
+ {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 2, 0)}, // TIM2_CH2
+ {PA_1_ALT1, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_TIM15, 1, 1)}, // TIM15_CH1N
+ {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 3, 0)}, // TIM2_CH3
+ {PA_2_ALT1, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_TIM15, 1, 0)}, // TIM15_CH1
+ {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 4, 0)}, // TIM2_CH4
+ {PA_3_ALT1, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_TIM15, 2, 0)}, // TIM15_CH2
+ {PA_4, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM14, 1, 0)}, // TIM14_CH1
+ {PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 1, 0)}, // TIM2_CH1
+ {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 1, 0)}, // TIM3_CH1
+ {PA_6_ALT1, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_TIM16, 1, 0)}, // TIM16_CH1
+ {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 1, 1)}, // TIM1_CH1N
+ {PA_7_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 2, 0)}, // TIM3_CH2
+ {PA_7_ALT2, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM14, 1, 0)}, // TIM14_CH1
+ {PA_7_ALT3, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_TIM17, 1, 0)}, // TIM17_CH1
+ {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 1, 0)}, // TIM1_CH1
+ {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 2, 0)}, // TIM1_CH2
+ {PA_9_R, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 2, 0)}, // TIM1_CH2
+ {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 3, 0)}, // TIM1_CH3
+ {PA_10_R, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 3, 0)}, // TIM1_CH3
+ {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 4, 0)}, // TIM1_CH4
+ {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 1, 0)}, // TIM2_CH1
+ {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 2, 1)}, // TIM1_CH2N
+ {PB_0_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 3, 0)}, // TIM3_CH3
+ {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 3, 1)}, // TIM1_CH3N
+ {PB_1_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 4, 0)}, // TIM3_CH4
+ {PB_1_ALT2, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_TIM14, 1, 0)}, // TIM14_CH1
+ {PB_3, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
+ {PB_3_ALT1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 2, 0)}, // TIM2_CH2
+ {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 1, 0)}, // TIM3_CH1
+ {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 2, 0)}, // TIM3_CH2
+ {PB_6, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
+ {PB_6_ALT1, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM4, 1, 0)}, // TIM4_CH1
+ {PB_6_ALT2, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM16, 1, 1)}, // TIM16_CH1N
+ {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM4, 2, 0)}, // TIM4_CH2
+ {PB_7_ALT1, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM17, 1, 1)}, // TIM17_CH1N
+ {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM4, 3, 0)}, // TIM4_CH3
+ {PB_8_ALT1, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM16, 1, 0)}, // TIM16_CH1
+ {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM4, 4, 0)}, // TIM4_CH4
+ {PB_9_ALT1, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM17, 1, 0)}, // TIM17_CH1
+ {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 3, 0)}, // TIM2_CH3
+ {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 4, 0)}, // TIM2_CH4
+ {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 1, 1)}, // TIM1_CH1N
+ {PB_13_ALT1, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_TIM15, 1, 1)}, // TIM15_CH1N
+ {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 2, 1)}, // TIM1_CH2N
+ {PB_14_ALT1, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_TIM15, 1, 0)}, // TIM15_CH1
+ {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 3, 1)}, // TIM1_CH3N
+ {PB_15_ALT1, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 1, 1)}, // TIM15_CH1N
+ {PB_15_ALT2, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_TIM15, 2, 0)}, // TIM15_CH2
+ {PC_6, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 3, 0)}, // TIM2_CH3
+ {PC_6_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 1, 0)}, // TIM3_CH1
+ {PC_7, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 4, 0)}, // TIM2_CH4
+ {PC_7_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 2, 0)}, // TIM3_CH2
+ {PD_0, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM16, 1, 0)}, // TIM16_CH1
+ {PD_1, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM17, 1, 0)}, // TIM17_CH1
+ {PD_2, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 1, 1)}, // TIM1_CH1N
+ {PD_3, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 2, 1)}, // TIM1_CH2N
+ {PF_0, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM14, 1, 0)}, // TIM14_CH1
+ {PF_1, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM15, 1, 1)}, // TIM15_CH1N
+ {NC, NP, 0}
+};
+#endif
+
+//*** UART ***
+
+#ifdef HAL_UART_MODULE_ENABLED
+WEAK const PinMap PinMap_UART_TX[] = {
+ {PA_0, USART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART4)},
+ {PA_2, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_LPUART1)},
+ {PA_2_ALT1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART2)},
+ {PA_4, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_USART6)},
+ {PA_5, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)},
+ {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART1)},
+ {PA_9_R, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART1)},
+ {PA_14, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_LPUART2)},
+ {PA_14_ALT1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART2)},
+ {PB_0, USART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART5)},
+ {PB_2, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)},
+ {PB_3, USART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_USART5)},
+ {PB_6, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_LPUART2)},
+ {PB_6_ALT1, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_USART1)},
+ {PB_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)},
+ {PB_8_ALT1, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
+ {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)},
+ {PB_11, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_LPUART1)},
+ {PC_6, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART2)},
+ {PD_3, USART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_USART5)},
+ {PF_2, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_LPUART2)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_UART_MODULE_ENABLED
+WEAK const PinMap PinMap_UART_RX[] = {
+ {PA_1, USART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART4)},
+ {PA_3, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_LPUART1)},
+ {PA_3_ALT1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART2)},
+ {PA_5, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_USART6)},
+ {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART1)},
+ {PA_10_R, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART1)},
+ {PA_13, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_LPUART2)},
+ {PA_15, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART2)},
+ {PB_0, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)},
+ {PB_1, USART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART5)},
+ {PB_4, USART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_USART5)},
+ {PB_7, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_LPUART2)},
+ {PB_7_ALT1, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_USART1)},
+ {PB_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)},
+ {PB_9_ALT1, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
+ {PB_10, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_LPUART1)},
+ {PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)},
+ {PC_7, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART2)},
+ {PD_2, USART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_USART5)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_UART_MODULE_ENABLED
+WEAK const PinMap PinMap_UART_RTS[] = {
+ {PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART2)},
+ {PA_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_USART6)},
+ {PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART1)},
+ {PA_15, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_USART3)},
+ {PA_15_ALT1, USART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART4)},
+ {PB_1, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_LPUART1)},
+ {PB_1_ALT1, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_LPUART2)},
+ {PB_1_ALT2, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)},
+ {PB_3, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART1)},
+ {PB_5, USART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART5)},
+ {PB_12, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_LPUART1)},
+ {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)},
+ {PB_14_ALT1, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
+ {PD_2, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_USART3)},
+ {PF_2, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART2)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_UART_MODULE_ENABLED
+WEAK const PinMap PinMap_UART_CTS[] = {
+ {PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART2)},
+ {PA_6, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_LPUART1)},
+ {PA_6_ALT1, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)},
+ {PA_6_ALT2, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_USART6)},
+ {PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART1)},
+ {PB_0, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_LPUART2)},
+ {PB_4, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART1)},
+ {PB_6, USART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART5)},
+ {PB_7, USART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART4)},
+ {PB_13, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_LPUART1)},
+ {PB_13_ALT1, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)},
+ {PB_15, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
+ {PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_USART2)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** SPI ***
+
+#ifdef HAL_SPI_MODULE_ENABLED
+WEAK const PinMap PinMap_SPI_MOSI[] = {
+ {PA_2, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)},
+ {PA_4, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI2)},
+ {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)},
+ {PA_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI2)},
+ {PA_10_R, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI2)},
+ {PA_12, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)},
+ {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)},
+ {PB_5_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_SPI3)},
+ {PB_7, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI2)},
+ {PB_11, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI2)},
+ {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI2)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_SPI_MODULE_ENABLED
+WEAK const PinMap PinMap_SPI_MISO[] = {
+ {PA_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI2)},
+ {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)},
+ {PA_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_SPI2)},
+ {PA_9_R, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_SPI2)},
+ {PA_11, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)},
+ {PB_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI2)},
+ {PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)},
+ {PB_4_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_SPI3)},
+ {PB_6, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_SPI2)},
+ {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI2)},
+ {PD_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI2)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_SPI_MODULE_ENABLED
+WEAK const PinMap PinMap_SPI_SCLK[] = {
+ {PA_0, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI2)},
+ {PA_1, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)},
+ {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)},
+ {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)},
+ {PB_3_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_SPI3)},
+ {PB_8, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI2)},
+ {PB_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI2)},
+ {PD_1, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI2)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_SPI_MODULE_ENABLED
+WEAK const PinMap PinMap_SPI_SSEL[] = {
+ {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)},
+ {PA_4_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_SPI3)},
+ {PA_8, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI2)},
+ {PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)},
+ {PA_15_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_SPI3)},
+ {PB_0, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)},
+ {PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI2)},
+ {PD_0, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI2)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** FDCAN ***
+
+#ifdef HAL_FDCAN_MODULE_ENABLED
+WEAK const PinMap PinMap_CAN_RD[] = {
+ {PA_11, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN1)},
+ {PB_0, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN2)},
+ {PB_5, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN2)},
+ {PB_8, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN1)},
+ {PB_12, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN2)},
+ {PD_0, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN1)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_FDCAN_MODULE_ENABLED
+WEAK const PinMap PinMap_CAN_TD[] = {
+ {PA_12, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN1)},
+ {PB_1, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN2)},
+ {PB_6, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN2)},
+ {PB_9, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN1)},
+ {PB_13, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN2)},
+ {PD_1, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN1)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** No ETHERNET ***
+
+//*** No QUADSPI ***
+
+//*** USB ***
+
+#if defined(HAL_PCD_MODULE_ENABLED) || defined(HAL_HCD_MODULE_ENABLED)
+WEAK const PinMap PinMap_USB_DRD_FS[] = {
+ {PA_4, USB_DRD_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_USB)}, // USB_NOE
+ {PA_11, USB_DRD_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_DM
+ {PA_12, USB_DRD_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_DP
+ {PA_13, USB_DRD_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_USB)}, // USB_NOE
+ {PA_15, USB_DRD_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_USB)}, // USB_NOE
+ {NC, NP, 0}
+};
+#endif
+
+//*** No SD ***
+
+#endif /* !CUSTOM_PERIPHERAL_PINS */
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BTT_EBB42_V1_1/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_BTT_EBB42_V1_1/PinNamesVar.h
new file mode 100644
index 00000000..4e91fa32
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_BTT_EBB42_V1_1/PinNamesVar.h
@@ -0,0 +1,78 @@
+/* Remap pin name */
+PA_9_R = PA_9 | PREMAP,
+PA_10_R = PA_10 | PREMAP,
+
+/* Alternate pin name */
+PA_1_ALT1 = PA_1 | ALT1,
+PA_2_ALT1 = PA_2 | ALT1,
+PA_3_ALT1 = PA_3 | ALT1,
+PA_4_ALT1 = PA_4 | ALT1,
+PA_6_ALT1 = PA_6 | ALT1,
+PA_6_ALT2 = PA_6 | ALT2,
+PA_7_ALT1 = PA_7 | ALT1,
+PA_7_ALT2 = PA_7 | ALT2,
+PA_7_ALT3 = PA_7 | ALT3,
+PA_9_ALT1 = PA_9 | ALT1,
+PA_9_R_ALT1 = PA_9_R | ALT1,
+PA_10_ALT1 = PA_10 | ALT1,
+PA_10_R_ALT1 = PA_10_R | ALT1,
+PA_14_ALT1 = PA_14 | ALT1,
+PA_15_ALT1 = PA_15 | ALT1,
+PB_0_ALT1 = PB_0 | ALT1,
+PB_1_ALT1 = PB_1 | ALT1,
+PB_1_ALT2 = PB_1 | ALT2,
+PB_3_ALT1 = PB_3 | ALT1,
+PB_4_ALT1 = PB_4 | ALT1,
+PB_5_ALT1 = PB_5 | ALT1,
+PB_6_ALT1 = PB_6 | ALT1,
+PB_6_ALT2 = PB_6 | ALT2,
+PB_7_ALT1 = PB_7 | ALT1,
+PB_8_ALT1 = PB_8 | ALT1,
+PB_9_ALT1 = PB_9 | ALT1,
+PB_13_ALT1 = PB_13 | ALT1,
+PB_14_ALT1 = PB_14 | ALT1,
+PB_15_ALT1 = PB_15 | ALT1,
+PB_15_ALT2 = PB_15 | ALT2,
+PC_6_ALT1 = PC_6 | ALT1,
+PC_7_ALT1 = PC_7 | ALT1,
+
+/* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = PC_13,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = PA_2,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = PB_5,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
+
+/* USB */
+#ifdef USBCON
+ USB_DM = PA_11,
+ USB_DP = PA_12,
+ #ifdef USB_NOE_PA_4
+ USB_NOE = PA_4,
+ #endif
+ #ifdef USB_NOE_PA_13
+ USB_NOE = PA_13,
+ #endif
+ #ifdef USB_NOE_PA_15
+ USB_NOE = PA_15,
+ #endif
+#endif
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BTT_EBB42_V1_1/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_BTT_EBB42_V1_1/ldscript.ld
new file mode 100644
index 00000000..ce97a9f4
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_BTT_EBB42_V1_1/ldscript.ld
@@ -0,0 +1,185 @@
+/*
+******************************************************************************
+**
+** @file : LinkerScript.ld
+**
+** @author : Auto-generated by STM32CubeIDE
+**
+** @brief : Linker script for STM32G0B1CBTx Device from STM32G0 series
+** 128Kbytes FLASH
+** 144Kbytes RAM
+**
+** Set heap size, stack size and stack location according
+** to application requirements.
+**
+** Set memory bank area and size if external memory is used
+**
+** Target : STMicroelectronics STM32
+**
+** Distribution: The file is distributed as is, without any warranty
+** of any kind.
+**
+******************************************************************************
+** @attention
+**
+** Copyright (c) 2022 STMicroelectronics.
+** All rights reserved.
+**
+** This software is licensed under terms that can be found in the LICENSE file
+** in the root directory of this software component.
+** If no LICENSE file comes with this software, it is provided AS-IS.
+**
+******************************************************************************
+*/
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = ORIGIN(RAM) + LENGTH(RAM); /* end of "RAM" Ram type memory */
+
+_Min_Heap_Size = 0x200; /* required amount of heap */
+_Min_Stack_Size = 0x400; /* required amount of stack */
+
+/* Memories definition */
+MEMORY
+{
+ RAM (xrw) : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE
+ FLASH (rx) : ORIGIN = 0x8000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET
+}
+
+/* Sections */
+SECTIONS
+{
+ /* The startup code into "FLASH" Rom type memory */
+ .isr_vector :
+ {
+ . = ALIGN(4);
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(4);
+ } >FLASH
+
+ /* The program code and other data into "FLASH" Rom type memory */
+ .text :
+ {
+ . = ALIGN(4);
+ *(.text) /* .text sections (code) */
+ *(.text*) /* .text* sections (code) */
+ *(.glue_7) /* glue arm to thumb code */
+ *(.glue_7t) /* glue thumb to arm code */
+ *(.eh_frame)
+
+ KEEP (*(.init))
+ KEEP (*(.fini))
+
+ . = ALIGN(4);
+ _etext = .; /* define a global symbols at end of code */
+ } >FLASH
+
+ /* Constant data into "FLASH" Rom type memory */
+ .rodata :
+ {
+ . = ALIGN(4);
+ *(.rodata) /* .rodata sections (constants, strings, etc.) */
+ *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
+ . = ALIGN(4);
+ } >FLASH
+
+ .ARM.extab : {
+ . = ALIGN(4);
+ *(.ARM.extab* .gnu.linkonce.armextab.*)
+ . = ALIGN(4);
+ } >FLASH
+
+ .ARM : {
+ . = ALIGN(4);
+ __exidx_start = .;
+ *(.ARM.exidx*)
+ __exidx_end = .;
+ . = ALIGN(4);
+ } >FLASH
+
+ .preinit_array :
+ {
+ . = ALIGN(4);
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array*))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ . = ALIGN(4);
+ } >FLASH
+
+ .init_array :
+ {
+ . = ALIGN(4);
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array*))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ . = ALIGN(4);
+ } >FLASH
+
+ .fini_array :
+ {
+ . = ALIGN(4);
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT(.fini_array.*)))
+ KEEP (*(.fini_array*))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ . = ALIGN(4);
+ } >FLASH
+
+ /* Used by the startup to initialize data */
+ _sidata = LOADADDR(.data);
+
+ /* Initialized data sections into "RAM" Ram type memory */
+ .data :
+ {
+ . = ALIGN(4);
+ _sdata = .; /* create a global symbol at data start */
+ *(.data) /* .data sections */
+ *(.data*) /* .data* sections */
+ *(.RamFunc) /* .RamFunc sections */
+ *(.RamFunc*) /* .RamFunc* sections */
+
+ . = ALIGN(4);
+ _edata = .; /* define a global symbol at data end */
+
+ } >RAM AT> FLASH
+
+ /* Uninitialized data section into "RAM" Ram type memory */
+ . = ALIGN(4);
+ .bss :
+ {
+ /* This is used by the startup in order to initialize the .bss section */
+ _sbss = .; /* define a global symbol at bss start */
+ __bss_start__ = _sbss;
+ *(.bss)
+ *(.bss*)
+ *(COMMON)
+
+ . = ALIGN(4);
+ _ebss = .; /* define a global symbol at bss end */
+ __bss_end__ = _ebss;
+ } >RAM
+
+ /* User_heap_stack section, used to check that there is enough "RAM" Ram type memory left */
+ ._user_heap_stack :
+ {
+ . = ALIGN(8);
+ PROVIDE ( end = . );
+ PROVIDE ( _end = . );
+ . = . + _Min_Heap_Size;
+ . = . + _Min_Stack_Size;
+ . = ALIGN(8);
+ } >RAM
+
+ /* Remove information from the compiler libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+}
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BTT_EBB42_V1_1/variant_MARLIN_BTT_EBB42_V1_1.cpp b/buildroot/share/PlatformIO/variants/MARLIN_BTT_EBB42_V1_1/variant_MARLIN_BTT_EBB42_V1_1.cpp
new file mode 100644
index 00000000..3bb5f755
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_BTT_EBB42_V1_1/variant_MARLIN_BTT_EBB42_V1_1.cpp
@@ -0,0 +1,138 @@
+/*
+ *******************************************************************************
+ * Copyright (c) 2021, STMicroelectronics
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ *******************************************************************************
+ */
+
+//#if defined(ARDUINO_EBB42_V1_1)
+#include "pins_arduino.h"
+
+// Pin number
+const PinName digitalPin[] = {
+ PA_0, // D0/A0
+ PA_1, // D1/A1
+ PA_2, // D2/A2
+ PA_3, // D3/A3
+ PA_4, // D4/A4
+ PA_5, // D5/A5
+ PA_6, // D6/A6
+ PA_7, // D7/A7
+ PA_8, // D8
+ PA_9, // D9
+ PA_10, // D10
+ PA_11, // D11
+ PA_12, // D12
+ PA_13, // D13
+ PA_14, // D14
+ PA_15, // D15
+ PB_0, // D16/A8
+ PB_1, // D17/A9
+ PB_2, // D18/A10
+ PB_3, // D19
+ PB_4, // D20
+ PB_5, // D21
+ PB_6, // D22
+ PB_7, // D23
+ PB_8, // D24
+ PB_9, // D25
+ PB_10, // D26/A11
+ PB_11, // D27/A12
+ PB_12, // D28/A13
+ PB_13, // D29
+ PB_14, // D30
+ PB_15, // D31
+ PC_6, // D32
+ PC_7, // D33
+ PC_13, // D34
+ PC_14, // D35
+ PC_15, // D36
+ PD_0, // D37
+ PD_1, // D38
+ PD_2, // D39
+ PD_3, // D40
+ PF_0, // D41
+ PF_1, // D42
+ PF_2, // D43
+ PA_9_R, // D44
+ PA_10_R // D45
+};
+
+// Analog (Ax) pin number array
+const uint32_t analogInputPin[] = {
+ 0, // A0, PA0
+ 1, // A1, PA1
+ 2, // A2, PA2
+ 3, // A3, PA3
+ 4, // A4, PA4
+ 5, // A5, PA5
+ 6, // A6, PA6
+ 7, // A7, PA7
+ 16, // A8, PB0
+ 17, // A9, PB1
+ 18, // A10, PB2
+ 26, // A11, PB10
+ 27, // A12, PB11
+ 28 // A13, PB12
+};
+
+// ----------------------------------------------------------------------------
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @brief System Clock Configuration
+ * @param None
+ * @retval None
+ */
+WEAK void SystemClock_Config(void)
+{
+ RCC_OscInitTypeDef RCC_OscInitStruct = {};
+ RCC_ClkInitTypeDef RCC_ClkInitStruct = {};
+
+ /** Configure the main internal regulator output voltage
+ */
+ HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1);
+
+ /** Initializes the RCC Oscillators according to the specified parameters
+ * in the RCC_OscInitTypeDef structure.
+ */
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE | RCC_OSCILLATORTYPE_HSI48;
+ RCC_OscInitStruct.HSEState = RCC_HSE_ON;
+ RCC_OscInitStruct.HSI48State = RCC_HSI48_ON;
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
+ RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
+ RCC_OscInitStruct.PLL.PLLM = RCC_PLLM_DIV1;
+ RCC_OscInitStruct.PLL.PLLN = 16;
+ RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
+ RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV2;
+ RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2;
+ if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
+ Error_Handler();
+ }
+
+ /** Initializes the CPU, AHB and APB buses clocks
+ */
+ RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK
+ | RCC_CLOCKTYPE_PCLK1;
+ RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
+ RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
+ RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
+
+ if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) {
+ Error_Handler();
+ }
+}
+
+#ifdef __cplusplus
+}
+#endif
+//#endif /* ARDUINO_EBB42_V1_1 */
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BTT_EBB42_V1_1/variant_MARLIN_BTT_EBB42_V1_1.h b/buildroot/share/PlatformIO/variants/MARLIN_BTT_EBB42_V1_1/variant_MARLIN_BTT_EBB42_V1_1.h
new file mode 100644
index 00000000..ff75bc1e
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_BTT_EBB42_V1_1/variant_MARLIN_BTT_EBB42_V1_1.h
@@ -0,0 +1,198 @@
+/*
+ *******************************************************************************
+ * Copyright (c) 2020, STMicroelectronics
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ *******************************************************************************
+ */
+#pragma once
+
+/*----------------------------------------------------------------------------
+ * STM32 pins number
+ *----------------------------------------------------------------------------*/
+#define PA0 PIN_A0
+#define PA1 PIN_A1
+#define PA2 PIN_A2
+#define PA3 PIN_A3
+#define PA4 PIN_A4
+#define PA5 PIN_A5
+#define PA6 PIN_A6
+#define PA7 PIN_A7
+#define PA8 8
+#define PA9 9
+#define PA10 10
+#define PA11 11
+#define PA12 12
+#define PA13 13
+#define PA14 14
+#define PA15 15
+#define PB0 PIN_A8
+#define PB1 PIN_A9
+#define PB2 PIN_A10
+#define PB3 19
+#define PB4 20
+#define PB5 21
+#define PB6 22
+#define PB7 23
+#define PB8 24
+#define PB9 25
+#define PB10 PIN_A11
+#define PB11 PIN_A12
+#define PB12 PIN_A13
+#define PB13 29
+#define PB14 30
+#define PB15 31
+#define PC6 32
+#define PC7 33
+#define PC13 34
+#define PC14 35
+#define PC15 36
+#define PD0 37
+#define PD1 38
+#define PD2 39
+#define PD3 40
+#define PF0 41
+#define PF1 42
+#define PF2 43
+#define PA9_R 44
+#define PA10_R 45
+
+// Alternate pins number
+#define PA1_ALT1 (PA1 | ALT1)
+#define PA2_ALT1 (PA2 | ALT1)
+#define PA3_ALT1 (PA3 | ALT1)
+#define PA4_ALT1 (PA4 | ALT1)
+#define PA6_ALT1 (PA6 | ALT1)
+#define PA6_ALT2 (PA6 | ALT2)
+#define PA7_ALT1 (PA7 | ALT1)
+#define PA7_ALT2 (PA7 | ALT2)
+#define PA7_ALT3 (PA7 | ALT3)
+#define PA9_ALT1 (PA9 | ALT1)
+#define PA9_R_ALT1 (PA9_R | ALT1)
+#define PA10_ALT1 (PA10 | ALT1)
+#define PA10_R_ALT1 (PA10_R | ALT1)
+#define PA14_ALT1 (PA14 | ALT1)
+#define PA15_ALT1 (PA15 | ALT1)
+#define PB0_ALT1 (PB0 | ALT1)
+#define PB1_ALT1 (PB1 | ALT1)
+#define PB1_ALT2 (PB1 | ALT2)
+#define PB3_ALT1 (PB3 | ALT1)
+#define PB4_ALT1 (PB4 | ALT1)
+#define PB5_ALT1 (PB5 | ALT1)
+#define PB6_ALT1 (PB6 | ALT1)
+#define PB6_ALT2 (PB6 | ALT2)
+#define PB7_ALT1 (PB7 | ALT1)
+#define PB8_ALT1 (PB8 | ALT1)
+#define PB9_ALT1 (PB9 | ALT1)
+#define PB13_ALT1 (PB13 | ALT1)
+#define PB14_ALT1 (PB14 | ALT1)
+#define PB15_ALT1 (PB15 | ALT1)
+#define PB15_ALT2 (PB15 | ALT2)
+#define PC6_ALT1 (PC6 | ALT1)
+#define PC7_ALT1 (PC7 | ALT1)
+
+#define NUM_DIGITAL_PINS 46
+#define NUM_REMAP_PINS 2
+#define NUM_ANALOG_INPUTS 14
+
+// On-board LED pin number
+#ifndef LED_BUILTIN
+ #define LED_BUILTIN PNUM_NOT_DEFINED
+#endif
+
+// On-board user button
+#ifndef USER_BTN
+ #define USER_BTN PNUM_NOT_DEFINED
+#endif
+
+// SPI definitions
+#ifndef PIN_SPI_SS
+ #define PIN_SPI_SS PA4
+#endif
+#ifndef PIN_SPI_SS1
+ #define PIN_SPI_SS1 PA15
+#endif
+#ifndef PIN_SPI_SS2
+ #define PIN_SPI_SS2 PB0
+#endif
+#ifndef PIN_SPI_SS3
+ #define PIN_SPI_SS3 PNUM_NOT_DEFINED
+#endif
+#ifndef PIN_SPI_MOSI
+ #define PIN_SPI_MOSI PA2
+#endif
+#ifndef PIN_SPI_MISO
+ #define PIN_SPI_MISO PA6
+#endif
+#ifndef PIN_SPI_SCK
+ #define PIN_SPI_SCK PA1
+#endif
+
+// I2C definitions
+#ifndef PIN_WIRE_SDA
+ #define PIN_WIRE_SDA PA6
+#endif
+#ifndef PIN_WIRE_SCL
+ #define PIN_WIRE_SCL PA7
+#endif
+
+// Timer Definitions
+// Use TIM6/TIM7 when possible as servo and tone don't need GPIO output pin
+#ifndef TIMER_TONE
+ #define TIMER_TONE TIM6
+#endif
+#ifndef TIMER_SERVO
+ #define TIMER_SERVO TIM7
+#endif
+
+// UART Definitions
+#ifndef SERIAL_UART_INSTANCE
+ #define SERIAL_UART_INSTANCE 4
+#endif
+
+// Default pin used for generic 'Serial' instance
+// Mandatory for Firmata
+#ifndef PIN_SERIAL_RX
+ #define PIN_SERIAL_RX PA1
+#endif
+#ifndef PIN_SERIAL_TX
+ #define PIN_SERIAL_TX PA0
+#endif
+
+// Extra HAL modules
+#if !defined(HAL_DAC_MODULE_DISABLED)
+ #define HAL_DAC_MODULE_ENABLED
+#endif
+
+/*----------------------------------------------------------------------------
+ * Arduino objects - C++ only
+ *----------------------------------------------------------------------------*/
+
+#ifdef __cplusplus
+ // These serial port names are intended to allow libraries and architecture-neutral
+ // sketches to automatically default to the correct port name for a particular type
+ // of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN,
+ // the first hardware serial port whose RX/TX pins are not dedicated to another use.
+ //
+ // SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor
+ //
+ // SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial
+ //
+ // SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library
+ //
+ // SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins.
+ //
+ // SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX
+ // pins are NOT connected to anything by default.
+ #ifndef SERIAL_PORT_MONITOR
+ #define SERIAL_PORT_MONITOR Serial
+ #endif
+ #ifndef SERIAL_PORT_HARDWARE
+ #define SERIAL_PORT_HARDWARE Serial
+ #endif
+#endif
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F401RC/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_F401RC/PeripheralPins.c
new file mode 100644
index 00000000..b30ccf60
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_F401RC/PeripheralPins.c
@@ -0,0 +1,256 @@
+/*
+ *******************************************************************************
+ * Copyright (c) 2020-2021, STMicroelectronics
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ *******************************************************************************
+ */
+/*
+ * Automatically generated from STM32F401R(B-C)Tx.xml, STM32F401R(D-E)Tx.xml
+ * CubeMX DB release 6.0.30
+ */
+#if !defined(CUSTOM_PERIPHERAL_PINS)
+#include "Arduino.h"
+#include "PeripheralPins.h"
+
+/* =====
+ * Notes:
+ * - The pins mentioned Px_y_ALTz are alternative possibilities which use other
+ * HW peripheral instances. You can use them the same way as any other "normal"
+ * pin (i.e. analogWrite(PA7_ALT1, 128);).
+ *
+ * - Commented lines are alternative possibilities which are not used per default.
+ * If you change them, you will have to know what you do
+ * =====
+ */
+
+//*** ADC ***
+
+#ifdef HAL_ADC_MODULE_ENABLED
+WEAK const PinMap PinMap_ADC[] = {
+ {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0
+ {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1
+ {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2
+ {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3
+ {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4
+ {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5
+ {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6
+ {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7
+ {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8
+ {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9
+ {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10
+ {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11
+ {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12
+ {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13
+ {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14
+ {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15
+ {NC, NP, 0}
+};
+#endif
+
+//*** No DAC ***
+
+//*** I2C ***
+
+#ifdef HAL_I2C_MODULE_ENABLED
+WEAK const PinMap PinMap_I2C_SDA[] = {
+ {PB_3, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF9_I2C2)},
+ {PB_4, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF9_I2C3)},
+ {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
+ {PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
+ {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_I2C_MODULE_ENABLED
+WEAK const PinMap PinMap_I2C_SCL[] = {
+ {PA_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
+ {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
+ {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
+ {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** TIM ***
+
+#ifdef HAL_TIM_MODULE_ENABLED
+WEAK const PinMap PinMap_TIM[] = {
+ {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
+ {PA_0_ALT1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1
+ {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
+ {PA_1_ALT1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2
+ {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
+ {PA_2_ALT1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3
+ {PA_2_ALT2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1
+ {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
+ {PA_3_ALT1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4
+ {PA_3_ALT2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2
+ {PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
+ {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
+ {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
+ {PA_7_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
+ {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
+ {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
+ {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
+ {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
+ {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
+ {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
+ {PB_0_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
+ {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
+ {PB_1_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
+ {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
+ {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
+ {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
+ {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1
+ {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2
+ {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3
+ {PB_8_ALT1, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1
+ {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
+ {PB_9_ALT1, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1
+ {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
+ {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
+ {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
+ {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
+ {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
+ {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
+ {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
+ {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
+ {NC, NP, 0}
+};
+#endif
+
+//*** UART ***
+
+#ifdef HAL_UART_MODULE_ENABLED
+WEAK const PinMap PinMap_UART_TX[] = {
+ {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ {PA_11, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
+ {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_UART_MODULE_ENABLED
+WEAK const PinMap PinMap_UART_RX[] = {
+ {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ {PA_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
+ {PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_UART_MODULE_ENABLED
+WEAK const PinMap PinMap_UART_RTS[] = {
+ {PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ {PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_UART_MODULE_ENABLED
+WEAK const PinMap PinMap_UART_CTS[] = {
+ {PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ {PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** SPI ***
+
+#ifdef HAL_SPI_MODULE_ENABLED
+WEAK const PinMap PinMap_SPI_MOSI[] = {
+ {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ {PB_5_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ {PC_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_SPI_MODULE_ENABLED
+WEAK const PinMap PinMap_SPI_MISO[] = {
+ {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ {PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ {PB_4_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ {PC_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ {PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_SPI_MODULE_ENABLED
+WEAK const PinMap PinMap_SPI_SCLK[] = {
+ {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ {PB_3_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {PB_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ {PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_SPI_MODULE_ENABLED
+WEAK const PinMap PinMap_SPI_SSEL[] = {
+ {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ {PA_4_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ {PA_15_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** No CAN ***
+
+//*** No ETHERNET ***
+
+//*** No QUADSPI ***
+
+//*** USB ***
+
+#if defined(HAL_PCD_MODULE_ENABLED) || defined(HAL_HCD_MODULE_ENABLED)
+WEAK const PinMap PinMap_USB_OTG_FS[] = {
+ {PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF
+ {PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS
+ {PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID
+ {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM
+ {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP
+ {NC, NP, 0}
+};
+#endif
+
+//*** SD ***
+
+#ifdef HAL_SD_MODULE_ENABLED
+WEAK const PinMap PinMap_SD[] = {
+ {PB_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D4
+ {PB_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D5
+ {PC_6, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D6
+ {PC_7, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D7
+ {PC_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D0
+ {PC_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D1
+ {PC_10, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D2
+ {PC_11, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D3
+ {PC_12, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CK
+ {PD_2, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CMD
+ {NC, NP, 0}
+};
+#endif
+
+#endif /* !CUSTOM_PERIPHERAL_PINS */
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F401RC/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_F401RC/PinNamesVar.h
new file mode 100644
index 00000000..766cc2ca
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_F401RC/PinNamesVar.h
@@ -0,0 +1,52 @@
+/* Alternate pin name */
+PA_0_ALT1 = PA_0 | ALT1,
+PA_1_ALT1 = PA_1 | ALT1,
+PA_2_ALT1 = PA_2 | ALT1,
+PA_2_ALT2 = PA_2 | ALT2,
+PA_3_ALT1 = PA_3 | ALT1,
+PA_3_ALT2 = PA_3 | ALT2,
+PA_4_ALT1 = PA_4 | ALT1,
+PA_7_ALT1 = PA_7 | ALT1,
+PA_15_ALT1 = PA_15 | ALT1,
+PB_0_ALT1 = PB_0 | ALT1,
+PB_1_ALT1 = PB_1 | ALT1,
+PB_3_ALT1 = PB_3 | ALT1,
+PB_4_ALT1 = PB_4 | ALT1,
+PB_5_ALT1 = PB_5 | ALT1,
+PB_8_ALT1 = PB_8 | ALT1,
+PB_9_ALT1 = PB_9 | ALT1,
+
+/* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
+
+/* USB */
+#ifdef USBCON
+ USB_OTG_FS_DM = PA_11,
+ USB_OTG_FS_DP = PA_12,
+ USB_OTG_FS_ID = PA_10,
+ USB_OTG_FS_SOF = PA_8,
+ USB_OTG_FS_VBUS = PA_9,
+#endif
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F401RC/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F401RC/ldscript.ld
new file mode 100644
index 00000000..c7e67d31
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_F401RC/ldscript.ld
@@ -0,0 +1,177 @@
+/**
+ ******************************************************************************
+ * @file LinkerScript.ld
+ * @author Auto-generated by STM32CubeIDE
+ * @brief Linker script for STM32F401RBTx Device from STM32F4 series
+ * 128Kbytes FLASH
+ * 64Kbytes RAM
+ *
+ * Set heap size, stack size and stack location according
+ * to application requirements.
+ *
+ * Set memory bank area and size if external memory is used
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ ******************************************************************************
+ */
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = ORIGIN(RAM) + LENGTH(RAM); /* end of "RAM" Ram type memory */
+
+_Min_Heap_Size = 0x200; /* required amount of heap */
+_Min_Stack_Size = 0x400; /* required amount of stack */
+
+/* Memories definition */
+MEMORY
+{
+ RAM (xrw) : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE
+ FLASH (rx) : ORIGIN = 0x8000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET
+}
+
+/* Sections */
+SECTIONS
+{
+ /* The startup code into "FLASH" Rom type memory */
+ .isr_vector :
+ {
+ . = ALIGN(4);
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(4);
+ } >FLASH
+
+ /* The program code and other data into "FLASH" Rom type memory */
+ .text :
+ {
+ . = ALIGN(4);
+ *(.text) /* .text sections (code) */
+ *(.text*) /* .text* sections (code) */
+ *(.glue_7) /* glue arm to thumb code */
+ *(.glue_7t) /* glue thumb to arm code */
+ *(.eh_frame)
+
+ KEEP (*(.init))
+ KEEP (*(.fini))
+
+ . = ALIGN(4);
+ _etext = .; /* define a global symbols at end of code */
+ } >FLASH
+
+ /* Constant data into "FLASH" Rom type memory */
+ .rodata :
+ {
+ . = ALIGN(4);
+ *(.rodata) /* .rodata sections (constants, strings, etc.) */
+ *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
+ . = ALIGN(4);
+ } >FLASH
+
+ .ARM.extab : {
+ . = ALIGN(4);
+ *(.ARM.extab* .gnu.linkonce.armextab.*)
+ . = ALIGN(4);
+ } >FLASH
+
+ .ARM : {
+ . = ALIGN(4);
+ __exidx_start = .;
+ *(.ARM.exidx*)
+ __exidx_end = .;
+ . = ALIGN(4);
+ } >FLASH
+
+ .preinit_array :
+ {
+ . = ALIGN(4);
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array*))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ . = ALIGN(4);
+ } >FLASH
+
+ .init_array :
+ {
+ . = ALIGN(4);
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array*))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ . = ALIGN(4);
+ } >FLASH
+
+ .fini_array :
+ {
+ . = ALIGN(4);
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT(.fini_array.*)))
+ KEEP (*(.fini_array*))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ . = ALIGN(4);
+ } >FLASH
+
+ /* Used by the startup to initialize data */
+ _sidata = LOADADDR(.data);
+
+ /* Initialized data sections into "RAM" Ram type memory */
+ .data :
+ {
+ . = ALIGN(4);
+ _sdata = .; /* create a global symbol at data start */
+ *(.data) /* .data sections */
+ *(.data*) /* .data* sections */
+ *(.RamFunc) /* .RamFunc sections */
+ *(.RamFunc*) /* .RamFunc* sections */
+
+ . = ALIGN(4);
+ _edata = .; /* define a global symbol at data end */
+
+ } >RAM AT> FLASH
+
+ /* Uninitialized data section into "RAM" Ram type memory */
+ . = ALIGN(4);
+ .bss :
+ {
+ /* This is used by the startup in order to initialize the .bss section */
+ _sbss = .; /* define a global symbol at bss start */
+ __bss_start__ = _sbss;
+ *(.bss)
+ *(.bss*)
+ *(COMMON)
+
+ . = ALIGN(4);
+ _ebss = .; /* define a global symbol at bss end */
+ __bss_end__ = _ebss;
+ } >RAM
+
+ /* User_heap_stack section, used to check that there is enough "RAM" Ram type memory left */
+ ._user_heap_stack :
+ {
+ . = ALIGN(8);
+ PROVIDE ( end = . );
+ PROVIDE ( _end = . );
+ . = . + _Min_Heap_Size;
+ . = . + _Min_Stack_Size;
+ . = ALIGN(8);
+ } >RAM
+
+ /* Remove information from the compiler libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+}
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F401RC/variant_MARLIN_STM32F401RC.cpp b/buildroot/share/PlatformIO/variants/MARLIN_F401RC/variant_MARLIN_STM32F401RC.cpp
new file mode 100644
index 00000000..aac11b0b
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_F401RC/variant_MARLIN_STM32F401RC.cpp
@@ -0,0 +1,223 @@
+/*
+ *******************************************************************************
+ * Copyright (c) 2020-2021, STMicroelectronics
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ *******************************************************************************
+ */
+
+#if defined(STM32F401xC)
+#include "pins_arduino.h"
+
+// Digital PinName array
+const PinName digitalPin[] = {
+ PA_0, // D0/A0
+ PA_1, // D1/A1
+ PA_2, // D2/A2
+ PA_3, // D3/A3
+ PA_4, // D4/A4
+ PA_5, // D5/A5
+ PA_6, // D6/A6
+ PA_7, // D7/A7
+ PA_8, // D8
+ PA_9, // D9
+ PA_10, // D10
+ PA_11, // D11
+ PA_12, // D12
+ PA_13, // D13
+ PA_14, // D14
+ PA_15, // D15
+ PB_0, // D16/A8
+ PB_1, // D17/A9
+ PB_2, // D18
+ PB_3, // D19
+ PB_4, // D20
+ PB_5, // D21
+ PB_6, // D22
+ PB_7, // D23
+ PB_8, // D24
+ PB_9, // D25
+ PB_10, // D26
+ PB_12, // D27
+ PB_13, // D28
+ PB_14, // D29
+ PB_15, // D30
+ PC_0, // D31/A10
+ PC_1, // D32/A11
+ PC_2, // D33/A12
+ PC_3, // D34/A13
+ PC_4, // D35/A14
+ PC_5, // D36/A15
+ PC_6, // D37
+ PC_7, // D38
+ PC_8, // D39
+ PC_9, // D40
+ PC_10, // D41
+ PC_11, // D42
+ PC_12, // D43
+ PC_13, // D44
+ PC_14, // D45
+ PC_15, // D46
+ PD_2, // D47
+ PH_0, // D48
+ PH_1 // D49
+};
+
+// Analog (Ax) pin number array
+const uint32_t analogInputPin[] = {
+ 0, // A0, PA0
+ 1, // A1, PA1
+ 2, // A2, PA2
+ 3, // A3, PA3
+ 4, // A4, PA4
+ 5, // A5, PA5
+ 6, // A6, PA6
+ 7, // A7, PA7
+ 16, // A8, PB0
+ 17, // A9, PB1
+ 31, // A10, PC0
+ 32, // A11, PC1
+ 33, // A12, PC2
+ 34, // A13, PC3
+ 35, // A14, PC4
+ 36 // A15, PC5
+};
+
+// ----------------------------------------------------------------------------
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/*
+ * @brief Configures the System clock source, PLL Multiplier and Divider factors,
+ * AHB/APBx prescalers and Flash settings
+ * @note This function should be called only once the RCC clock configuration
+ * is reset to the default reset state (done in SystemInit() function).
+ * @param None
+ * @retval None
+ */
+
+/******************************************************************************/
+/* PLL (clocked by HSE) used as System clock source */
+/******************************************************************************/
+static uint8_t SetSysClock_PLL_HSE(uint8_t bypass)
+{
+ RCC_OscInitTypeDef RCC_OscInitStruct;
+ RCC_ClkInitTypeDef RCC_ClkInitStruct;
+
+ /* The voltage scaling allows optimizing the power consumption when the device is
+ clocked below the maximum system frequency, to update the voltage scaling value
+ regarding system frequency refer to product datasheet. */
+ __HAL_RCC_PWR_CLK_ENABLE();
+ __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE2);
+
+ // Enable HSE oscillator and activate PLL with HSE as source
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
+ if (bypass == 0) {
+ RCC_OscInitStruct.HSEState = RCC_HSE_ON; // External 8 MHz xtal on OSC_IN/OSC_OUT
+ } else {
+ RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS; // External 8 MHz clock on OSC_IN
+ }
+
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
+ RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
+ RCC_OscInitStruct.PLL.PLLM = HSE_VALUE / 1000000L; // Expects an 8 MHz external clock by default. Redefine HSE_VALUE if not
+ RCC_OscInitStruct.PLL.PLLN = 336; // VCO output clock = 336 MHz (1 MHz * 336)
+ RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV4; // PLLCLK = 84 MHz (336 MHz / 4)
+ RCC_OscInitStruct.PLL.PLLQ = 7; // USB clock = 48 MHz (336 MHz / 7) --> OK for USB
+ if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
+ return 0; // FAIL
+ }
+
+ // Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers
+ RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
+ RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; // 84 MHz
+ RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; // 84 MHz
+ RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; // 42 MHz
+ RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; // 84 MHz
+ if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) {
+ return 0; // FAIL
+ }
+
+ /* Output clock on MCO1 pin(PA8) for debugging purpose */
+ /*
+ if (bypass == 0)
+ HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSE, RCC_MCODIV_2); // 4 MHz
+ else
+ HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSE, RCC_MCODIV_1); // 8 MHz
+ */
+
+ return 1; // OK
+}
+
+/******************************************************************************/
+/* PLL (clocked by HSI) used as System clock source */
+/******************************************************************************/
+uint8_t SetSysClock_PLL_HSI(void)
+{
+ RCC_OscInitTypeDef RCC_OscInitStruct;
+ RCC_ClkInitTypeDef RCC_ClkInitStruct;
+
+ /* The voltage scaling allows optimizing the power consumption when the device is
+ clocked below the maximum system frequency, to update the voltage scaling value
+ regarding system frequency refer to product datasheet. */
+ __HAL_RCC_PWR_CLK_ENABLE();
+ __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE2);
+
+ // Enable HSI oscillator and activate PLL with HSI as source
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_HSE;
+ RCC_OscInitStruct.HSIState = RCC_HSI_ON;
+ RCC_OscInitStruct.HSEState = RCC_HSE_OFF;
+ RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
+ RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
+ RCC_OscInitStruct.PLL.PLLM = 16; // VCO input clock = 1 MHz (16 MHz / 16)
+ RCC_OscInitStruct.PLL.PLLN = 336; // VCO output clock = 336 MHz (1 MHz * 336)
+ RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV4; // PLLCLK = 84 MHz (336 MHz / 4)
+ RCC_OscInitStruct.PLL.PLLQ = 7; // USB clock = 48 MHz (336 MHz / 7) --> freq is ok but not precise enough
+ if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
+ return 0; // FAIL
+ }
+
+ /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */
+ RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2);
+ RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; // 84 MHz
+ RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; // 84 MHz
+ RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; // 42 MHz
+ RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; // 84 MHz
+ if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) {
+ return 0; // FAIL
+ }
+
+ /* Output clock on MCO1 pin(PA8) for debugging purpose */
+ //HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSI, RCC_MCODIV_1); // 16 MHz
+
+ return 1; // OK
+}
+
+WEAK void SystemClock_Config(void)
+{
+ /* 1- If fail try to start with HSE and external xtal */
+ if (SetSysClock_PLL_HSE(0) == 0) {
+ /* 2- Try to start with HSE and external clock */
+ if (SetSysClock_PLL_HSE(1) == 0) {
+ /* 3- If fail start with HSI clock */
+ if (SetSysClock_PLL_HSI() == 0) {
+ Error_Handler();
+ }
+ }
+ }
+ /* Output clock on MCO2 pin(PC9) for debugging purpose */
+ //HAL_RCC_MCOConfig(RCC_MCO2, RCC_MCO2SOURCE_SYSCLK, RCC_MCODIV_4);
+}
+
+#ifdef __cplusplus
+}
+#endif
+#endif /* STM32F401xC */
\ No newline at end of file
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F401RC/variant_MARLIN_STM32F401RC.h b/buildroot/share/PlatformIO/variants/MARLIN_F401RC/variant_MARLIN_STM32F401RC.h
new file mode 100644
index 00000000..37d60d93
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_F401RC/variant_MARLIN_STM32F401RC.h
@@ -0,0 +1,186 @@
+/*
+ *******************************************************************************
+ * Copyright (c) 2020-2021, STMicroelectronics
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ *******************************************************************************
+ */
+#pragma once
+
+/*----------------------------------------------------------------------------
+ * STM32 pins number
+ *----------------------------------------------------------------------------*/
+#define PA0 PIN_A0
+#define PA1 PIN_A1
+#define PA2 PIN_A2
+#define PA3 PIN_A3
+#define PA4 PIN_A4
+#define PA5 PIN_A5
+#define PA6 PIN_A6
+#define PA7 PIN_A7
+#define PA8 8
+#define PA9 9
+#define PA10 10
+#define PA11 11
+#define PA12 12
+#define PA13 13
+#define PA14 14
+#define PA15 15
+#define PB0 PIN_A8
+#define PB1 PIN_A9
+#define PB2 18
+#define PB3 19
+#define PB4 20
+#define PB5 21
+#define PB6 22
+#define PB7 23
+#define PB8 24
+#define PB9 25
+#define PB10 26
+#define PB12 27
+#define PB13 28
+#define PB14 29
+#define PB15 30
+#define PC0 PIN_A10
+#define PC1 PIN_A11
+#define PC2 PIN_A12
+#define PC3 PIN_A13
+#define PC4 PIN_A14
+#define PC5 PIN_A15
+#define PC6 37
+#define PC7 38
+#define PC8 39
+#define PC9 40
+#define PC10 41
+#define PC11 42
+#define PC12 43
+#define PC13 44
+#define PC14 45
+#define PC15 46
+#define PD2 47
+#define PH0 48
+#define PH1 49
+
+// Alternate pins number
+#define PA0_ALT1 (PA0 | ALT1)
+#define PA1_ALT1 (PA1 | ALT1)
+#define PA2_ALT1 (PA2 | ALT1)
+#define PA2_ALT2 (PA2 | ALT2)
+#define PA3_ALT1 (PA3 | ALT1)
+#define PA3_ALT2 (PA3 | ALT2)
+#define PA4_ALT1 (PA4 | ALT1)
+#define PA7_ALT1 (PA7 | ALT1)
+#define PA15_ALT1 (PA15 | ALT1)
+#define PB0_ALT1 (PB0 | ALT1)
+#define PB1_ALT1 (PB1 | ALT1)
+#define PB3_ALT1 (PB3 | ALT1)
+#define PB4_ALT1 (PB4 | ALT1)
+#define PB5_ALT1 (PB5 | ALT1)
+#define PB8_ALT1 (PB8 | ALT1)
+#define PB9_ALT1 (PB9 | ALT1)
+
+#define NUM_DIGITAL_PINS 50
+#define NUM_ANALOG_INPUTS 16
+#define NUM_ANALOG_FIRST 192
+
+// On-board LED pin number
+#ifndef LED_BUILTIN
+ #define LED_BUILTIN PNUM_NOT_DEFINED
+#endif
+
+// On-board user button
+#ifndef USER_BTN
+ #define USER_BTN PNUM_NOT_DEFINED
+#endif
+
+// SPI definitions
+#ifndef PIN_SPI_SS
+ #define PIN_SPI_SS PA4
+#endif
+#ifndef PIN_SPI_SS1
+ #define PIN_SPI_SS1 PA15
+#endif
+#ifndef PIN_SPI_SS2
+ #define PIN_SPI_SS2 PNUM_NOT_DEFINED
+#endif
+#ifndef PIN_SPI_SS3
+ #define PIN_SPI_SS3 PNUM_NOT_DEFINED
+#endif
+#ifndef PIN_SPI_MOSI
+ #define PIN_SPI_MOSI PA7
+#endif
+#ifndef PIN_SPI_MISO
+ #define PIN_SPI_MISO PA6
+#endif
+#ifndef PIN_SPI_SCK
+ #define PIN_SPI_SCK PA5
+#endif
+
+// I2C definitions
+#ifndef PIN_WIRE_SDA
+ #define PIN_WIRE_SDA PB3
+#endif
+#ifndef PIN_WIRE_SCL
+ #define PIN_WIRE_SCL PB10
+#endif
+
+// Timer Definitions
+// Use TIM6/TIM7 when possible as servo and tone don't need GPIO output pin
+#ifndef TIMER_TONE
+ #define TIMER_TONE TIM10
+#endif
+#ifndef TIMER_SERVO
+ #define TIMER_SERVO TIM11
+#endif
+
+// UART Definitions
+#ifndef SERIAL_UART_INSTANCE
+ #define SERIAL_UART_INSTANCE 2
+#endif
+
+// Default pin used for generic 'Serial' instance
+// Mandatory for Firmata
+#ifndef PIN_SERIAL_RX
+ #define PIN_SERIAL_RX PA3
+#endif
+#ifndef PIN_SERIAL_TX
+ #define PIN_SERIAL_TX PA2
+#endif
+
+// Extra HAL modules
+#if !defined(HAL_SD_MODULE_DISABLED)
+ #define HAL_SD_MODULE_ENABLED
+#endif
+
+/*----------------------------------------------------------------------------
+ * Arduino objects - C++ only
+ *----------------------------------------------------------------------------*/
+
+#ifdef __cplusplus
+ // These serial port names are intended to allow libraries and architecture-neutral
+ // sketches to automatically default to the correct port name for a particular type
+ // of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN,
+ // the first hardware serial port whose RX/TX pins are not dedicated to another use.
+ //
+ // SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor
+ //
+ // SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial
+ //
+ // SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library
+ //
+ // SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins.
+ //
+ // SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX
+ // pins are NOT connected to anything by default.
+ #ifndef SERIAL_PORT_MONITOR
+ #define SERIAL_PORT_MONITOR Serial
+ #endif
+ #ifndef SERIAL_PORT_HARDWARE
+ #define SERIAL_PORT_HARDWARE Serial
+ #endif
+#endif
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/PeripheralPins.c
new file mode 100644
index 00000000..d0905853
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/PeripheralPins.c
@@ -0,0 +1,433 @@
+/*
+ *******************************************************************************
+ * Copyright (c) 2016, STMicroelectronics
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *******************************************************************************
+ */
+#include "Arduino.h"
+#include "PeripheralPins.h"
+
+// =====
+// Note: Commented lines are alternative possibilities which are not used per default.
+// If you change them, you will have to know what you do
+// =====
+
+
+//*** ADC ***
+
+#ifdef HAL_ADC_MODULE_ENABLED
+const PinMap PinMap_ADC[] = {
+ {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3
+ {PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4
+ {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10
+ {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11
+ {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12
+ {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13
+ {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14
+ {PF_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9 TH_0
+ {PF_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14 TH_1
+ {PF_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15 TH_2
+ {PF_6, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4 TH_3
+ {PF_7, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5 EXP_13
+ {PF_8, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6 PT100
+ {NC, NP, 0}
+
+ // {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0
+ // {PA_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0
+ // {PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0
+ // {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1
+ // {PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1
+ // {PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1
+ // {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2
+ // {PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2
+ // {PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2
+ // {PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3
+ // {PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3
+ //{PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4
+ // {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5
+ // {PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5
+ // {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6
+ // {PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6
+ // {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7
+ // {PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7
+ // {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8
+ // {PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8
+ // {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9
+ // {PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9
+ // {PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10
+ // {PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10
+ // {PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11
+ // {PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11
+ // {PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12
+ // {PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12
+ // {PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13
+ // {PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13
+ // {PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14
+ // {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15
+ // {PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15
+
+};
+#endif
+
+//*** DAC ***
+
+#ifdef HAL_DAC_MODULE_ENABLED
+const PinMap PinMap_DAC[] = {
+ // {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1
+ // {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 - LD2
+ {NC, NP, 0}
+};
+#endif
+
+//*** I2C ***
+
+#ifdef HAL_I2C_MODULE_ENABLED
+const PinMap PinMap_I2C_SDA[] = {
+ // {PB_3, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
+ // {PB_4, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
+ // {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
+ {PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
+ // {PC_7, FMPI2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_FMPI2C1)},
+ // {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
+ // {PC_12, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_I2C_MODULE_ENABLED
+const PinMap PinMap_I2C_SCL[] = {
+ // {PA_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
+ // {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
+ {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
+ // {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
+ // {PC_6, FMPI2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_FMPI2C1)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** PWM ***
+
+#ifdef HAL_TIM_MODULE_ENABLED
+const PinMap PinMap_PWM[] = {
+ {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 BED
+ {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 HEATER0
+ {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 HEATER1
+ {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 HEATER2
+ {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 HEATER3
+ {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 FAN0
+ {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 FAN1
+ {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 FAN2
+ {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 FAN3
+ {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 FAN4
+ {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 FAN5
+
+ /**
+ * Unused by specifications on Octopus.
+ * Uncomment the corresponding line if you want to have HardwarePWM on some pins.
+ * WARNING: check timers' usage first to avoid conflicts.
+ * If you don't know what you're doing leave things as they are or you WILL break something (including hardware)
+ * If you alter this section DO NOT report bugs to Marlin team since they are most likely caused by you. Thank you.
+ */
+ //{PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
+ //{PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1
+ //{PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 BLTOUCH is a "servo"
+ //{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 BLTOUCH is a "servo"
+ //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2
+ //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3
+ //{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1
+ //{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
+ //{PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4
+ //{PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2
+ //{PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
+ //{PA_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N
+ //{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
+ //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1
+ //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
+ //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
+ //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N
+ //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1
+ //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
+ //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
+ //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
+ //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
+ //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
+ //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
+ //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N
+ //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
+ //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N
+ //{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
+ //{PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
+ //{PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
+ //{PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1
+ //{PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3
+ //{PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1
+ //{PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
+ //{PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1
+ //{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
+ //{PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
+ //{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
+ //{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
+ //{PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N
+ //{PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1
+ //{PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
+ //{PB_15, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N
+ //{PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 2, 0)}, // TIM12_CH2
+ //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1
+ //{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
+ //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2
+ //{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
+ //{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
+ //{PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2
+ //{PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
+ //{PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
+ //{PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
+ //{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
+ //{PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
+ //{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
+ //{PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
+ //{PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
+ //144 pins mcu, 114 gpio
+ //{PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1
+ //{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1
+ //{PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1
+ //{PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1
+
+ //176 pins mcu, 140 gpio
+ //{PH_10, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1
+ //{PH_6, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1
+ //{PH_11, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2
+ //{PI_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1
+ //{PI_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2
+
+ {NC, NP, 0}
+};
+#endif
+
+//*** SERIAL ***
+
+#ifdef HAL_UART_MODULE_ENABLED
+const PinMap PinMap_UART_TX[] = {
+ // {PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
+ // {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ {PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ // {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ // {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ // {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
+ // {PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
+ //{PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ // {PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_UART_MODULE_ENABLED
+const PinMap PinMap_UART_RX[] = {
+ // {PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
+ // {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ {PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ {PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ // {PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ // {PC_5, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ // {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
+ // {PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
+ //{PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ // {PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_UART_MODULE_ENABLED
+const PinMap PinMap_UART_RTS[] = {
+ // {PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ // {PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ // {PA_15, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
+ // {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ // {PC_8, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART5)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_UART_MODULE_ENABLED
+const PinMap PinMap_UART_CTS[] = {
+ // {PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ // {PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ // {PB_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
+ // {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ // {PC_9, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART5)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** SPI ***
+
+#ifdef HAL_SPI_MODULE_ENABLED
+const PinMap PinMap_SPI_MOSI[] = {
+ {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ // {PB_0, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)},
+ // {PB_2, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)},
+ // {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ // {PB_5, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ // {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ // {PC_1, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)},
+ // {PC_1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI3)},
+ // {PC_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ // {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_SPI_MODULE_ENABLED
+const PinMap PinMap_SPI_MISO[] = {
+ {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ // {PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ // {PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ // {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ // {PC_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ // {PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_SPI_MODULE_ENABLED
+const PinMap PinMap_SPI_SCLK[] = {
+ {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ // {PA_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ // {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ // {PB_3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ // {PB_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ // {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ // {PC_7, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ // {PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_SPI_MODULE_ENABLED
+const PinMap PinMap_SPI_SSEL[] = {
+ {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ // {PA_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ // {PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ // {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ // {PB_4, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)},
+ // {PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ // {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** CAN ***
+
+#ifdef HAL_CAN_MODULE_ENABLED
+const PinMap PinMap_CAN_RD[] = {
+ // {PA_11, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
+ // {PB_5, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
+ // {PB_8, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
+ // {PB_12, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_CAN_MODULE_ENABLED
+const PinMap PinMap_CAN_TD[] = {
+ // {PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
+ // {PB_6, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
+ // {PB_9, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
+ // {PB_13, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** ETHERNET ***
+
+//*** No Ethernet ***
+
+//*** QUADSPI ***
+
+#ifdef HAL_QSPI_MODULE_ENABLED
+const PinMap PinMap_QUADSPI[] = {
+ // {PA_1, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO3
+ // {PB_2, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_CLK
+ // {PB_6, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QSPI)}, // QUADSPI_BK1_NCS
+ // {PC_9, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO0
+ // {PC_10, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO1
+ // {PC_11, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK2_NCS
+ {NC, NP, 0}
+};
+#endif
+
+//*** USB ***
+
+#ifdef HAL_PCD_MODULE_ENABLED
+const PinMap PinMap_USB_OTG_FS[] = {
+ // {PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF
+ // {PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0)}, // USB_OTG_FS_VBUS
+ // {PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID
+ {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM
+ {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP
+ {NC, NP, 0}
+};
+
+const PinMap PinMap_USB_OTG_HS[] = {
+ //{PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID
+ //{PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS
+ {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM
+ {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP
+
+ /*#error "USB in HS mode isn't supported by the board"
+ {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0
+ {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1
+ {PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2
+ {PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7
+ {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3
+ {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5
+ {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6
+ {PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP
+ {PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR
+ {PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT
+ */
+ {NC, NP, 0}
+};
+
+
+#ifdef HAL_SD_MODULE_ENABLED
+WEAK const PinMap PinMap_SD[] = {
+ // {PB_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D4
+ // {PB_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D5
+ // {PC_6, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D6
+ // {PC_7, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D7
+ {PC_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D0
+ {PC_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D1
+ {PC_10, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D2
+ {PC_11, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D3
+ {PC_12, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CK
+ {PD_2, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CMD
+ {NC, NP, 0}
+};
+#endif
+#endif
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/PinNamesVar.h
new file mode 100644
index 00000000..bff3f213
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/PinNamesVar.h
@@ -0,0 +1,30 @@
+/* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0, /* SYS_WKUP0 */
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
+/* USB */
+#ifdef USBCON
+ USB_OTG_FS_DM = PA_11,
+ USB_OTG_FS_DP = PA_12,
+#endif
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/hal_conf_extra.h
new file mode 100644
index 00000000..d62c5100
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/hal_conf_extra.h
@@ -0,0 +1,53 @@
+#pragma once
+
+#define HAL_MODULE_ENABLED
+#define HAL_ADC_MODULE_ENABLED
+#define HAL_CRC_MODULE_ENABLED
+#define HAL_DMA_MODULE_ENABLED
+#define HAL_EXTI_MODULE_ENABLED // Needed for Endstop (and other external) Interrupts
+#define HAL_GPIO_MODULE_ENABLED
+#define HAL_I2C_MODULE_ENABLED
+#define HAL_PWR_MODULE_ENABLED
+#define HAL_RCC_MODULE_ENABLED
+//#define HAL_RTC_MODULE_ENABLED // Real Time Clock...do we use it?
+#define HAL_SPI_MODULE_ENABLED
+#define HAL_TIM_MODULE_ENABLED
+#define HAL_USART_MODULE_ENABLED
+#define HAL_CORTEX_MODULE_ENABLED
+//#define HAL_UART_MODULE_ENABLED // by default
+//#define HAL_PCD_MODULE_ENABLED // Since STM32 v3.10700.191028 this is automatically added if any type of USB is enabled (as in Arduino IDE)
+#define HAL_SD_MODULE_ENABLED
+
+//#undef HAL_SD_MODULE_ENABLED
+#undef HAL_DAC_MODULE_ENABLED
+#undef HAL_FLASH_MODULE_ENABLED
+#undef HAL_CAN_MODULE_ENABLED
+#undef HAL_CAN_LEGACY_MODULE_ENABLED
+#undef HAL_CEC_MODULE_ENABLED
+#undef HAL_CRYP_MODULE_ENABLED
+#undef HAL_DCMI_MODULE_ENABLED
+#undef HAL_DMA2D_MODULE_ENABLED
+#undef HAL_ETH_MODULE_ENABLED
+#undef HAL_NAND_MODULE_ENABLED
+#undef HAL_NOR_MODULE_ENABLED
+#undef HAL_PCCARD_MODULE_ENABLED
+#undef HAL_SRAM_MODULE_ENABLED
+#undef HAL_SDRAM_MODULE_ENABLED
+#undef HAL_HASH_MODULE_ENABLED
+#undef HAL_SMBUS_MODULE_ENABLED
+#undef HAL_I2S_MODULE_ENABLED
+#undef HAL_IWDG_MODULE_ENABLED
+#undef HAL_LTDC_MODULE_ENABLED
+#undef HAL_DSI_MODULE_ENABLED
+#undef HAL_QSPI_MODULE_ENABLED
+#undef HAL_RNG_MODULE_ENABLED
+#undef HAL_SAI_MODULE_ENABLED
+#undef HAL_IRDA_MODULE_ENABLED
+#undef HAL_SMARTCARD_MODULE_ENABLED
+#undef HAL_WWDG_MODULE_ENABLED
+//#undef HAL_HCD_MODULE_ENABLED
+#undef HAL_FMPI2C_MODULE_ENABLED
+#undef HAL_SPDIFRX_MODULE_ENABLED
+#undef HAL_DFSDM_MODULE_ENABLED
+#undef HAL_LPTIM_MODULE_ENABLED
+#undef HAL_MMC_MODULE_ENABLED
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/ldscript.ld
new file mode 100644
index 00000000..0edf17b8
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/ldscript.ld
@@ -0,0 +1,209 @@
+/*
+*****************************************************************************
+**
+
+** File : LinkerScript.ld
+**
+** Abstract : Linker script for STM32F407ZETx Device with
+** 512KByte FLASH, 64KByte RAM
+**
+** Set heap size, stack size and stack location according
+** to application requirements.
+**
+** Set memory bank area and size if external memory is used.
+**
+** Target : STMicroelectronics STM32
+**
+**
+** Distribution: The file is distributed as is, without any warranty
+** of any kind.
+**
+*****************************************************************************
+** @attention
+**
+** © COPYRIGHT(c) 2014 Ac6
+**
+** Redistribution and use in source and binary forms, with or without modification,
+** are permitted provided that the following conditions are met:
+** 1. Redistributions of source code must retain the above copyright notice,
+** this list of conditions and the following disclaimer.
+** 2. Redistributions in binary form must reproduce the above copyright notice,
+** this list of conditions and the following disclaimer in the documentation
+** and/or other materials provided with the distribution.
+** 3. Neither the name of Ac6 nor the names of its contributors
+** may be used to endorse or promote products derived from this software
+** without specific prior written permission.
+**
+** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+**
+*****************************************************************************
+*/
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = 0x20000000 + LD_MAX_DATA_SIZE; /* end of RAM */
+/* Generate a link error if heap and stack don't fit into RAM */
+_Min_Heap_Size = 0x200; /* required amount of heap */
+_Min_Stack_Size = 0x400; /* required amount of stack */
+
+/* Specify the memory areas */
+MEMORY
+{
+FLASH (rx) : ORIGIN = 0x08000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET
+RAM (xrw) : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE
+CCMRAM (rw) : ORIGIN = 0x10000000, LENGTH = 64K
+MEMORY_ARRAY (rw) : ORIGIN = 0x10000000, LENGTH = 0x144
+}
+
+/* Define output sections */
+SECTIONS
+{
+ /* The startup code goes first into FLASH */
+ .isr_vector :
+ {
+ . = ALIGN(4);
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(4);
+ } >FLASH
+
+ /* The program code and other data goes into FLASH */
+ .text ALIGN(4):
+ {
+ . = ALIGN(4);
+ *(.text) /* .text sections (code) */
+ *(.text*) /* .text* sections (code) */
+ *(.glue_7) /* glue arm to thumb code */
+ *(.glue_7t) /* glue thumb to arm code */
+ *(.eh_frame)
+
+ KEEP (*(.init))
+ KEEP (*(.fini))
+
+ . = ALIGN(4);
+ _etext = .; /* define a global symbols at end of code */
+ } >FLASH
+
+ /* Constant data goes into FLASH */
+ .rodata ALIGN(4) :
+ {
+ . = ALIGN(4);
+ *(.rodata) /* .rodata sections (constants, strings, etc.) */
+ *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
+ . = ALIGN(4);
+ } >FLASH
+
+ .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
+ .ARM : {
+ __exidx_start = .;
+ *(.ARM.exidx*)
+ __exidx_end = .;
+ } >FLASH
+
+ .preinit_array :
+ {
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array*))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ } >FLASH
+ .init_array :
+ {
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array*))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ } >FLASH
+ .fini_array :
+ {
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT(.fini_array.*)))
+ KEEP (*(.fini_array*))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ } >FLASH
+
+ /* used by the startup to initialize data */
+ _sidata = LOADADDR(.data);
+
+ /* Initialized data sections goes into RAM, load LMA copy after code */
+ .data :
+ {
+ . = ALIGN(4);
+ _sdata = .; /* create a global symbol at data start */
+ *(.data) /* .data sections */
+ *(.data*) /* .data* sections */
+
+ . = ALIGN(4);
+ _edata = .; /* define a global symbol at data end */
+ } >RAM AT> FLASH
+
+
+ _siccmram = LOADADDR(.ccmram);
+
+ /* CCM-RAM section
+ *
+ * IMPORTANT NOTE!
+ * If initialized variables will be placed in this section,
+ * the startup code needs to be modified to copy the init-values.
+ */
+ .ccmram :
+ {
+ . = ALIGN(4);
+ _sccmram = .; /* create a global symbol at ccmram start */
+ *(.ccmram)
+ *(.ccmram*)
+
+ . = ALIGN(4);
+ _eccmram = .; /* create a global symbol at ccmram end */
+ } >CCMRAM AT> FLASH
+
+
+ /* Uninitialized data section */
+ . = ALIGN(4);
+ .bss :
+ {
+ /* This is used by the startup in order to initialize the .bss secion */
+ _sbss = .; /* define a global symbol at bss start */
+ __bss_start__ = _sbss;
+ *(.bss)
+ *(.bss*)
+ *(COMMON)
+
+ . = ALIGN(4);
+ _ebss = .; /* define a global symbol at bss end */
+ __bss_end__ = _ebss;
+ } >RAM
+
+ /* User_heap_stack section, used to check that there is enough RAM left */
+ ._user_heap_stack :
+ {
+ . = ALIGN(8);
+ PROVIDE ( end = . );
+ PROVIDE ( _end = . );
+ . = . + _Min_Heap_Size;
+ . = . + _Min_Stack_Size;
+ . = ALIGN(8);
+ } >RAM
+
+
+
+ /* Remove information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+ ExtRAMData : {*(.ExtRAMData)} >MEMORY_ARRAY
+}
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/variant.cpp
new file mode 100644
index 00000000..7b5fdd0b
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/variant.cpp
@@ -0,0 +1,228 @@
+/*
+ Copyright (c) 2011 Arduino. All right reserved.
+
+ This library is free software; you can redistribute it and/or
+ modify it under the terms of the GNU Lesser General Public
+ License as published by the Free Software Foundation; either
+ version 2.1 of the License, or (at your option) any later version.
+
+ This library 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 Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with this library; if not, write to the Free Software
+ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+*/
+
+#include "pins_arduino.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+// Pin number
+const PinName digitalPin[] = {
+ PA_0, //D0
+ PA_1, //D1
+ PA_2, //D2
+ PA_3, //D3
+ PA_4, //D4
+ PA_5, //D5
+ PA_6, //D6
+ PA_7, //D7
+ PA_8, //D8
+ PA_9, //D9
+ PA_10, //D10
+ PA_11, //D11
+ PA_12, //D12
+ PA_13, //D13
+ PA_14, //D14
+ PA_15, //D15
+ PB_0, //D16
+ PB_1, //D17
+ PB_2, //D18
+ PB_3, //D19
+ PB_4, //D20
+ PB_5, //D21
+ PB_6, //D22
+ PB_7, //D23
+ PB_8, //D24
+ PB_9, //D25
+ PB_10, //D26
+ PB_11, //D27
+ PB_12, //D28
+ PB_13, //D29
+ PB_14, //D30
+ PB_15, //D31
+ PC_0, //D32
+ PC_1, //D33
+ PC_2, //D34
+ PC_3, //D35
+ PC_4, //D36
+ PC_5, //D37
+ PC_6, //D38
+ PC_7, //D39
+ PC_8, //D40
+ PC_9, //D41
+ PC_10, //D42
+ PC_11, //D43
+ PC_12, //D44
+ PC_13, //D45
+ PC_14, //D46
+ PC_15, //D47
+ PD_0, //D48
+ PD_1, //D49
+ PD_2, //D50
+ PD_3, //D51
+ PD_4, //D52
+ PD_5, //D53
+ PD_6, //D54
+ PD_7, //D55
+ PD_8, //D56
+ PD_9, //D57
+ PD_10, //D58
+ PD_11, //D59
+ PD_12, //D60
+ PD_13, //D61
+ PD_14, //D62
+ PD_15, //D63
+ PE_0, //D64
+ PE_1, //D65
+ PE_2, //D66
+ PE_3, //D67
+ PE_4, //D68
+ PE_5, //D69
+ PE_6, //D70
+ PE_7, //D71
+ PE_8, //D72
+ PE_9, //D73
+ PE_10, //D74
+ PE_11, //D75
+ PE_12, //D76
+ PE_13, //D77
+ PE_14, //D78
+ PE_15, //D79
+ PF_0, //D80
+ PF_1, //D81
+ PF_2, //D82
+ PF_3, //D83
+ PF_4, //D84
+ PF_5, //D85
+ PF_6, //D86
+ PF_7, //D87
+ PF_8, //D88
+ PF_9, //D89
+ PF_10, //D90
+ PF_11, //D91
+ PF_12, //D92
+ PF_13, //D93
+ PF_14, //D94
+ PF_15, //D95
+ PG_0, //D96
+ PG_1, //D97
+ PG_2, //D98
+ PG_3, //D99
+ PG_4, //D100
+ PG_5, //D101
+ PG_6, //D102
+ PG_7, //D103
+ PG_8, //D104
+ PG_9, //D105
+ PG_10, //D106
+ PG_11, //D107
+ PG_12, //D108
+ PG_13, //D109
+ PG_14, //D110
+ PG_15, //D111
+
+ //Duplicated ADC Pins
+ PA_3, //D112/A0
+ PA_4, //D113/A1
+ PC_0, //D114/A2
+ PC_1, //D115/A3
+ PC_2, //D116/A4
+ PC_3, //D117/A5
+ PC_4, //D118/A6
+ PF_3, //D119/A16 - 1:FSMC_A3 2:ADC3_IN9
+ PF_4, //D120/A17 - 1:FSMC_A4 2:ADC3_IN14
+ PF_5, //D121/A18 - 1:FSMC_A5 2:ADC3_IN15
+ PF_6, //D122/A19 - 1:TIM10_CH1 2:ADC3_IN4
+ PF_7, //D123/A20 - 1:TIM11_CH1 2:ADC3_IN5
+ PF_8, //D124/A20 - 1:TIM11_CH1 2:ADC3_IN6
+};
+
+#ifdef __cplusplus
+}
+#endif
+
+// ----------------------------------------------------------------------------
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @brief System Clock Configuration
+ * The system Clock is configured as follow :
+ * System Clock source = PLL (HSE)
+ * SYSCLK(Hz) = 168000000
+ * HCLK(Hz) = 168000000
+ * AHB Prescaler = 1
+ * APB1 Prescaler = 4
+ * APB2 Prescaler = 2
+ * HSE Frequency(Hz) = 8000000
+ * PLL_M = 8
+ * PLL_N = 336
+ * PLL_P = 2
+ * PLL_Q = 7
+ * VDD(V) = 3.3
+ * Main regulator output voltage = Scale1 mode
+ * Flash Latency(WS) = 5
+ * @param None
+ * @retval None
+ */
+WEAK void SystemClock_Config(void)
+{
+ RCC_ClkInitTypeDef RCC_ClkInitStruct;
+ RCC_OscInitTypeDef RCC_OscInitStruct;
+
+ /* Enable Power Control clock */
+ __HAL_RCC_PWR_CLK_ENABLE();
+
+ /* The voltage scaling allows optimizing the power consumption when the device is
+ clocked below the maximum system frequency, to update the voltage scaling value
+ regarding system frequency refer to product datasheet. */
+ __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
+
+ /* Enable HSE Oscillator and activate PLL with HSE as source */
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
+ RCC_OscInitStruct.HSEState = RCC_HSE_ON;
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
+ RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
+ RCC_OscInitStruct.PLL.PLLM = 8;
+ RCC_OscInitStruct.PLL.PLLN = 336;
+ RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
+ RCC_OscInitStruct.PLL.PLLQ = 7;
+ if(HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
+ {
+ /* Initialization Error */
+ }
+
+ /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2
+ clocks dividers */
+ RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2);
+ RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
+ RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
+ RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4;
+ RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;
+ if(HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK)
+ {
+ /* Initialization Error */
+ }
+}
+
+#ifdef __cplusplus
+}
+#endif
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/variant.h
new file mode 100644
index 00000000..b8e4b966
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/variant.h
@@ -0,0 +1,216 @@
+/*
+ Copyright (c) 2011 Arduino. All right reserved.
+
+ This library is free software; you can redistribute it and/or
+ modify it under the terms of the GNU Lesser General Public
+ License as published by the Free Software Foundation; either
+ version 2.1 of the License, or (at your option) any later version.
+
+ This library 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 Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with this library; if not, write to the Free Software
+ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+*/
+
+#ifndef _VARIANT_ARDUINO_STM32_
+#define _VARIANT_ARDUINO_STM32_
+
+#ifdef __cplusplus
+extern "C" {
+#endif // __cplusplus
+
+/*----------------------------------------------------------------------------
+ * Pins
+ *----------------------------------------------------------------------------*/
+
+#define PA0 0 //D0
+#define PA1 1 //D1
+#define PA2 2 //D2
+#define PA3 3 //D3
+#define PA4 4 //D4
+#define PA5 5 //D5
+#define PA6 6 //D6
+#define PA7 7 //D7
+#define PA8 8 //D8
+#define PA9 9 //D9
+#define PA10 10 //D10
+#define PA11 11 //D11
+#define PA12 12 //D12
+#define PA13 13 //D13
+#define PA14 14 //D14
+#define PA15 15 //D15
+#define PB0 16 //D16
+#define PB1 17 //D17
+#define PB2 18 //D18
+#define PB3 19 //D19
+#define PB4 20 //D20
+#define PB5 21 //D21
+#define PB6 22 //D22
+#define PB7 23 //D23
+#define PB8 24 //D24
+#define PB9 25 //D25
+#define PB10 26 //D26
+#define PB11 27 //D27
+#define PB12 28 //D28
+#define PB13 29 //D29
+#define PB14 30 //D30
+#define PB15 31 //D31
+#define PC0 32 //D32
+#define PC1 33 //D33
+#define PC2 34 //D34
+#define PC3 35 //D35
+#define PC4 36 //D36
+#define PC5 37 //D37
+#define PC6 38 //D38
+#define PC7 39 //D39
+#define PC8 40 //D40
+#define PC9 41 //D41
+#define PC10 42 //D42
+#define PC11 43 //D43
+#define PC12 44 //D44
+#define PC13 45 //D45
+#define PC14 46 //D46
+#define PC15 47 //D47
+#define PD0 48 //D48
+#define PD1 49 //D49
+#define PD2 50 //D50
+#define PD3 51 //D51
+#define PD4 52 //D52
+#define PD5 53 //D53
+#define PD6 54 //D54
+#define PD7 55 //D55
+#define PD8 56 //D56
+#define PD9 57 //D57
+#define PD10 58 //D58
+#define PD11 59 //D59
+#define PD12 60 //D60
+#define PD13 61 //D61
+#define PD14 62 //D62
+#define PD15 63 //D63
+#define PE0 64 //D64
+#define PE1 65 //D65
+#define PE2 66 //D66
+#define PE3 67 //D67
+#define PE4 68 //D68
+#define PE5 69 //D69
+#define PE6 70 //D70
+#define PE7 71 //D71
+#define PE8 72 //D72
+#define PE9 73 //D73
+#define PE10 74 //D74
+#define PE11 75 //D75
+#define PE12 76 //D76
+#define PE13 77 //D77
+#define PE14 78 //D78
+#define PE15 79 //D79
+#define PF0 80 //D64
+#define PF1 81 //D65
+#define PF2 82 //D66
+#define PF3 83 //D67
+#define PF4 84 //D68
+#define PF5 85 //D69
+#define PF6 86 //D70
+#define PF7 87 //D71
+#define PF8 88 //D72
+#define PF9 89 //D73
+#define PF10 90 //D74
+#define PF11 91 //D75
+#define PF12 92 //D76
+#define PF13 93 //D77
+#define PF14 94 //D78
+#define PF15 95 //D79
+#define PG0 96 //D64
+#define PG1 97 //D65
+#define PG2 98 //D66
+#define PG3 99 //D67
+#define PG4 100 //D68
+#define PG5 101 //D69
+#define PG6 102 //D70
+#define PG7 103 //D71
+#define PG8 104 //D72
+#define PG9 105 //D73
+#define PG10 106 //D74
+#define PG11 107 //D75
+#define PG12 108 //D76
+#define PG13 109 //D77
+#define PG14 110 //D78
+#define PG15 111 //D79
+
+// This must be a literal with the same value as PEND
+#define NUM_DIGITAL_PINS 112
+// This must be a literal with a value less than or equal to to MAX_ANALOG_INPUTS
+#define NUM_ANALOG_INPUTS 13
+#define NUM_ANALOG_FIRST NUM_DIGITAL_PINS
+
+//#define ADC_RESOLUTION 12
+
+// PWM resolution
+//#define PWM_RESOLUTION 12
+#define PWM_FREQUENCY 1000 // >= 20 Khz => inaudible noise for fans
+#define PWM_MAX_DUTY_CYCLE 255
+
+// SPI Definitions
+#define PIN_SPI_SS PA4
+#define PIN_SPI_MOSI PA7
+#define PIN_SPI_MISO PA6
+#define PIN_SPI_SCK PA5
+
+// I2C Definitions
+#define PIN_WIRE_SDA PB9
+#define PIN_WIRE_SCL PB8
+
+// Timer Definitions
+// Do not use timer used by PWM pin. See PinMap_PWM.
+#define TIMER_TONE TIM6 // TIMER_TONE must be defined in this file
+#define TIMER_SERVO TIM5 // TIMER_SERVO must be defined in this file
+#define TIMER_SERIAL TIM7 // TIMER_SERIAL must be defined in this file
+
+// UART Definitions
+//#define SERIAL_UART_INSTANCE 1 // Connected to EXP3 header
+/* Enable Serial 3 */
+#define HAVE_HWSERIAL1
+#define HAVE_HWSERIAL3
+
+// Default pin used for 'Serial' instance (ex: ST-Link)
+// Mandatory for Firmata
+#define PIN_SERIAL_RX PA10
+#define PIN_SERIAL_TX PA9
+
+/* HAL configuration */
+#define HSE_VALUE 8000000U
+
+#define FLASH_PAGE_SIZE (4U * 1024U)
+
+#ifdef __cplusplus
+} // extern "C"
+#endif
+
+/*----------------------------------------------------------------------------
+ * Arduino objects - C++ only
+ *----------------------------------------------------------------------------*/
+
+#ifdef __cplusplus
+// These serial port names are intended to allow libraries and architecture-neutral
+// sketches to automatically default to the correct port name for a particular type
+// of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN,
+// the first hardware serial port whose RX/TX pins are not dedicated to another use.
+//
+// SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor
+//
+// SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial
+//
+// SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library
+//
+// SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins.
+//
+// SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX
+// pins are NOT connected to anything by default.
+#define SERIAL_PORT_MONITOR Serial
+#define SERIAL_PORT_HARDWARE_OPEN Serial
+#endif
+
+#endif /* _VARIANT_ARDUINO_STM32_ */
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/PeripheralPins.c
new file mode 100644
index 00000000..4514efe7
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/PeripheralPins.c
@@ -0,0 +1,359 @@
+/*
+ *******************************************************************************
+ * Copyright (c) 2016, STMicroelectronics
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *******************************************************************************
+ */
+#include "Arduino.h"
+#include "PeripheralPins.h"
+
+// =====
+// Note: Commented lines are alternative possibilities which are not used per default.
+// If you change them, you will have to know what you do
+// =====
+
+
+//*** ADC ***
+
+#ifdef HAL_ADC_MODULE_ENABLED
+const PinMap PinMap_ADC[] = {
+ // {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0
+ // {PA_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0
+ // {PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0
+ // {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1
+ // {PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1
+ // {PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1
+ // {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2
+ // {PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2
+ // {PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2
+ {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3
+ // {PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3
+ // {PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3
+ {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4
+ // {PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4
+ // {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5
+ // {PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5
+ // {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6
+ // {PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6
+ // {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7
+ // {PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7
+ // {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8
+ // {PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8
+ // {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9
+ // {PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9
+ {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10
+ // {PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10
+ // {PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10
+ {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11
+ // {PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11
+ // {PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11
+ {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12
+ // {PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12
+ // {PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12
+ {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13
+ // {PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13
+ // {PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13
+ {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14
+ // {PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14
+ // {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15
+ // {PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15
+ {NC, NP, 0}
+};
+#endif
+
+//*** DAC ***
+
+#ifdef HAL_DAC_MODULE_ENABLED
+const PinMap PinMap_DAC[] = {
+ // {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1
+ // {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 - LD2
+ {NC, NP, 0}
+};
+#endif
+
+//*** I2C ***
+
+#ifdef HAL_I2C_MODULE_ENABLED
+const PinMap PinMap_I2C_SDA[] = {
+ // {PB_3, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
+ // {PB_4, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
+ // {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
+ {PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
+ // {PC_7, FMPI2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_FMPI2C1)},
+ // {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
+ // {PC_12, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_I2C_MODULE_ENABLED
+const PinMap PinMap_I2C_SCL[] = {
+ // {PA_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
+ // {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
+ {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
+ // {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
+ // {PC_6, FMPI2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_FMPI2C1)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** PWM ***
+
+#ifdef HAL_TIM_MODULE_ENABLED
+const PinMap PinMap_PWM[] = {
+ {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
+ // {PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1
+ // {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
+ {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2
+ // {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 - STLink Tx
+ // {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 - STLink Tx
+ // {PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 - STLink Tx
+ // {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 - STLink Rx
+ // {PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 - STLink Rx
+ // {PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 - STLink Rx
+ {PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
+ // {PA_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N
+ {PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1
+ // {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
+ //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1
+ // {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
+ // {PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
+ // {PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N
+ // {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
+ {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
+ {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
+ {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
+ {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
+ // {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
+ // {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
+ {PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // Fan0, TIM8_CH2N
+ // {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
+ // {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
+ {PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // Fan1, TIM8_CH3N
+ {PB_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // Fan2, TIM2_CH4
+ {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // E0 Heater, TIM2_CH2
+ {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // E1 Heater, TIM3_CH1
+ {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // LED G, TIM3_CH2
+ {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // LED R, TIM4_CH1
+ {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // LED B, TIM4_CH2
+ // {PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1
+ // {PB_8, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
+ {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3
+ {PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1
+ // {PB_9, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
+ // {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
+ {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
+ {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
+ {PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1
+ // {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
+ // {PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N
+ {PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 2, 0)}, // TIM12_CH2
+ // {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
+ // {PB_15, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N
+ {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
+ // {PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1
+ // {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
+ {PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2
+ {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
+ // {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3
+ // {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
+ {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4
+ {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
+ {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
+ {PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
+ {NC, NP, 0}
+};
+#endif
+
+//*** SERIAL ***
+
+#ifdef HAL_UART_MODULE_ENABLED
+const PinMap PinMap_UART_TX[] = {
+ // {PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
+ // {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ // {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ // {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ // {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
+ // {PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
+ {PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ // {PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_UART_MODULE_ENABLED
+const PinMap PinMap_UART_RX[] = {
+ // {PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
+ // {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ // {PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ // {PC_5, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ // {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
+ // {PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
+ {PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ // {PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_UART_MODULE_ENABLED
+const PinMap PinMap_UART_RTS[] = {
+ // {PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ // {PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ // {PA_15, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
+ // {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ // {PC_8, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART5)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_UART_MODULE_ENABLED
+const PinMap PinMap_UART_CTS[] = {
+ // {PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ // {PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ // {PB_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
+ // {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ // {PC_9, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART5)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** SPI ***
+
+#ifdef HAL_SPI_MODULE_ENABLED
+const PinMap PinMap_SPI_MOSI[] = {
+ {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ // {PB_0, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)},
+ // {PB_2, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)},
+ // {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ // {PB_5, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ // {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ // {PC_1, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)},
+ // {PC_1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI3)},
+ // {PC_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ // {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_SPI_MODULE_ENABLED
+const PinMap PinMap_SPI_MISO[] = {
+ {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ // {PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ // {PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ // {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ // {PC_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ // {PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_SPI_MODULE_ENABLED
+const PinMap PinMap_SPI_SCLK[] = {
+ {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ // {PA_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ // {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ // {PB_3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ // {PB_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ // {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ // {PC_7, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ // {PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_SPI_MODULE_ENABLED
+const PinMap PinMap_SPI_SSEL[] = {
+ {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ // {PA_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ // {PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ // {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ // {PB_4, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)},
+ // {PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ // {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** CAN ***
+
+#ifdef HAL_CAN_MODULE_ENABLED
+const PinMap PinMap_CAN_RD[] = {
+ // {PA_11, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
+ // {PB_5, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
+ // {PB_8, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
+ // {PB_12, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_CAN_MODULE_ENABLED
+const PinMap PinMap_CAN_TD[] = {
+ // {PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
+ // {PB_6, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
+ // {PB_9, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
+ // {PB_13, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** ETHERNET ***
+
+//*** No Ethernet ***
+
+//*** QUADSPI ***
+
+#ifdef HAL_QSPI_MODULE_ENABLED
+const PinMap PinMap_QUADSPI[] = {
+ // {PA_1, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO3
+ // {PB_2, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_CLK
+ // {PB_6, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QSPI)}, // QUADSPI_BK1_NCS
+ // {PC_9, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO0
+ // {PC_10, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO1
+ // {PC_11, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK2_NCS
+ {NC, NP, 0}
+};
+#endif
+
+//*** USB ***
+
+#ifdef HAL_PCD_MODULE_ENABLED
+const PinMap PinMap_USB_OTG_FS[] = {
+ // {PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF
+ // {PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0)}, // USB_OTG_FS_VBUS
+ // {PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID
+ {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM
+ {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP
+ {NC, NP, 0}
+};
+#endif
+
+#ifdef HAL_PCD_MODULE_ENABLED
+const PinMap PinMap_USB_OTG_HS[] = {
+ {NC, NP, 0}
+};
+#endif
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/PinNamesVar.h
new file mode 100644
index 00000000..bff3f213
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/PinNamesVar.h
@@ -0,0 +1,30 @@
+/* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0, /* SYS_WKUP0 */
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
+/* USB */
+#ifdef USBCON
+ USB_OTG_FS_DM = PA_11,
+ USB_OTG_FS_DP = PA_12,
+#endif
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/hal_conf_custom.h
new file mode 100644
index 00000000..c23d30ce
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/hal_conf_custom.h
@@ -0,0 +1,505 @@
+/**
+ ******************************************************************************
+ * @file stm32f4xx_hal_conf.h
+ * @brief HAL configuration file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2017 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_HAL_CONF_CUSTOM
+#define __STM32F4xx_HAL_CONF_CUSTOM
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/* ########################## Module Selection ############################## */
+ /**
+ * @brief This is the list of modules to be used in the HAL driver
+ */
+#define HAL_MODULE_ENABLED
+#define HAL_ADC_MODULE_ENABLED
+/* #define HAL_CAN_MODULE_ENABLED */
+/* #define HAL_CAN_LEGACY_MODULE_ENABLED */
+#define HAL_CRC_MODULE_ENABLED
+/* #define HAL_CEC_MODULE_ENABLED */
+/* #define HAL_CRYP_MODULE_ENABLED */
+#define HAL_DAC_MODULE_ENABLED
+/* #define HAL_DCMI_MODULE_ENABLED */
+#define HAL_DMA_MODULE_ENABLED
+/* #define HAL_DMA2D_MODULE_ENABLED */
+/* #define HAL_ETH_MODULE_ENABLED */
+#define HAL_FLASH_MODULE_ENABLED
+/* #define HAL_NAND_MODULE_ENABLED */
+/* #define HAL_NOR_MODULE_ENABLED */
+/* #define HAL_PCCARD_MODULE_ENABLED */
+#define HAL_SRAM_MODULE_ENABLED //YSZ-WORK
+/* #define HAL_SDRAM_MODULE_ENABLED */
+/* #define HAL_HASH_MODULE_ENABLED */
+#define HAL_GPIO_MODULE_ENABLED
+/* #define HAL_EXTI_MODULE_ENABLED */
+#define HAL_I2C_MODULE_ENABLED
+/* #define HAL_SMBUS_MODULE_ENABLED */
+/* #define HAL_I2S_MODULE_ENABLED */
+/* #define HAL_IWDG_MODULE_ENABLED */
+/* #define HAL_LTDC_MODULE_ENABLED */
+/* #define HAL_DSI_MODULE_ENABLED */
+#define HAL_PWR_MODULE_ENABLED
+/* #define HAL_QSPI_MODULE_ENABLED */
+#define HAL_RCC_MODULE_ENABLED
+/* #define HAL_RNG_MODULE_ENABLED */
+#define HAL_RTC_MODULE_ENABLED
+/* #define HAL_SAI_MODULE_ENABLED */
+#define HAL_SD_MODULE_ENABLED
+#define HAL_SPI_MODULE_ENABLED
+#define HAL_TIM_MODULE_ENABLED
+/* #define HAL_UART_MODULE_ENABLED */
+/* #define HAL_USART_MODULE_ENABLED */
+/* #define HAL_IRDA_MODULE_ENABLED */
+/* #define HAL_SMARTCARD_MODULE_ENABLED */
+/* #define HAL_WWDG_MODULE_ENABLED */
+#define HAL_CORTEX_MODULE_ENABLED
+#ifndef HAL_PCD_MODULE_ENABLED
+ #define HAL_PCD_MODULE_ENABLED //Since STM32 v3.10700.191028 this is automatically added if any type of USB is enabled (as in Arduino IDE)
+#endif
+#define HAL_HCD_MODULE_ENABLED
+/* #define HAL_FMPI2C_MODULE_ENABLED */
+/* #define HAL_SPDIFRX_MODULE_ENABLED */
+/* #define HAL_DFSDM_MODULE_ENABLED */
+/* #define HAL_LPTIM_MODULE_ENABLED */
+/* #define HAL_MMC_MODULE_ENABLED */
+
+/* ########################## HSE/HSI Values adaptation ##################### */
+/**
+ * @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
+ * This value is used by the RCC HAL module to compute the system frequency
+ * (when HSE is used as system clock source, directly or through the PLL).
+ */
+#ifndef HSE_VALUE
+#define HSE_VALUE 8000000U /*!< Value of the External oscillator in Hz */
+#endif /* HSE_VALUE */
+
+#ifndef HSE_STARTUP_TIMEOUT
+#if STM32_TYPE == 4
+#define HSE_STARTUP_TIMEOUT 0xFFFFu
+#else
+#define HSE_STARTUP_TIMEOUT 100U /*!< Time out for HSE start up, in ms */
+#endif
+#endif /* HSE_STARTUP_TIMEOUT */
+
+/**
+ * @brief Internal High Speed oscillator (HSI) value.
+ * This value is used by the RCC HAL module to compute the system frequency
+ * (when HSI is used as system clock source, directly or through the PLL).
+ */
+#ifndef HSI_VALUE
+#define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz */
+#endif /* HSI_VALUE */
+
+/**
+ * @brief Internal Low Speed oscillator (LSI) value.
+ */
+#ifndef LSI_VALUE
+#define LSI_VALUE 32000U /*!< LSI Typical Value in Hz */
+#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
+The real value may vary depending on the variations
+in voltage and temperature. */
+/**
+ * @brief External Low Speed oscillator (LSE) value.
+ */
+#ifndef LSE_VALUE
+#define LSE_VALUE 32768U /*!< Value of the External Low Speed oscillator in Hz */
+#endif /* LSE_VALUE */
+
+#ifndef LSE_STARTUP_TIMEOUT
+#define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */
+#endif /* LSE_STARTUP_TIMEOUT */
+
+/**
+ * @brief External clock source for I2S peripheral
+ * This value is used by the I2S HAL module to compute the I2S clock source
+ * frequency, this source is inserted directly through I2S_CKIN pad.
+ */
+#ifndef EXTERNAL_CLOCK_VALUE
+#define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External oscillator in Hz*/
+#endif /* EXTERNAL_CLOCK_VALUE */
+
+/* Tip: To avoid modifying this file each time you need to use different HSE,
+ === you can define the HSE value in your toolchain compiler preprocessor. */
+
+/* ########################### System Configuration ######################### */
+/**
+ * @brief This is the HAL system configuration section
+ */
+#if !defined (VDD_VALUE)
+#define VDD_VALUE 3300U /*!< Value of VDD in mv */
+#endif
+#if !defined (TICK_INT_PRIORITY)
+#define TICK_INT_PRIORITY 0x00U /*!< tick interrupt priority */
+#endif
+#if !defined (USE_RTOS)
+#define USE_RTOS 0U
+#endif
+#if !defined (PREFETCH_ENABLE)
+#define PREFETCH_ENABLE 1U
+#endif
+#if !defined (INSTRUCTION_CACHE_ENABLE)
+#define INSTRUCTION_CACHE_ENABLE 1U
+#endif
+#if !defined (DATA_CACHE_ENABLE)
+#define DATA_CACHE_ENABLE 1U
+#endif
+
+#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */
+#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */
+#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */
+#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */
+#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */
+#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */
+#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */
+#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */
+#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */
+#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */
+#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */
+#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */
+#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */
+#define USE_HAL_FMPI2C_REGISTER_CALLBACKS 0U /* FMPI2C register callback disabled */
+#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */
+#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */
+#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */
+#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */
+#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */
+#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */
+#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */
+#define USE_HAL_PCCARD_REGISTER_CALLBACKS 0U /* PCCARD register callback disabled */
+#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */
+#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */
+#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */
+#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */
+#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */
+#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */
+#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */
+#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */
+#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */
+#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */
+#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */
+#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */
+#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */
+#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */
+#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */
+#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */
+
+/* ########################## Assert Selection ############################## */
+/**
+ * @brief Uncomment the line below to expanse the "assert_param" macro in the
+ * HAL drivers code
+ */
+/* #define USE_FULL_ASSERT 1U */
+
+/* ################## Ethernet peripheral configuration ##################### */
+
+/* Section 1 : Ethernet peripheral configuration */
+
+/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */
+#define MAC_ADDR0 2U
+#define MAC_ADDR1 0U
+#define MAC_ADDR2 0U
+#define MAC_ADDR3 0U
+#define MAC_ADDR4 0U
+#define MAC_ADDR5 0U
+
+/* Definition of the Ethernet driver buffers size and count */
+#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */
+#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */
+#define ETH_RXBUFNB ((uint32_t)4U) /* 4 Rx buffers of size ETH_RX_BUF_SIZE */
+#define ETH_TXBUFNB ((uint32_t)4U) /* 4 Tx buffers of size ETH_TX_BUF_SIZE */
+
+/* Section 2: PHY configuration section */
+
+/* DP83848_PHY_ADDRESS Address*/
+#define DP83848_PHY_ADDRESS 0x01U
+/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/
+#define PHY_RESET_DELAY 0x000000FFU
+/* PHY Configuration delay */
+#define PHY_CONFIG_DELAY 0x00000FFFU
+
+#define PHY_READ_TO 0x0000FFFFU
+#define PHY_WRITE_TO 0x0000FFFFU
+
+/* Section 3: Common PHY Registers */
+
+#define PHY_BCR ((uint16_t)0x0000) /*!< Transceiver Basic Control Register */
+#define PHY_BSR ((uint16_t)0x0001) /*!< Transceiver Basic Status Register */
+
+#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */
+#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */
+#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */
+#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */
+#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */
+#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */
+#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */
+#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */
+#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */
+#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */
+
+#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */
+#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */
+#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */
+
+/* Section 4: Extended PHY Registers */
+#define PHY_SR ((uint16_t)0x10U) /*!< PHY status register Offset */
+
+#define PHY_SPEED_STATUS ((uint16_t)0x0002U) /*!< PHY Speed mask */
+#define PHY_DUPLEX_STATUS ((uint16_t)0x0004U) /*!< PHY Duplex mask */
+
+/* ################## SPI peripheral configuration ########################## */
+
+/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
+ * Activated: CRC code is present inside driver
+ * Deactivated: CRC code cleaned from driver
+ */
+#ifndef USE_SPI_CRC
+#define USE_SPI_CRC 0U
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+/**
+ * @brief Include module's header file
+ */
+
+#ifdef HAL_RCC_MODULE_ENABLED
+#include "stm32f4xx_hal_rcc.h"
+#endif /* HAL_RCC_MODULE_ENABLED */
+
+#ifdef HAL_GPIO_MODULE_ENABLED
+#include "stm32f4xx_hal_gpio.h"
+#include "stm32f4xx_hal_gpio_ex.h" //YSZ-WORK
+#endif /* HAL_GPIO_MODULE_ENABLED */
+
+#ifdef HAL_EXTI_MODULE_ENABLED
+#include "stm32f4xx_hal_exti.h"
+#endif /* HAL_EXTI_MODULE_ENABLED */
+
+#ifdef HAL_DMA_MODULE_ENABLED
+#include "stm32f4xx_hal_dma.h"
+#endif /* HAL_DMA_MODULE_ENABLED */
+
+#ifdef HAL_CORTEX_MODULE_ENABLED
+#include "stm32f4xx_hal_cortex.h"
+#endif /* HAL_CORTEX_MODULE_ENABLED */
+
+#ifdef HAL_ADC_MODULE_ENABLED
+#include "stm32f4xx_hal_adc.h"
+#endif /* HAL_ADC_MODULE_ENABLED */
+
+#ifdef HAL_CAN_MODULE_ENABLED
+#include "stm32f4xx_hal_can.h"
+#endif /* HAL_CAN_MODULE_ENABLED */
+
+#ifdef HAL_CAN_LEGACY_MODULE_ENABLED
+#include "stm32f4xx_hal_can_legacy.h"
+#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */
+
+#ifdef HAL_CRC_MODULE_ENABLED
+#include "stm32f4xx_hal_crc.h"
+#endif /* HAL_CRC_MODULE_ENABLED */
+
+#ifdef HAL_CRYP_MODULE_ENABLED
+#include "stm32f4xx_hal_cryp.h"
+#endif /* HAL_CRYP_MODULE_ENABLED */
+
+#ifdef HAL_DMA2D_MODULE_ENABLED
+#include "stm32f4xx_hal_dma2d.h"
+#endif /* HAL_DMA2D_MODULE_ENABLED */
+
+#ifdef HAL_DAC_MODULE_ENABLED
+#include "stm32f4xx_hal_dac.h"
+#endif /* HAL_DAC_MODULE_ENABLED */
+
+#ifdef HAL_DCMI_MODULE_ENABLED
+#include "stm32f4xx_hal_dcmi.h"
+#endif /* HAL_DCMI_MODULE_ENABLED */
+
+#ifdef HAL_ETH_MODULE_ENABLED
+#include "stm32f4xx_hal_eth.h"
+#endif /* HAL_ETH_MODULE_ENABLED */
+
+#ifdef HAL_FLASH_MODULE_ENABLED
+#include "stm32f4xx_hal_flash.h"
+#endif /* HAL_FLASH_MODULE_ENABLED */
+
+#ifdef HAL_SRAM_MODULE_ENABLED
+#include "stm32f4xx_hal_sram.h"
+#endif /* HAL_SRAM_MODULE_ENABLED */
+
+#ifdef HAL_NOR_MODULE_ENABLED
+#include "stm32f4xx_hal_nor.h"
+#endif /* HAL_NOR_MODULE_ENABLED */
+
+#ifdef HAL_NAND_MODULE_ENABLED
+#include "stm32f4xx_hal_nand.h"
+#endif /* HAL_NAND_MODULE_ENABLED */
+
+#ifdef HAL_PCCARD_MODULE_ENABLED
+#include "stm32f4xx_hal_pccard.h"
+#endif /* HAL_PCCARD_MODULE_ENABLED */
+
+#ifdef HAL_SDRAM_MODULE_ENABLED
+#include "stm32f4xx_hal_sdram.h"
+#endif /* HAL_SDRAM_MODULE_ENABLED */
+
+#ifdef HAL_HASH_MODULE_ENABLED
+#include "stm32f4xx_hal_hash.h"
+#endif /* HAL_HASH_MODULE_ENABLED */
+
+#ifdef HAL_I2C_MODULE_ENABLED
+#include "stm32f4xx_hal_i2c.h"
+#endif /* HAL_I2C_MODULE_ENABLED */
+
+#ifdef HAL_SMBUS_MODULE_ENABLED
+#include "stm32f4xx_hal_smbus.h"
+#endif /* HAL_SMBUS_MODULE_ENABLED */
+
+#ifdef HAL_I2S_MODULE_ENABLED
+#include "stm32f4xx_hal_i2s.h"
+#endif /* HAL_I2S_MODULE_ENABLED */
+
+#ifdef HAL_IWDG_MODULE_ENABLED
+#include "stm32f4xx_hal_iwdg.h"
+#endif /* HAL_IWDG_MODULE_ENABLED */
+
+#ifdef HAL_LTDC_MODULE_ENABLED
+#include "stm32f4xx_hal_ltdc.h"
+#endif /* HAL_LTDC_MODULE_ENABLED */
+
+#ifdef HAL_PWR_MODULE_ENABLED
+#include "stm32f4xx_hal_pwr.h"
+#endif /* HAL_PWR_MODULE_ENABLED */
+
+#ifdef HAL_RNG_MODULE_ENABLED
+#include "stm32f4xx_hal_rng.h"
+#endif /* HAL_RNG_MODULE_ENABLED */
+
+#ifdef HAL_RTC_MODULE_ENABLED
+#include "stm32f4xx_hal_rtc.h"
+#endif /* HAL_RTC_MODULE_ENABLED */
+
+#ifdef HAL_SAI_MODULE_ENABLED
+#include "stm32f4xx_hal_sai.h"
+#endif /* HAL_SAI_MODULE_ENABLED */
+
+#ifdef HAL_SD_MODULE_ENABLED
+#include "stm32f4xx_hal_sd.h"
+#endif /* HAL_SD_MODULE_ENABLED */
+
+#ifdef HAL_SPI_MODULE_ENABLED
+#include "stm32f4xx_hal_spi.h"
+#endif /* HAL_SPI_MODULE_ENABLED */
+
+#ifdef HAL_TIM_MODULE_ENABLED
+#include "stm32f4xx_hal_tim.h"
+#endif /* HAL_TIM_MODULE_ENABLED */
+
+#ifdef HAL_UART_MODULE_ENABLED
+#include "stm32f4xx_hal_uart.h"
+#endif /* HAL_UART_MODULE_ENABLED */
+
+#ifdef HAL_USART_MODULE_ENABLED
+#include "stm32f4xx_hal_usart.h"
+#endif /* HAL_USART_MODULE_ENABLED */
+
+#ifdef HAL_IRDA_MODULE_ENABLED
+#include "stm32f4xx_hal_irda.h"
+#endif /* HAL_IRDA_MODULE_ENABLED */
+
+#ifdef HAL_SMARTCARD_MODULE_ENABLED
+#include "stm32f4xx_hal_smartcard.h"
+#endif /* HAL_SMARTCARD_MODULE_ENABLED */
+
+#ifdef HAL_WWDG_MODULE_ENABLED
+#include "stm32f4xx_hal_wwdg.h"
+#endif /* HAL_WWDG_MODULE_ENABLED */
+
+#ifdef HAL_PCD_MODULE_ENABLED
+#include "stm32f4xx_hal_pcd.h"
+#endif /* HAL_PCD_MODULE_ENABLED */
+
+#ifdef HAL_HCD_MODULE_ENABLED
+#include "stm32f4xx_hal_hcd.h"
+#endif /* HAL_HCD_MODULE_ENABLED */
+
+#ifdef HAL_DSI_MODULE_ENABLED
+#include "stm32f4xx_hal_dsi.h"
+#endif /* HAL_DSI_MODULE_ENABLED */
+
+#ifdef HAL_QSPI_MODULE_ENABLED
+#include "stm32f4xx_hal_qspi.h"
+#endif /* HAL_QSPI_MODULE_ENABLED */
+
+#ifdef HAL_CEC_MODULE_ENABLED
+#include "stm32f4xx_hal_cec.h"
+#endif /* HAL_CEC_MODULE_ENABLED */
+
+#ifdef HAL_FMPI2C_MODULE_ENABLED
+#include "stm32f4xx_hal_fmpi2c.h"
+#endif /* HAL_FMPI2C_MODULE_ENABLED */
+
+#ifdef HAL_SPDIFRX_MODULE_ENABLED
+#include "stm32f4xx_hal_spdifrx.h"
+#endif /* HAL_SPDIFRX_MODULE_ENABLED */
+
+#ifdef HAL_DFSDM_MODULE_ENABLED
+#include "stm32f4xx_hal_dfsdm.h"
+#endif /* HAL_DFSDM_MODULE_ENABLED */
+
+#ifdef HAL_LPTIM_MODULE_ENABLED
+#include "stm32f4xx_hal_lptim.h"
+#endif /* HAL_LPTIM_MODULE_ENABLED */
+
+#ifdef HAL_MMC_MODULE_ENABLED
+#include "stm32f4xx_hal_mmc.h"
+#endif /* HAL_MMC_MODULE_ENABLED */
+
+#ifdef HAL_FSMC_MODULE_ENABLED
+#include "stm32f4xx_ll_fmc.h"
+#endif
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef USE_FULL_ASSERT
+/**
+ * @brief The assert_param macro is used for function's parameters check.
+ * @param expr If expr is false, it calls assert_failed function
+ * which reports the name of the source file and the source
+ * line number of the call that failed.
+ * If expr is true, it returns no value.
+ * @retval None
+ */
+#define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+void assert_failed(uint8_t *file, uint32_t line);
+#else
+#define assert_param(expr) ((void)0U)
+#endif /* USE_FULL_ASSERT */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F4xx_HAL_CONF_CUSTOM_H */
+
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/ldscript.ld
new file mode 100644
index 00000000..20a9f1db
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/ldscript.ld
@@ -0,0 +1,188 @@
+/*
+*****************************************************************************
+**
+
+** File : LinkerScript.ld
+**
+** Abstract : Linker script for STM32F446RETx Device with
+** 512KByte FLASH, 128KByte RAM
+**
+** Set heap size, stack size and stack location according
+** to application requirements.
+**
+** Set memory bank area and size if external memory is used.
+**
+** Target : STMicroelectronics STM32
+**
+**
+** Distribution: The file is distributed as is, without any warranty
+** of any kind.
+**
+*****************************************************************************
+** @attention
+**
+** © COPYRIGHT(c) 2014 Ac6
+**
+** Redistribution and use in source and binary forms, with or without modification,
+** are permitted provided that the following conditions are met:
+** 1. Redistributions of source code must retain the above copyright notice,
+** this list of conditions and the following disclaimer.
+** 2. Redistributions in binary form must reproduce the above copyright notice,
+** this list of conditions and the following disclaimer in the documentation
+** and/or other materials provided with the distribution.
+** 3. Neither the name of Ac6 nor the names of its contributors
+** may be used to endorse or promote products derived from this software
+** without specific prior written permission.
+**
+** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+**
+*****************************************************************************
+*/
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = 0x20000000 + LD_MAX_DATA_SIZE; /* end of RAM */
+/* Generate a link error if heap and stack don't fit into RAM */
+_Min_Heap_Size = 0x2000; /* required amount of heap */
+_Min_Stack_Size = 0x400; /* required amount of stack */
+
+/* Specify the memory areas */
+MEMORY
+{
+RAM (xrw) : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE
+FLASH (rx) : ORIGIN = 0x08000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET
+}
+
+/* Define output sections */
+SECTIONS
+{
+ /* The startup code goes first into FLASH */
+ .isr_vector :
+ {
+ . = ALIGN(4);
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(4);
+ } >FLASH
+
+ /* The program code and other data goes into FLASH */
+ .text ALIGN(4):
+ {
+ . = ALIGN(4);
+ *(.text) /* .text sections (code) */
+ *(.text*) /* .text* sections (code) */
+ *(.glue_7) /* glue arm to thumb code */
+ *(.glue_7t) /* glue thumb to arm code */
+ *(.eh_frame)
+
+ KEEP (*(.init))
+ KEEP (*(.fini))
+
+ . = ALIGN(8); /*YSZ-WORK:4->8*/
+ _etext = .; /* define a global symbols at end of code */
+ } >FLASH
+
+ /* Constant data goes into FLASH */
+ .rodata :
+ {
+ . = ALIGN(4);
+ *(.rodata) /* .rodata sections (constants, strings, etc.) */
+ *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
+ . = ALIGN(4);
+ } >FLASH
+
+ .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
+ .ARM : {
+ __exidx_start = .;
+ *(.ARM.exidx*)
+ __exidx_end = .;
+ } >FLASH
+
+ .preinit_array :
+ {
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array*))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ } >FLASH
+ .init_array :
+ {
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array*))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ } >FLASH
+ .fini_array :
+ {
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT(.fini_array.*)))
+ KEEP (*(.fini_array*))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ } >FLASH
+
+ /* used by the startup to initialize data */
+ _sidata = LOADADDR(.data);
+
+ /* Initialized data sections goes into RAM, load LMA copy after code */
+ .data :
+ {
+ . = ALIGN(4);
+ _sdata = .; /* create a global symbol at data start */
+ *(.data) /* .data sections */
+ *(.data*) /* .data* sections */
+
+ . = ALIGN(4);
+ _edata = .; /* define a global symbol at data end */
+ } >RAM AT> FLASH
+
+
+ /* Uninitialized data section */
+ . = ALIGN(4);
+ .bss :
+ {
+ /* This is used by the startup in order to initialize the .bss secion */
+ _sbss = .; /* define a global symbol at bss start */
+ __bss_start__ = _sbss;
+ *(.bss)
+ *(.bss*)
+ *(COMMON)
+
+ . = ALIGN(4);
+ _ebss = .; /* define a global symbol at bss end */
+ __bss_end__ = _ebss;
+ } >RAM
+
+ /* User_heap_stack section, used to check that there is enough RAM left */
+ ._user_heap_stack :
+ {
+ . = ALIGN(4);/*YSZ-WORK:8->4*/
+ PROVIDE ( end = . );
+ PROVIDE ( _end = . );
+ . = . + _Min_Heap_Size;
+ . = . + _Min_Stack_Size;
+ . = ALIGN(4);/*YSZ-WORK:8->4*/
+ } >RAM
+
+
+
+ /* Remove information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+}
+
+
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/variant.cpp
new file mode 100644
index 00000000..2d94ee76
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/variant.cpp
@@ -0,0 +1,320 @@
+/*
+ Copyright (c) 2011 Arduino. All right reserved.
+
+ This library is free software; you can redistribute it and/or
+ modify it under the terms of the GNU Lesser General Public
+ License as published by the Free Software Foundation; either
+ version 2.1 of the License, or (at your option) any later version.
+
+ This library 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 Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with this library; if not, write to the Free Software
+ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+*/
+
+#include "pins_arduino.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+// Pin number
+const PinName digitalPin[] = {
+ PA_0, //D0
+ PA_1, //D1
+ PA_2, //D2
+ PA_3, //D3
+ PA_4, //D4
+ PA_5, //D5
+ PA_6, //D6
+ PA_7, //D7
+ PA_8, //D8
+ PA_9, //D9
+ PA_10, //D10
+ PA_11, //D11
+ PA_12, //D12
+ PA_13, //D13
+ PA_14, //D14
+ PA_15, //D15
+ PB_0, //D16
+ PB_1, //D17
+ PB_2, //D18
+ PB_3, //D19
+ PB_4, //D20
+ PB_5, //D21
+ PB_6, //D22
+ PB_7, //D23
+ PB_8, //D24
+ PB_9, //D25
+ PB_10, //D26
+ PB_11, //D27
+ PB_12, //D28
+ PB_13, //D29
+ PB_14, //D30
+ PB_15, //D31
+ PC_0, //D32
+ PC_1, //D33
+ PC_2, //D34
+ PC_3, //D35
+ PC_4, //D36
+ PC_5, //D37
+ PC_6, //D38
+ PC_7, //D39
+ PC_8, //D40
+ PC_9, //D41
+ PC_10, //D42
+ PC_11, //D43
+ PC_12, //D44
+ PC_13, //D45
+ PC_14, //D46
+ PC_15, //D47
+ PD_0, //D48
+ PD_1, //D49
+ PD_2, //D50
+ PD_3, //D51
+ PD_4, //D52
+ PD_5, //D53
+ PD_6, //D54
+ PD_7, //D55
+ PD_8, //D56
+ PD_9, //D57
+ PD_10, //D58
+ PD_11, //D59
+ PD_12, //D60
+ PD_13, //D61
+ PD_14, //D62
+ PD_15, //D63
+ PE_0, //D64
+ PE_1, //D65
+ PE_2, //D66
+ PE_3, //D67
+ PE_4, //D68
+ PE_5, //D69
+ PE_6, //D70
+ PE_7, //D71
+ PE_8, //D72
+ PE_9, //D73
+ PE_10, //D74
+ PE_11, //D75
+ PE_12, //D76
+ PE_13, //D77
+ PE_14, //D78
+ PE_15, //D79
+ PF_0, //D80
+ PF_1, //D81
+ PF_2, //D82
+ PF_3, //D83
+ PF_4, //D84
+ PF_5, //D85
+ PF_6, //D86
+ PF_7, //D87
+ PF_8, //D88
+ PF_9, //D89
+ PF_10, //D90
+ PF_11, //D91
+ PF_12, //D92
+ PF_13, //D93
+ PF_14, //D94
+ PF_15, //D95
+ PG_0, //D96
+ PG_1, //D97
+ PG_2, //D98
+ PG_3, //D99
+ PG_4, //D100
+ PG_5, //D101
+ PG_6, //D102
+ PG_7, //D103
+ PG_8, //D104
+ PG_9, //D105
+ PG_10, //D106
+ PG_11, //D107
+ PG_12, //D108
+ PG_13, //D109
+ PG_14, //D110
+ PG_15, //D111
+ PH_0, //D112
+ PH_1, //D113
+ PH_2, //D114
+ PH_3, //D115
+ PH_4, //D116
+ PH_5, //D117
+ PH_6, //D118
+ PH_7, //D119
+ PH_8, //D120
+ PH_9, //D121
+ PH_10, //D122
+ PH_11, //D123
+ PH_12, //D124
+ PH_13, //D125
+ PH_14, //D126
+ PH_15, //D127
+
+ //Duplicated ADC Pins
+ PC_3, //A0 T0 D128
+ PC_0, //A1 T1 D129
+ PC_2, //A2 BED D130
+};
+
+#ifdef __cplusplus
+}
+#endif
+
+// ----------------------------------------------------------------------------
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+uint32_t myvar[] = {1,2,3,4,5,6,7,8};
+void myshow(int fre, int times) // YSZ-WORK
+{
+ uint32_t index = 10;
+ RCC->AHB1ENR |= 1 << 6; // port G clock
+ GPIOG->MODER &= ~(3UL << 2 * index); // clear old mode
+ GPIOG->MODER |= 1 << 2 * index; // mode is output
+ GPIOG->OSPEEDR &= ~(3UL << 2 * index) // Clear old output speed
+ GPIOG->OSPEEDR |= 2 << 2 * index; // Set output speed
+ GPIOG->OTYPER &= ~(1UL << index) // clear old output
+ GPIOG->OTYPER |= 0 << index; // Set the output mode to push-pull
+ GPIOG->PUPDR &= ~(3 << 2 * index) // Clear the original settings first
+ GPIOG->PUPDR |= 1 << 2 * index; // Set new up and down
+ while (times != 0) {
+ GPIOG->BSRR = 1UL << index;
+ for (int i = 0; i < fre; i++)
+ for (int j = 0; j < 1000000; j++) __NOP();
+ GPIOG->BSRR = 1UL << (index + 16);
+ for (int i = 0; i < fre; i++)
+ for (int j = 0; j < 1000000; j++) __NOP();
+ if (times > 0) times--;
+ }
+}
+
+HAL_StatusTypeDef SDMMC_IsProgramming(SDIO_TypeDef *SDIOx,uint32_t RCA)
+{
+ HAL_SD_CardStateTypeDef CardState;
+ volatile uint32_t respR1 = 0, status = 0;
+ SDIO_CmdInitTypeDef sdmmc_cmdinit;
+ do {
+ sdmmc_cmdinit.Argument = RCA << 16;
+ sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SEND_STATUS;
+ sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT;
+ sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO;
+ sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE;
+ SDIO_SendCommand(SDIOx,&sdmmc_cmdinit); // send CMD13
+ do status = SDIOx->STA;
+ while (!(status & ((1 << 0) | (1 << 6) | (1 << 2)))); // wait for the operation to complete
+ if (status & (1 << 0)) { // CRC check failed
+ SDIOx->ICR |= 1 << 0; // clear error flag
+ return HAL_ERROR;
+ }
+ if (status & (1 << 2)) { // command timed out
+ SDIOx->ICR |= 1 << 2; // clear error flag
+ return HAL_ERROR;
+ }
+ if (SDIOx->RESPCMD != SDMMC_CMD_SEND_STATUS) return HAL_ERROR;
+ SDIOx->ICR = 0X5FF; // clear all tags
+ respR1 = SDIOx->RESP1;
+ CardState = (respR1 >> 9) & 0x0000000F;
+ } while ((CardState == HAL_SD_CARD_RECEIVING) || (CardState == HAL_SD_CARD_SENDING) || (CardState == HAL_SD_CARD_PROGRAMMING));
+ return HAL_OK;
+}
+
+void debugStr(const char *str) {
+ while (*str) {
+ while ((USART1->SR & 0x40) == 0);
+ USART1->DR = *str++;
+ }
+}
+
+/**
+ * @brief System Clock Configuration
+ * The system Clock is configured as follows:
+ * System Clock source = PLL (HSE)
+ * SYSCLK(Hz) = 168000000/120000000/180000000
+ * HCLK(Hz) = 168000000/120000000/180000000
+ * AHB Prescaler = 1
+ * APB1 Prescaler = 4
+ * APB2 Prescaler = 2
+ * HSE Frequency(Hz) = 8000000
+ * PLL_M = 8/4/8
+ * PLL_N = 336/120/360
+ * PLL_P = 2
+ * PLL_Q = 7/5/7
+ * VDD(V) = 3.3
+ * Main regulator output voltage = Scale1 mode
+ * Flash Latency(WS) = 5
+ * @param None
+ * @retval None
+ */
+WEAK void SystemClock_Config(void)
+{
+ RCC_ClkInitTypeDef RCC_ClkInitStruct;
+ RCC_OscInitTypeDef RCC_OscInitStruct;
+ RCC_PeriphCLKInitTypeDef PeriphClkInitStruct;
+ HAL_StatusTypeDef ret = HAL_OK;
+
+ __HAL_FLASH_INSTRUCTION_CACHE_ENABLE();
+ __HAL_FLASH_DATA_CACHE_ENABLE();
+ __HAL_FLASH_PREFETCH_BUFFER_ENABLE();
+ HAL_RCC_DeInit();
+
+ /* Enable Power Control clock */
+ __HAL_RCC_PWR_CLK_ENABLE();
+
+ /* The voltage scaling allows optimizing the power consumption when the device is
+ clocked below the maximum system frequency, to update the voltage scaling value
+ regarding system frequency refer to product datasheet. */
+ __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
+
+ /* Enable HSE Oscillator and activate PLL with HSE as source */
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
+ RCC_OscInitStruct.HSEState = RCC_HSE_ON;
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
+ RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
+ RCC_OscInitStruct.PLL.PLLM = 8;
+ RCC_OscInitStruct.PLL.PLLN = 336;
+ RCC_OscInitStruct.PLL.PLLP = 2;
+ RCC_OscInitStruct.PLL.PLLQ = 7;
+ RCC_OscInitStruct.PLL.PLLR = 2;
+ ret = HAL_RCC_OscConfig(&RCC_OscInitStruct);
+
+ if (ret != HAL_OK) myshow(10,-1);
+ HAL_PWREx_EnableOverDrive();
+
+ /* Select PLLSAI output as USB clock source */
+ PeriphClkInitStruct.PLLSAI.PLLSAIM = 8;
+ PeriphClkInitStruct.PLLSAI.PLLSAIN = 192;
+ PeriphClkInitStruct.PLLSAI.PLLSAIP = RCC_PLLSAIP_DIV4;
+ PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_CLK48 | RCC_PERIPHCLK_SDIO;
+ PeriphClkInitStruct.Clk48ClockSelection = RCC_CK48CLKSOURCE_PLLSAIP;
+ PeriphClkInitStruct.SdioClockSelection = RCC_SDIOCLKSOURCE_CLK48; // SDIO Clock Mux
+ HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct);
+
+ /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */
+ RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2);
+ RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
+ RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
+ RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4;
+ RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;
+ ret = HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5);
+ if (ret != HAL_OK) myshow(10,-1);
+
+ SystemCoreClockUpdate();
+ /* Configure the Systick interrupt time */
+ HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq() / 1000);
+
+ /* Configure the Systick */
+ HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK);
+
+ /* SysTick_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);
+ __enable_irq(); // Turn on the interrupt here because it is turned off in the bootloader
+}
+
+#ifdef __cplusplus
+}
+#endif
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/variant.h
new file mode 100644
index 00000000..082be940
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/variant.h
@@ -0,0 +1,243 @@
+/*
+ Copyright (c) 2011 Arduino. All right reserved.
+
+ This library is free software; you can redistribute it and/or
+ modify it under the terms of the GNU Lesser General Public
+ License as published by the Free Software Foundation; either
+ version 2.1 of the License, or (at your option) any later version.
+
+ This library 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 Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with this library; if not, write to the Free Software
+ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+*/
+
+#ifndef _VARIANT_ARDUINO_STM32_
+#define _VARIANT_ARDUINO_STM32_
+
+#ifdef __cplusplus
+extern "C" {
+#endif // __cplusplus
+
+extern unsigned long myvar[];
+void myshow(int fre, int times);
+void debugStr(const char *str);
+
+/*----------------------------------------------------------------------------
+ * Pins
+ *----------------------------------------------------------------------------*/
+
+#define PA0 0x00
+#define PA1 0x01
+#define PA2 0x02
+#define PA3 0x03
+#define PA4 0x04
+#define PA5 0x05
+#define PA6 0x06
+#define PA7 0x07
+#define PA8 0x08
+#define PA9 0x09
+#define PA10 0x0A
+#define PA11 0x0B
+#define PA12 0x0C
+#define PA13 0x0D
+#define PA14 0x0E
+#define PA15 0x0F
+
+#define PB0 0x10
+#define PB1 0x11
+#define PB2 0x12
+#define PB3 0x13
+#define PB4 0x14
+#define PB5 0x15
+#define PB6 0x16
+#define PB7 0x17 // 36 pins (F103T)
+#define PB8 0x18
+#define PB9 0x19
+#define PB10 0x1A
+#define PB11 0x1B
+#define PB12 0x1C
+#define PB13 0x1D
+#define PB14 0x1E
+#define PB15 0x1F
+
+#define PC0 0x20
+#define PC1 0x21
+#define PC2 0x22
+#define PC3 0x23
+#define PC4 0x24
+#define PC5 0x25
+#define PC6 0x26
+#define PC7 0x27
+#define PC8 0x28
+#define PC9 0x29
+#define PC10 0x2A
+#define PC11 0x2B
+#define PC12 0x2C
+#define PC13 0x2D
+#define PC14 0x2E
+#define PC15 0x2F
+
+#define PD0 0x30
+#define PD1 0x31
+#define PD2 0x32 // 64 pins (F103R)
+#define PD3 0x33
+#define PD4 0x34
+#define PD5 0x35
+#define PD6 0x36
+#define PD7 0x37
+#define PD8 0x38
+#define PD9 0x39
+#define PD10 0x3A
+#define PD11 0x3B
+#define PD12 0x3C
+#define PD13 0x3D
+#define PD14 0x3E
+#define PD15 0x3F
+
+#define PE0 0x40
+#define PE1 0x41
+#define PE2 0x42
+#define PE3 0x43
+#define PE4 0x44
+#define PE5 0x45
+#define PE6 0x46
+#define PE7 0x47
+#define PE8 0x48
+#define PE9 0x49
+#define PE10 0x4A
+#define PE11 0x4B
+#define PE12 0x4C
+#define PE13 0x4D
+#define PE14 0x4E
+#define PE15 0x4F // 100 pins (F446V)
+
+#define PF0 0x50
+#define PF1 0x51
+#define PF2 0x52
+#define PF3 0x53
+#define PF4 0x54
+#define PF5 0x55
+#define PF6 0x56
+#define PF7 0x57
+#define PF8 0x58
+#define PF9 0x59
+#define PF10 0x5A
+#define PF11 0x5B
+#define PF12 0x5C
+#define PF13 0x5D
+#define PF14 0x5E
+#define PF15 0x5F
+
+#define PG0 0x60
+#define PG1 0x61
+#define PG2 0x62
+#define PG3 0x63
+#define PG4 0x64
+#define PG5 0x65
+#define PG6 0x66
+#define PG7 0x67
+#define PG8 0x68
+#define PG9 0x69
+#define PG10 0x6A
+#define PG11 0x6B
+#define PG12 0x6C
+#define PG13 0x6D
+#define PG14 0x6E
+#define PG15 0x6F
+
+#define PH0 0x70
+#define PH1 0x71
+#define PH2 0x72
+#define PH3 0x73
+#define PH4 0x74
+#define PH5 0x75
+#define PH6 0x76
+#define PH7 0x77
+#define PH8 0x78
+#define PH9 0x79
+#define PH10 0x7A
+#define PH11 0x7B
+#define PH12 0x7C
+#define PH13 0x7D
+#define PH14 0x7E
+#define PH15 0x7F // 144 pins (F446Z)
+
+// This must be a literal with the same value as PEND
+#define NUM_DIGITAL_PINS 0x80
+// This must be a literal with a value less than or equal to to MAX_ANALOG_INPUTS
+#define NUM_ANALOG_INPUTS 3
+#define NUM_ANALOG_FIRST 128
+
+// PWM resolution
+// #define PWM_RESOLUTION 12
+#define PWM_FREQUENCY 20000 // >= 20 Khz => inaudible noise for fans
+#define PWM_MAX_DUTY_CYCLE 255
+
+// SPI Definitions
+// #define PIN_SPI_SS PG15
+// #define PIN_SPI_MOSI PB5
+// #define PIN_SPI_MISO PB4
+// #define PIN_SPI_SCK PB3
+
+// I2C Definitions
+#define PIN_WIRE_SDA PB9
+#define PIN_WIRE_SCL PB8
+#define PIN_I2C_WP PB7
+#define EEPROM_DEVICE_ADDRESS 0x50
+
+// Timer Definitions
+// Do not use timer used by PWM pin. See PinMap_PWM.
+#define TIMER_TONE TIM8
+#define TIMER_SERVO TIM5
+#define TIMER_SERIAL TIM7
+
+// UART Definitions
+//#define SERIAL_UART_INSTANCE 1 // Connected to EXP3 header
+/* Enable Serial 3 */
+#define HAVE_HWSERIAL1
+// #define HAVE_HWSERIAL3
+
+// Default pin used for 'Serial' instance (ex: ST-Link)
+// Mandatory for Firmata
+#define PIN_SERIAL_RX PA10
+#define PIN_SERIAL_TX PA9
+
+/* HAL configuration */
+#define HSE_VALUE 8000000U
+
+#define FLASH_PAGE_SIZE (4U * 1024U)
+
+#ifdef __cplusplus
+} // extern "C"
+#endif
+
+/*----------------------------------------------------------------------------
+ * Arduino objects - C++ only
+ *----------------------------------------------------------------------------*/
+
+#ifdef __cplusplus
+// These serial port names are intended to allow libraries and architecture-neutral
+// sketches to automatically default to the correct port name for a particular type
+// of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN,
+// the first hardware serial port whose RX/TX pins are not dedicated to another use.
+//
+// SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor
+//
+// SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial
+//
+// SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library
+//
+// SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins.
+//
+// SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX
+// pins are NOT connected to anything by default.
+#define SERIAL_PORT_MONITOR Serial
+#define SERIAL_PORT_HARDWARE_OPEN Serial
+#endif
+
+#endif /* _VARIANT_ARDUINO_STM32_ */
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_SPIDER_KING407/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_SPIDER_KING407/PeripheralPins.c
new file mode 100644
index 00000000..5c7c301f
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_SPIDER_KING407/PeripheralPins.c
@@ -0,0 +1,399 @@
+/*
+ *******************************************************************************
+ * Copyright (c) 2019, STMicroelectronics
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *******************************************************************************
+ * Automatically generated from STM32F407Z(E-G)Tx.xml
+ */
+#include
+#include
+
+/* =====
+ * Note: Commented lines are alternative possibilities which are not used per default.
+ * If you change them, you will have to know what you do
+ * =====
+ */
+
+//*** ADC ***
+
+#ifdef HAL_ADC_MODULE_ENABLED
+WEAK const PinMap PinMap_ADC[] = {
+ //{PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0
+ //{PA_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0
+ //{PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0
+ //{PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1
+ //{PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1
+ //{PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1
+ {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 LCD RX
+ //{PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2
+ //{PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2
+ {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 LCD TX
+ //{PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3
+ //{PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3
+ //{PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4
+ //{PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4
+ //{PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5
+ //{PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5
+ //{PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6
+ //{PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6
+ //{PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7
+ //{PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7
+ //{PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8
+ //{PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8
+ //{PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9
+ //{PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9
+ {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10
+ //{PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10
+ //{PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10
+ {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11
+ //{PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11
+ //{PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11
+ {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12
+ //{PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12
+ //{PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12
+ {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13
+ //{PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13
+ //{PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13
+ //{PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14
+ //{PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14
+ //{PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15
+ //{PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15
+ //{PF_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9
+ //{PF_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14
+ //{PF_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15
+ //{PF_6, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4
+ //{PF_7, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5
+ //{PF_8, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6
+ {PF_9, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC3_IN7
+ {PF_10, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC3_IN8
+ {NC, NP, 0}
+};
+#endif
+
+//*** DAC ***
+
+#ifdef HAL_DAC_MODULE_ENABLED
+WEAK const PinMap PinMap_DAC[] = {
+ //{PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1
+ //{PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2
+ {NC, NP, 0}
+};
+#endif
+
+//*** I2C ***
+
+#ifdef HAL_I2C_MODULE_ENABLED
+WEAK const PinMap PinMap_I2C_SDA[] = {
+ {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
+ {PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
+ {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
+ {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
+ {PF_0, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
+ {NC, NP, 0}
+};
+
+WEAK const PinMap PinMap_I2C_SCL[] = {
+ {PA_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
+ {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
+ {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
+ {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
+ {PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** PWM ***
+
+#ifdef HAL_TIM_MODULE_ENABLED
+WEAK const PinMap PinMap_PWM[] = {
+ //{PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
+ // {PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1
+ // {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
+ //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2
+ // {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
+ //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3
+ // {PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1
+ // {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
+ //{PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4
+ // {PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2
+ //{PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
+ // {PA_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N
+ // {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
+ //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1
+ // {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
+ // {PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
+ // {PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N
+ //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1
+ //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
+ //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
+ //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
+ //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
+ {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 HEATER_4_PIN
+ // {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
+ // {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
+ {PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N HEATER_1_PIN
+ // {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
+ // {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
+ //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N
+ //{PB_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
+ //{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
+ {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 HEATER_0_PIN
+ //{PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
+ //{PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1
+ //{PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2
+ //{PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3
+ // {PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1
+ // {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
+ //{PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1
+ //{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
+ //{PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
+ //{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
+ // {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
+ // {PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N
+ //{PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1
+ // {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
+ // {PB_15, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N
+ //{PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 2, 0)}, // TIM12_CH2
+ //{PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
+ // {PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1
+ // {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
+ //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2
+ // {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
+ {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 HEATER_3_PIN
+ // {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
+ //{PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4
+ {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 FAN3
+ {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 HEATER_2_PIN
+ {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 FAN4
+ {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 FAN2_PIN
+ //{PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1
+ //{PE_6, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2
+ {PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N FAN_PIN
+ {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 FAN1_PIN
+ {PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N HEATER_BED_PIN
+ //{PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
+ //{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
+ //{PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
+ //{PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
+ {NC, NP, 0}
+};
+#endif
+
+//*** SERIAL ***
+
+#ifdef HAL_UART_MODULE_ENABLED
+WEAK const PinMap PinMap_UART_TX[] = {
+ //{PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
+ {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ //{PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ //{PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ //{PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
+ //{PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
+ //{PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ //{PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)},
+ //{PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ //{PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ {NC, NP, 0}
+};
+
+WEAK const PinMap PinMap_UART_RX[] = {
+ //{PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
+ {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ //{PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ //{PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ //{PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
+ // {PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
+ //{PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ //{PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)},
+ //{PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ //{PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ {NC, NP, 0}
+};
+
+WEAK const PinMap PinMap_UART_RTS[] = {
+ //{PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ //{PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ //{PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ //{PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ //{PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ //{PG_8, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
+ //{PG_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
+ {NC, NP, 0}
+};
+
+WEAK const PinMap PinMap_UART_CTS[] = {
+ //{PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ //{PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ //{PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ //{PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
+ //{PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ //{PG_13, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
+ //{PG_15, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** SPI ***
+
+#ifdef HAL_SPI_MODULE_ENABLED
+WEAK const PinMap PinMap_SPI_MOSI[] = {
+ {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ //{PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ //{PB_5, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ //{PC_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ //{PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {NC, NP, 0}
+};
+
+WEAK const PinMap PinMap_SPI_MISO[] = {
+ {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ //{PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ //{PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ //{PC_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ //{PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {NC, NP, 0}
+};
+
+WEAK const PinMap PinMap_SPI_SCLK[] = {
+ {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ //{PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ //{PB_3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ //{PB_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ //{PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {NC, NP, 0}
+};
+
+WEAK const PinMap PinMap_SPI_SSEL[] = {
+ {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ //{PA_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ //{PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ //{PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ //{PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** CAN ***
+
+#ifdef HAL_CAN_MODULE_ENABLED
+WEAK const PinMap PinMap_CAN_RD[] = {
+ //{PA_11, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
+ //{PB_5, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
+ {PB_8, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
+ //{PB_12, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
+ //{PD_0, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
+ {NC, NP, 0}
+};
+
+WEAK const PinMap PinMap_CAN_TD[] = {
+ //{PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
+ //{PB_6, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
+ {PB_9, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
+ //{PB_13, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
+ //{PD_1, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** ETHERNET ***
+
+#ifdef HAL_ETH_MODULE_ENABLED
+WEAK const PinMap PinMap_Ethernet[] = {
+ /*
+ {PA_0, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS
+ {PA_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_REF_CLK|ETH_RX_CLK
+ {PA_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDIO
+ {PA_3, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_COL
+ {PA_7, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS_DV|ETH_RX_DV
+ {PB_0, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD2
+ {PB_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD3
+ {PB_5, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_PPS_OUT
+ {PB_8, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3
+ {PB_10, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RX_ER
+ {PB_11, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_EN
+ {PB_12, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD0
+ {PB_13, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD1
+ {PC_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDC
+ {PC_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD2
+ {PC_3, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_CLK
+ {PC_4, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD0
+ {PC_5, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD1
+ {PE_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3
+ {PG_8, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_PPS_OUT
+ {PG_11, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_EN
+ {PG_13, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD0
+ {PG_14, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD1
+ {NC, NP, 0}
+ */
+};
+#endif
+
+//*** No QUADSPI ***
+
+//*** USB ***
+
+#ifdef HAL_PCD_MODULE_ENABLED
+WEAK const PinMap PinMap_USB_OTG_FS[] = {
+ //{PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF
+ //{PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS
+ //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID
+ {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM
+ {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP
+ {NC, NP, 0}
+};
+
+WEAK const PinMap PinMap_USB_OTG_HS[] = {
+ /*
+ #ifdef USE_USB_HS_IN_FS
+ {PA_4, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_SOF
+ {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID
+ {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS
+ {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM
+ {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP
+ #else
+ {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0
+ {PA_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_CK
+ {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1
+ {PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2
+ {PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7
+ {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3
+ {PB_11, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D4
+ {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5
+ {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6
+ {PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP
+ {PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR
+ {PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT
+ #endif // USE_USB_HS_IN_FS
+ */
+ {NC, NP, 0}
+};
+#endif
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_SPIDER_KING407/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_SPIDER_KING407/PinNamesVar.h
new file mode 100644
index 00000000..b4bb9d45
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_SPIDER_KING407/PinNamesVar.h
@@ -0,0 +1,50 @@
+/* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
+/* USB */
+#ifdef USBCON
+ USB_OTG_FS_SOF = PA_8,
+ USB_OTG_FS_VBUS = PA_9,
+ USB_OTG_FS_ID = PA_10,
+ USB_OTG_FS_DM = PA_11,
+ USB_OTG_FS_DP = PA_12,
+ USB_OTG_HS_ULPI_D0 = PA_3,
+ USB_OTG_HS_SOF = PA_4,
+ USB_OTG_HS_ULPI_CK = PA_5,
+ USB_OTG_HS_ULPI_D1 = PB_0,
+ USB_OTG_HS_ULPI_D2 = PB_1,
+ USB_OTG_HS_ULPI_D7 = PB_5,
+ USB_OTG_HS_ULPI_D3 = PB_10,
+ USB_OTG_HS_ULPI_D4 = PB_11,
+ USB_OTG_HS_ID = PB_12,
+ USB_OTG_HS_ULPI_D5 = PB_12,
+ USB_OTG_HS_ULPI_D6 = PB_13,
+ USB_OTG_HS_VBUS = PB_13,
+ USB_OTG_HS_DM = PB_14,
+ USB_OTG_HS_DP = PB_15,
+ USB_OTG_HS_ULPI_STP = PC_0,
+ USB_OTG_HS_ULPI_DIR = PC_2,
+ USB_OTG_HS_ULPI_NXT = PC_3,
+#endif
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_SPIDER_KING407/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_SPIDER_KING407/ldscript.ld
new file mode 100644
index 00000000..f7e09b8e
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_SPIDER_KING407/ldscript.ld
@@ -0,0 +1,204 @@
+/*
+*****************************************************************************
+**
+
+** File : LinkerScript.ld
+**
+** Abstract : Linker script for STM32F407ZGTx Device with
+** 1024KByte FLASH, 128KByte RAM
+**
+** Set heap size, stack size and stack location according
+** to application requirements.
+**
+** Set memory bank area and size if external memory is used.
+**
+** Target : STMicroelectronics STM32
+**
+**
+** Distribution: The file is distributed as is, without any warranty
+** of any kind.
+**
+*****************************************************************************
+** @attention
+**
+** Copyright (c) 2014 Ac6
+**
+** Redistribution and use in source and binary forms, with or without modification,
+** are permitted provided that the following conditions are met:
+** 1. Redistributions of source code must retain the above copyright notice,
+** this list of conditions and the following disclaimer.
+** 2. Redistributions in binary form must reproduce the above copyright notice,
+** this list of conditions and the following disclaimer in the documentation
+** and/or other materials provided with the distribution.
+** 3. Neither the name of Ac6 nor the names of its contributors
+** may be used to endorse or promote products derived from this software
+** without specific prior written permission.
+**
+** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+**
+*****************************************************************************
+*/
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = 0x20020000; /* end of RAM */
+/* Generate a link error if heap and stack don't fit into RAM */
+_Min_Heap_Size = 0x200;; /* required amount of heap */
+_Min_Stack_Size = 0x400;; /* required amount of stack */
+
+/* Specify the memory areas */
+MEMORY
+{
+FLASH (rx) : ORIGIN = 0x8008000, LENGTH = 1024K
+RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
+CCMRAM (rw) : ORIGIN = 0x10000000, LENGTH = 64K
+}
+
+/* Define output sections */
+SECTIONS
+{
+ /* The startup code goes first into FLASH */
+ .isr_vector :
+ {
+ . = ALIGN(4);
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(4);
+ } >FLASH
+
+ /* The program code and other data goes into FLASH */
+ .text ALIGN(4):
+ {
+ . = ALIGN(4);
+ *(.text) /* .text sections (code) */
+ *(.text*) /* .text* sections (code) */
+ *(.glue_7) /* glue arm to thumb code */
+ *(.glue_7t) /* glue thumb to arm code */
+ *(.eh_frame)
+
+ KEEP (*(.init))
+ KEEP (*(.fini))
+
+ . = ALIGN(4);
+ _etext = .; /* define a global symbols at end of code */
+ } >FLASH
+
+ /* Constant data goes into FLASH */
+ .rodata ALIGN(4):
+ {
+ . = ALIGN(4);
+ *(.rodata) /* .rodata sections (constants, strings, etc.) */
+ *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
+ . = ALIGN(4);
+ } >FLASH
+
+ .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
+ .ARM : {
+ __exidx_start = .;
+ *(.ARM.exidx*)
+ __exidx_end = .;
+ } >FLASH
+
+ .preinit_array :
+ {
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array*))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ } >FLASH
+ .init_array :
+ {
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array*))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ } >FLASH
+ .fini_array :
+ {
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT(.fini_array.*)))
+ KEEP (*(.fini_array*))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ } >FLASH
+
+ /* used by the startup to initialize data */
+ _sidata = LOADADDR(.data);
+
+ /* Initialized data sections goes into RAM, load LMA copy after code */
+ .data :
+ {
+ . = ALIGN(4);
+ _sdata = .; /* create a global symbol at data start */
+ *(.data) /* .data sections */
+ *(.data*) /* .data* sections */
+
+ . = ALIGN(4);
+ _edata = .; /* define a global symbol at data end */
+ } >RAM AT> FLASH
+
+ _siccmram = LOADADDR(.ccmram);
+
+ /* CCM-RAM section
+ *
+ * IMPORTANT NOTE!
+ * If initialized variables will be placed in this section,
+ * the startup code needs to be modified to copy the init-values.
+ */
+ .ccmram :
+ {
+ . = ALIGN(4);
+ _sccmram = .; /* create a global symbol at ccmram start */
+ *(.ccmram)
+ *(.ccmram*)
+
+ . = ALIGN(4);
+ _eccmram = .; /* create a global symbol at ccmram end */
+ } >CCMRAM AT> FLASH
+
+
+ /* Uninitialized data section */
+ . = ALIGN(4);
+ .bss :
+ {
+ /* This is used by the startup in order to initialize the .bss section */
+ _sbss = .; /* define a global symbol at bss start */
+ __bss_start__ = _sbss;
+ *(.bss)
+ *(.bss*)
+ *(COMMON)
+
+ . = ALIGN(4);
+ _ebss = .; /* define a global symbol at bss end */
+ __bss_end__ = _ebss;
+ } >RAM
+
+ /* User_heap_stack section, used to check that there is enough RAM left */
+ ._user_heap_stack :
+ {
+ . = ALIGN(4);
+ PROVIDE ( end = . );
+ PROVIDE ( _end = . );
+ . = . + _Min_Heap_Size;
+ . = . + _Min_Stack_Size;
+ . = ALIGN(4);
+ } >RAM
+
+ /* Remove information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+}
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_SPIDER_KING407/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_SPIDER_KING407/variant.cpp
new file mode 100644
index 00000000..1c7aedd9
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_SPIDER_KING407/variant.cpp
@@ -0,0 +1,212 @@
+/*
+ *******************************************************************************
+ * Copyright (c) 2017, STMicroelectronics
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *******************************************************************************
+ */
+
+#include "pins_arduino.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+const PinName digitalPin[] = {
+PA_1,
+PA_2,
+PA_3,
+PA_4,
+PA_5,
+PA_6,
+PA_7,
+PA_8,
+PA_9,
+PA_10,
+PA_11,
+PA_12,
+PA_13,
+PA_14,
+PA_15,
+PB_0,
+PB_1,
+PB_2,
+PB_3,
+PB_4,
+PB_5,
+PB_6,
+PB_7,
+PB_8,
+PB_9,
+PB_10,
+PB_11,
+PB_12,
+PB_13,
+PB_14,
+PB_15,
+PC_2,
+PC_3,
+PC_4,
+PC_5,
+PC_6,
+PC_7,
+PC_8,
+PC_9,
+PC_10,
+PC_11,
+PC_12,
+PC_13,
+PC_14,
+PC_15,
+PD_0,
+PD_1,
+PD_2,
+PD_3,
+PD_4,
+PD_5,
+PD_6,
+PD_7,
+PD_8,
+PD_9,
+PD_10,
+PD_11,
+PD_12,
+PD_13,
+PD_14,
+PD_15,
+PE_0,
+PE_1,
+PE_11,
+PE_3,
+PE_4,
+PE_5,
+PE_6,
+PE_7,
+PE_8,
+PE_9,
+PE_10,
+PE_2,
+PE_12,
+PE_13,
+PE_14,
+PE_15,
+PF_0,
+PF_1,
+PF_2,
+PF_6,
+PF_7,
+PF_8,
+PF_9,
+PF_11,
+PF_12,
+PF_13,
+PF_14,
+PF_15,
+PG_0,
+PG_1,
+PG_2,
+PG_3,
+PG_4,
+PG_5,
+PG_6,
+PG_7,
+PG_8,
+PG_9,
+PG_10,
+PG_11,
+PG_12,
+PG_13,
+PG_14,
+PG_15,
+PH_0,
+PH_1,
+PA_0,
+PC_1,
+PC_0,
+PF_10,
+PF_5,
+PF_4,
+PF_3,
+};
+
+#ifdef __cplusplus
+}
+#endif
+
+// ----------------------------------------------------------------------------
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @brief System Clock Configuration
+ * @param None
+ * @retval None
+ */
+WEAK void SystemClock_Config(void)
+{
+
+ RCC_OscInitTypeDef RCC_OscInitStruct;
+ RCC_ClkInitTypeDef RCC_ClkInitStruct;
+
+ /**Configure the main internal regulator output voltage
+ */
+ __HAL_RCC_PWR_CLK_ENABLE();
+
+ __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
+
+ /**Initializes the CPU, AHB and APB busses clocks
+ */
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
+ RCC_OscInitStruct.HSEState = RCC_HSE_ON;
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
+ RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
+ RCC_OscInitStruct.PLL.PLLM = 8;
+ RCC_OscInitStruct.PLL.PLLN = 336;
+ RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
+ RCC_OscInitStruct.PLL.PLLQ = 7;
+ if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
+ _Error_Handler(__FILE__, __LINE__);
+ }
+
+ /**Initializes the CPU, AHB and APB busses clocks
+ */
+ RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK
+ | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
+ RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
+ RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
+ RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4;
+ RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;
+
+ if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK) {
+ _Error_Handler(__FILE__, __LINE__);
+ }
+}
+
+#ifdef __cplusplus
+}
+#endif
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_SPIDER_KING407/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_SPIDER_KING407/variant.h
new file mode 100644
index 00000000..727c0d07
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_SPIDER_KING407/variant.h
@@ -0,0 +1,237 @@
+/*
+ *******************************************************************************
+ * Copyright (c) 2017, STMicroelectronics
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *******************************************************************************
+ */
+#pragma once
+
+#ifdef __cplusplus
+extern "C" {
+#endif // __cplusplus
+
+/*----------------------------------------------------------------------------
+ * Pins
+ *----------------------------------------------------------------------------*/
+
+
+#define PA1 0
+#define PA2 1
+#define PA3 2
+#define PA4 3
+#define PA5 4
+#define PA6 5
+#define PA7 6
+#define PA8 7
+#define PA9 8
+#define PA10 9
+#define PA11 10
+#define PA12 11
+#define PA13 12
+#define PA14 13
+#define PA15 14
+#define PB0 15
+#define PB1 16
+#define PB2 17
+#define PB3 18
+#define PB4 19
+#define PB5 20
+#define PB6 21
+#define PB7 22
+#define PB8 23
+#define PB9 24
+#define PB10 25
+#define PB11 26
+#define PB12 27
+#define PB13 28
+#define PB14 29
+#define PB15 30
+#define PC2 31
+#define PC3 32
+#define PC4 33
+#define PC5 34
+#define PC6 35
+#define PC7 36
+#define PC8 37
+#define PC9 38
+#define PC10 39
+#define PC11 40
+#define PC12 41
+#define PC13 42
+#define PC14 43
+#define PC15 44
+#define PD0 45
+#define PD1 46
+#define PD2 47
+#define PD3 48
+#define PD4 49
+#define PD5 50
+#define PD6 51
+#define PD7 52
+#define PD8 53
+#define PD9 54
+#define PD10 55
+#define PD11 56
+#define PD12 57
+#define PD13 58
+#define PD14 59
+#define PD15 60
+#define PE0 61
+#define PE1 62
+#define PE11 63
+#define PE3 64
+#define PE4 65
+#define PE5 66
+#define PE6 67
+#define PE7 68
+#define PE8 69
+#define PE9 70
+#define PE10 71
+#define PE2 72
+#define PE12 73
+#define PE13 74
+#define PE14 75
+#define PE15 76
+#define PF0 77
+#define PF1 78
+#define PF2 79
+#define PF6 80
+#define PF7 81
+#define PF8 82
+#define PF9 83
+#define PF11 84
+#define PF12 85
+#define PF13 86
+#define PF14 87
+#define PF15 88
+#define PG0 89
+#define PG1 90
+#define PG2 91
+#define PG3 92
+#define PG4 93
+#define PG5 94
+#define PG6 95
+#define PG7 96
+#define PG8 97
+#define PG9 98
+#define PG10 99
+#define PG11 100
+#define PG12 101
+#define PG13 102
+#define PG14 103
+#define PG15 104
+#define PH0 105
+#define PH1 106
+#define PA0 107
+#define PC1 108
+#define PC0 109
+#define PF10 110
+#define PF5 111
+#define PF4 112
+#define PF3 113
+
+// This must be a literal
+#define NUM_DIGITAL_PINS 114
+// This must be a literal with a value less than or equal to MAX_ANALOG_INPUTS
+#define NUM_ANALOG_INPUTS 7
+#define NUM_ANALOG_FIRST 107
+
+
+// Below SPI and I2C definitions already done in the core
+// Could be redefined here if differs from the default one
+// SPI Definitions
+#define PIN_SPI_SS PA4
+#define PIN_SPI_MOSI PA7
+#define PIN_SPI_MISO PA6
+#define PIN_SPI_SCK PA5
+
+// I2C Definitions
+#define PIN_WIRE_SDA PF0
+#define PIN_WIRE_SCL PF1
+
+// Timer Definitions
+// Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c
+#define TIMER_TONE TIM2
+#define TIMER_SERVO TIM5
+#define TIMER_SERIAL TIM7
+
+// UART Definitions
+#define ENABLE_HWSERIAL1
+#define ENABLE_HWSERIAL2
+// Define here Serial instance number to map on Serial generic name
+//#define SERIAL_UART_INSTANCE 1 //1 for Serial = Serial1 (USART1)
+// DEBUG_UART could be redefined to print on another instance than 'Serial'
+//#define DEBUG_UART ((USART_TypeDef *) U(S)ARTX) // ex: USART3
+// DEBUG_UART baudrate, default: 9600 if not defined
+//#define DEBUG_UART_BAUDRATE x
+// DEBUG_UART Tx pin name, default: the first one found in PinMap_UART_TX for DEBUG_UART
+//#define DEBUG_PINNAME_TX PX_n // PinName used for TX
+
+// Default pin used for 'Serial' instance (ex: ST-Link)
+// Mandatory for Firmata
+#define PIN_SERIAL_RX PA10
+#define PIN_SERIAL_TX PA9
+
+// Optional PIN_SERIALn_RX and PIN_SERIALn_TX where 'n' is the U(S)ART number
+// Used when user instantiate a hardware Serial using its peripheral name.
+// Example: HardwareSerial mySerial(USART3);
+// will use PIN_SERIAL3_RX and PIN_SERIAL3_TX if defined.
+#define PIN_SERIAL1_RX PA10
+#define PIN_SERIAL1_TX PA9
+#define PIN_SERIAL2_RX PA3
+#define PIN_SERIAL2_TX PA2
+
+/* HAL configuration */
+#define HSE_VALUE 8000000U
+
+#ifdef __cplusplus
+} // extern "C"
+#endif
+/*----------------------------------------------------------------------------
+ * Arduino objects - C++ only
+ *----------------------------------------------------------------------------*/
+
+#ifdef __cplusplus
+// These serial port names are intended to allow libraries and architecture-neutral
+// sketches to automatically default to the correct port name for a particular type
+// of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN,
+// the first hardware serial port whose RX/TX pins are not dedicated to another use.
+//
+// SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor
+//
+// SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial
+//
+// SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library
+//
+// SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins.
+//
+// SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX
+// pins are NOT connected to anything by default.
+#define SERIAL_PORT_MONITOR Serial
+#define SERIAL_PORT_HARDWARE Serial1
+#define SERIAL_PORT_HARDWARE_OPEN Serial2
+#endif
+
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_MKS_SKIPR_V1/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_MKS_SKIPR_V1/PeripheralPins.c
new file mode 100644
index 00000000..11f5cc5a
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_MKS_SKIPR_V1/PeripheralPins.c
@@ -0,0 +1,169 @@
+/*
+ *******************************************************************************
+ * Copyright (c) 2016, STMicroelectronics
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *******************************************************************************
+ */
+#include "Arduino.h"
+#include "PeripheralPins.h"
+
+// =====
+// Note: Commented lines are alternative possibilities which are not used per default.
+// If you change them, you will have to know what you do
+// =====
+
+//*** ADC ***
+
+#ifdef HAL_ADC_MODULE_ENABLED
+WEAK const PinMap PinMap_ADC[] = {
+ {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 THBED
+ {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 TH0
+ {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 TH1
+ {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 TH2
+ {NC, NP, 0}
+};
+#endif
+
+//*** I2C ***
+
+#ifdef HAL_I2C_MODULE_ENABLED
+WEAK const PinMap PinMap_I2C_SDA[] = {
+ {PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
+ {NC, NP, 0}
+};
+
+WEAK const PinMap PinMap_I2C_SCL[] = {
+ {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** PWM ***
+
+#ifdef HAL_TIM_MODULE_ENABLED
+// Some pins can perform PWM from more than one timer. These were selected to utilize as many channels as
+// possible from timers which were already dedicated to PWM output.
+
+// TIM1 = HEATER0, HEATER1, [SERVO]
+// TIM2 = FAN1, FAN2, [BEEPER]
+// TIM4 = HEATER_BED
+// TIM5 = HEATER2, FAN0
+
+WEAK const PinMap PinMap_PWM[] = {
+ {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 Fan2
+ {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 Fan1
+ {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 Fan0
+ {PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 HE2
+ {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 Servo
+ {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N HE1
+ {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N HE0
+ {PB_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 BEEPER
+ {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 HOTBED
+ {NC, NP, 0}
+};
+#endif
+
+//*** SERIAL ***
+
+#ifdef HAL_UART_MODULE_ENABLED
+WEAK const PinMap PinMap_UART_TX[] = {
+ {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ {NC, NP, 0}
+};
+
+WEAK const PinMap PinMap_UART_RX[] = {
+ {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
+ {PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
+ {NC, NP, 0}
+};
+
+WEAK const PinMap PinMap_UART_RTS[] = {
+ {NC, NP, 0}
+};
+
+WEAK const PinMap PinMap_UART_CTS[] = {
+ {NC, NP, 0}
+};
+#endif
+
+//*** SPI ***
+
+#ifdef HAL_SPI_MODULE_ENABLED
+WEAK const PinMap PinMap_SPI_MOSI[] = {
+ {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {NC, NP, 0}
+};
+
+WEAK const PinMap PinMap_SPI_MISO[] = {
+ {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ {PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {NC, NP, 0}
+};
+
+WEAK const PinMap PinMap_SPI_SCLK[] = {
+ {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ {PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
+ {NC, NP, 0}
+};
+
+WEAK const PinMap PinMap_SPI_SSEL[] = {
+ {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** CAN ***
+
+#ifdef HAL_CAN_MODULE_ENABLED
+WEAK const PinMap PinMap_CAN_RD[] = {
+ {PB_12, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
+ {NC, NP, 0}
+};
+
+const PinMap PinMap_CAN_TD[] = {
+ {PB_13, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
+ {NC, NP, 0}
+};
+#endif
+
+//*** USB ***
+
+// If anyone for some unfathomable reason want to run gcode from Marlin's USB-C drive at 12Mbps - you can
+#ifdef HAL_PCD_MODULE_ENABLED
+WEAK const PinMap PinMap_USB_OTG_FS[] = {
+ {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM
+ {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP
+ {NC, NP, 0}
+};
+
+WEAK const PinMap PinMap_USB_OTG_HS[] = {
+ {NC, NP, 0}
+};
+#endif
+
+
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_MKS_SKIPR_V1/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_MKS_SKIPR_V1/PinNamesVar.h
new file mode 100644
index 00000000..bff3f213
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_MKS_SKIPR_V1/PinNamesVar.h
@@ -0,0 +1,30 @@
+/* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0, /* SYS_WKUP0 */
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
+/* USB */
+#ifdef USBCON
+ USB_OTG_FS_DM = PA_11,
+ USB_OTG_FS_DP = PA_12,
+#endif
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_MKS_SKIPR_V1/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_MKS_SKIPR_V1/hal_conf_extra.h
new file mode 100644
index 00000000..2ca9df2e
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_MKS_SKIPR_V1/hal_conf_extra.h
@@ -0,0 +1,496 @@
+/**
+ ******************************************************************************
+ * @file stm32f4xx_hal_conf_template.h
+ * @author MCD Application Team
+ * @brief HAL configuration template file.
+ * This file should be copied to the application folder and renamed
+ * to stm32f4xx_hal_conf.h.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2017 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_HAL_CONF_H
+#define __STM32F4xx_HAL_CONF_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/* ########################## Module Selection ############################## */
+/**
+ * @brief This is the list of modules to be used in the HAL driver
+ */
+#define HAL_MODULE_ENABLED
+#define HAL_ADC_MODULE_ENABLED
+#define HAL_CAN_LEGACY_MODULE_ENABLED
+#define HAL_CRC_MODULE_ENABLED
+#define HAL_DAC_MODULE_ENABLED
+#define HAL_DMA_MODULE_ENABLED
+#define HAL_EXTI_MODULE_ENABLED // Needed for Endstop (and other external) Interrupts
+#define HAL_GPIO_MODULE_ENABLED
+#define HAL_I2C_MODULE_ENABLED
+#define HAL_PWR_MODULE_ENABLED
+#define HAL_RCC_MODULE_ENABLED
+#define HAL_SPI_MODULE_ENABLED
+#define HAL_TIM_MODULE_ENABLED
+#define HAL_USART_MODULE_ENABLED
+#define HAL_CORTEX_MODULE_ENABLED
+// #define HAL_UART_MODULE_ENABLED
+// #define HAL_PCD_MODULE_ENABLED
+
+// #define HAL_CAN_MODULE_ENABLED
+//#define HAL_CEC_MODULE_ENABLED
+//#define HAL_CRYP_MODULE_ENABLED
+//#define HAL_DCMI_MODULE_ENABLED
+//#define HAL_DMA2D_MODULE_ENABLED
+//#define HAL_ETH_MODULE_ENABLED
+//#define HAL_FLASH_MODULE_ENABLED
+//#define HAL_NAND_MODULE_ENABLED
+//#define HAL_NOR_MODULE_ENABLED
+//#define HAL_PCCARD_MODULE_ENABLED
+//#define HAL_SRAM_MODULE_ENABLED
+//#define HAL_SDRAM_MODULE_ENABLED
+//#define HAL_HASH_MODULE_ENABLED
+//#define HAL_SMBUS_MODULE_ENABLED
+//#define HAL_I2S_MODULE_ENABLED
+//#define HAL_IWDG_MODULE_ENABLED
+//#define HAL_LTDC_MODULE_ENABLED
+//#define HAL_DSI_MODULE_ENABLED
+//#define HAL_QSPI_MODULE_ENABLED
+//#define HAL_RNG_MODULE_ENABLED
+//#define HAL_RTC_MODULE_ENABLED
+//#define HAL_SAI_MODULE_ENABLED
+//#define HAL_SD_MODULE_ENABLED
+//#define HAL_IRDA_MODULE_ENABLED
+//#define HAL_SMARTCARD_MODULE_ENABLED
+//#define HAL_WWDG_MODULE_ENABLED
+//#define HAL_HCD_MODULE_ENABLED
+//#define HAL_FMPI2C_MODULE_ENABLED
+//#define HAL_SPDIFRX_MODULE_ENABLED
+//#define HAL_DFSDM_MODULE_ENABLED
+//#define HAL_LPTIM_MODULE_ENABLED
+//#define HAL_MMC_MODULE_ENABLED
+
+/* ########################## HSE/HSI Values adaptation ##################### */
+/**
+ * @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
+ * This value is used by the RCC HAL module to compute the system frequency
+ * (when HSE is used as system clock source, directly or through the PLL).
+ */
+#ifndef HSE_VALUE
+ #define HSE_VALUE 25000000U /*!< Value of the External oscillator in Hz */
+#endif /* HSE_VALUE */
+
+#ifndef HSE_STARTUP_TIMEOUT
+ #define HSE_STARTUP_TIMEOUT 100U /*!< Time out for HSE start up, in ms */
+#endif /* HSE_STARTUP_TIMEOUT */
+
+/**
+ * @brief Internal High Speed oscillator (HSI) value.
+ * This value is used by the RCC HAL module to compute the system frequency
+ * (when HSI is used as system clock source, directly or through the PLL).
+ */
+#ifndef HSI_VALUE
+ #define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz */
+#endif /* HSI_VALUE */
+
+/**
+ * @brief Internal Low Speed oscillator (LSI) value.
+ */
+#ifndef LSI_VALUE
+ #define LSI_VALUE 32000U /*!< LSI Typical Value in Hz */
+#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
+ The real value may vary depending on the variations
+ in voltage and temperature. */
+/**
+ * @brief External Low Speed oscillator (LSE) value.
+ */
+#ifndef LSE_VALUE
+ #define LSE_VALUE 32768U /*!< Value of the External Low Speed oscillator in Hz */
+#endif /* LSE_VALUE */
+
+#ifndef LSE_STARTUP_TIMEOUT
+ #define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */
+#endif /* LSE_STARTUP_TIMEOUT */
+
+/**
+ * @brief External clock source for I2S peripheral
+ * This value is used by the I2S HAL module to compute the I2S clock source
+ * frequency, this source is inserted directly through I2S_CKIN pad.
+ */
+#ifndef EXTERNAL_CLOCK_VALUE
+ #define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External oscillator in Hz*/
+#endif /* EXTERNAL_CLOCK_VALUE */
+
+/* Tip: To avoid modifying this file each time you need to use different HSE,
+ === you can define the HSE value in your toolchain compiler preprocessor. */
+
+/* ########################### System Configuration ######################### */
+/**
+ * @brief This is the HAL system configuration section
+ */
+#define VDD_VALUE 3300U /*!< Value of VDD in mv */
+#define TICK_INT_PRIORITY 0x0FU /*!< tick interrupt priority */
+#define USE_RTOS 0U
+#define PREFETCH_ENABLE 1U
+#define INSTRUCTION_CACHE_ENABLE 1U
+#define DATA_CACHE_ENABLE 1U
+
+#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */
+#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */
+#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */
+#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */
+#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */
+#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */
+#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */
+#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */
+#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */
+#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */
+#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */
+#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */
+#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */
+#define USE_HAL_FMPI2C_REGISTER_CALLBACKS 0U /* FMPI2C register callback disabled */
+#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */
+#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */
+#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */
+#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */
+#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */
+#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */
+#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */
+#define USE_HAL_PCCARD_REGISTER_CALLBACKS 0U /* PCCARD register callback disabled */
+#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */
+#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */
+#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */
+#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */
+#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */
+#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */
+#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */
+#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */
+#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */
+#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */
+#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */
+#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */
+#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */
+#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */
+#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */
+#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */
+
+/* ########################## Assert Selection ############################## */
+/**
+ * @brief Uncomment the line below to expanse the "assert_param" macro in the
+ * HAL drivers code
+ */
+// #define USE_FULL_ASSERT 1U
+
+/* ################## Ethernet peripheral configuration ##################### */
+
+/* Section 1 : Ethernet peripheral configuration */
+
+/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */
+#define MAC_ADDR0 2U
+#define MAC_ADDR1 0U
+#define MAC_ADDR2 0U
+#define MAC_ADDR3 0U
+#define MAC_ADDR4 0U
+#define MAC_ADDR5 0U
+
+/* Definition of the Ethernet driver buffers size and count */
+#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */
+#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */
+#define ETH_RXBUFNB 4U /* 4 Rx buffers of size ETH_RX_BUF_SIZE */
+#define ETH_TXBUFNB 4U /* 4 Tx buffers of size ETH_TX_BUF_SIZE */
+
+/* Section 2: PHY configuration section */
+
+/* DP83848 PHY Address*/
+#define DP83848_PHY_ADDRESS 0x01U
+/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/
+#define PHY_RESET_DELAY 0x000000FFU
+/* PHY Configuration delay */
+#define PHY_CONFIG_DELAY 0x00000FFFU
+
+#define PHY_READ_TO 0x0000FFFFU
+#define PHY_WRITE_TO 0x0000FFFFU
+
+/* Section 3: Common PHY Registers */
+
+#define PHY_BCR ((uint16_t)0x0000) /*!< Transceiver Basic Control Register */
+#define PHY_BSR ((uint16_t)0x0001) /*!< Transceiver Basic Status Register */
+
+#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */
+#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */
+#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */
+#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */
+#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */
+#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */
+#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */
+#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */
+#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */
+#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */
+
+#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */
+#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */
+#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */
+
+/* Section 4: Extended PHY Registers */
+
+#define PHY_SR ((uint16_t)0x0010) /*!< PHY status register Offset */
+#define PHY_MICR ((uint16_t)0x0011) /*!< MII Interrupt Control Register */
+#define PHY_MISR ((uint16_t)0x0012) /*!< MII Interrupt Status and Misc. Control Register */
+
+#define PHY_LINK_STATUS ((uint16_t)0x0001) /*!< PHY Link mask */
+#define PHY_SPEED_STATUS ((uint16_t)0x0002) /*!< PHY Speed mask */
+#define PHY_DUPLEX_STATUS ((uint16_t)0x0004) /*!< PHY Duplex mask */
+
+#define PHY_MICR_INT_EN ((uint16_t)0x0002) /*!< PHY Enable interrupts */
+#define PHY_MICR_INT_OE ((uint16_t)0x0001) /*!< PHY Enable output interrupt events */
+
+#define PHY_MISR_LINK_INT_EN ((uint16_t)0x0020) /*!< Enable Interrupt on change of link status */
+#define PHY_LINK_INTERRUPT ((uint16_t)0x2000) /*!< PHY link status interrupt mask */
+
+/* ################## SPI peripheral configuration ########################## */
+
+/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
+* Activated: CRC code is present inside driver
+* Deactivated: CRC code cleaned from driver
+*/
+
+#define USE_SPI_CRC 0U
+
+/* Includes ------------------------------------------------------------------*/
+/**
+ * @brief Include module's header file
+ */
+
+#ifdef HAL_RCC_MODULE_ENABLED
+ #include "stm32f4xx_hal_rcc.h"
+#endif /* HAL_RCC_MODULE_ENABLED */
+
+#ifdef HAL_GPIO_MODULE_ENABLED
+ #include "stm32f4xx_hal_gpio.h"
+#endif /* HAL_GPIO_MODULE_ENABLED */
+
+#ifdef HAL_EXTI_MODULE_ENABLED
+ #include "stm32f4xx_hal_exti.h"
+#endif /* HAL_EXTI_MODULE_ENABLED */
+
+#ifdef HAL_DMA_MODULE_ENABLED
+ #include "stm32f4xx_hal_dma.h"
+#endif /* HAL_DMA_MODULE_ENABLED */
+
+#ifdef HAL_CORTEX_MODULE_ENABLED
+ #include "stm32f4xx_hal_cortex.h"
+#endif /* HAL_CORTEX_MODULE_ENABLED */
+
+#ifdef HAL_ADC_MODULE_ENABLED
+ #include "stm32f4xx_hal_adc.h"
+#endif /* HAL_ADC_MODULE_ENABLED */
+
+#ifdef HAL_CAN_MODULE_ENABLED
+ #include "stm32f4xx_hal_can.h"
+#endif /* HAL_CAN_MODULE_ENABLED */
+
+#ifdef HAL_CAN_LEGACY_MODULE_ENABLED
+ #include "stm32f4xx_hal_can_legacy.h"
+#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */
+
+#ifdef HAL_CRC_MODULE_ENABLED
+ #include "stm32f4xx_hal_crc.h"
+#endif /* HAL_CRC_MODULE_ENABLED */
+
+#ifdef HAL_CRYP_MODULE_ENABLED
+ #include "stm32f4xx_hal_cryp.h"
+#endif /* HAL_CRYP_MODULE_ENABLED */
+
+#ifdef HAL_DMA2D_MODULE_ENABLED
+ #include "stm32f4xx_hal_dma2d.h"
+#endif /* HAL_DMA2D_MODULE_ENABLED */
+
+#ifdef HAL_DAC_MODULE_ENABLED
+ #include "stm32f4xx_hal_dac.h"
+#endif /* HAL_DAC_MODULE_ENABLED */
+
+#ifdef HAL_DCMI_MODULE_ENABLED
+ #include "stm32f4xx_hal_dcmi.h"
+#endif /* HAL_DCMI_MODULE_ENABLED */
+
+#ifdef HAL_ETH_MODULE_ENABLED
+ #include "stm32f4xx_hal_eth.h"
+#endif /* HAL_ETH_MODULE_ENABLED */
+
+#ifdef HAL_FLASH_MODULE_ENABLED
+ #include "stm32f4xx_hal_flash.h"
+#endif /* HAL_FLASH_MODULE_ENABLED */
+
+#ifdef HAL_SRAM_MODULE_ENABLED
+ #include "stm32f4xx_hal_sram.h"
+#endif /* HAL_SRAM_MODULE_ENABLED */
+
+#ifdef HAL_NOR_MODULE_ENABLED
+ #include "stm32f4xx_hal_nor.h"
+#endif /* HAL_NOR_MODULE_ENABLED */
+
+#ifdef HAL_NAND_MODULE_ENABLED
+ #include "stm32f4xx_hal_nand.h"
+#endif /* HAL_NAND_MODULE_ENABLED */
+
+#ifdef HAL_PCCARD_MODULE_ENABLED
+ #include "stm32f4xx_hal_pccard.h"
+#endif /* HAL_PCCARD_MODULE_ENABLED */
+
+#ifdef HAL_SDRAM_MODULE_ENABLED
+ #include "stm32f4xx_hal_sdram.h"
+#endif /* HAL_SDRAM_MODULE_ENABLED */
+
+#ifdef HAL_HASH_MODULE_ENABLED
+ #include "stm32f4xx_hal_hash.h"
+#endif /* HAL_HASH_MODULE_ENABLED */
+
+#ifdef HAL_I2C_MODULE_ENABLED
+ #include "stm32f4xx_hal_i2c.h"
+#endif /* HAL_I2C_MODULE_ENABLED */
+
+#ifdef HAL_SMBUS_MODULE_ENABLED
+ #include "stm32f4xx_hal_smbus.h"
+#endif /* HAL_SMBUS_MODULE_ENABLED */
+
+#ifdef HAL_I2S_MODULE_ENABLED
+ #include "stm32f4xx_hal_i2s.h"
+#endif /* HAL_I2S_MODULE_ENABLED */
+
+#ifdef HAL_IWDG_MODULE_ENABLED
+ #include "stm32f4xx_hal_iwdg.h"
+#endif /* HAL_IWDG_MODULE_ENABLED */
+
+#ifdef HAL_LTDC_MODULE_ENABLED
+ #include "stm32f4xx_hal_ltdc.h"
+#endif /* HAL_LTDC_MODULE_ENABLED */
+
+#ifdef HAL_PWR_MODULE_ENABLED
+ #include "stm32f4xx_hal_pwr.h"
+#endif /* HAL_PWR_MODULE_ENABLED */
+
+#ifdef HAL_RNG_MODULE_ENABLED
+ #include "stm32f4xx_hal_rng.h"
+#endif /* HAL_RNG_MODULE_ENABLED */
+
+#ifdef HAL_RTC_MODULE_ENABLED
+ #include "stm32f4xx_hal_rtc.h"
+#endif /* HAL_RTC_MODULE_ENABLED */
+
+#ifdef HAL_SAI_MODULE_ENABLED
+ #include "stm32f4xx_hal_sai.h"
+#endif /* HAL_SAI_MODULE_ENABLED */
+
+#ifdef HAL_SD_MODULE_ENABLED
+ #include "stm32f4xx_hal_sd.h"
+#endif /* HAL_SD_MODULE_ENABLED */
+
+#ifdef HAL_SPI_MODULE_ENABLED
+ #include "stm32f4xx_hal_spi.h"
+#endif /* HAL_SPI_MODULE_ENABLED */
+
+#ifdef HAL_TIM_MODULE_ENABLED
+ #include "stm32f4xx_hal_tim.h"
+#endif /* HAL_TIM_MODULE_ENABLED */
+
+#ifdef HAL_UART_MODULE_ENABLED
+ #include "stm32f4xx_hal_uart.h"
+#endif /* HAL_UART_MODULE_ENABLED */
+
+#ifdef HAL_USART_MODULE_ENABLED
+ #include "stm32f4xx_hal_usart.h"
+#endif /* HAL_USART_MODULE_ENABLED */
+
+#ifdef HAL_IRDA_MODULE_ENABLED
+ #include "stm32f4xx_hal_irda.h"
+#endif /* HAL_IRDA_MODULE_ENABLED */
+
+#ifdef HAL_SMARTCARD_MODULE_ENABLED
+ #include "stm32f4xx_hal_smartcard.h"
+#endif /* HAL_SMARTCARD_MODULE_ENABLED */
+
+#ifdef HAL_WWDG_MODULE_ENABLED
+ #include "stm32f4xx_hal_wwdg.h"
+#endif /* HAL_WWDG_MODULE_ENABLED */
+
+#ifdef HAL_PCD_MODULE_ENABLED
+ #include "stm32f4xx_hal_pcd.h"
+#endif /* HAL_PCD_MODULE_ENABLED */
+
+#ifdef HAL_HCD_MODULE_ENABLED
+ #include "stm32f4xx_hal_hcd.h"
+#endif /* HAL_HCD_MODULE_ENABLED */
+
+#ifdef HAL_DSI_MODULE_ENABLED
+ #include "stm32f4xx_hal_dsi.h"
+#endif /* HAL_DSI_MODULE_ENABLED */
+
+#ifdef HAL_QSPI_MODULE_ENABLED
+ #include "stm32f4xx_hal_qspi.h"
+#endif /* HAL_QSPI_MODULE_ENABLED */
+
+#ifdef HAL_CEC_MODULE_ENABLED
+ #include "stm32f4xx_hal_cec.h"
+#endif /* HAL_CEC_MODULE_ENABLED */
+
+#ifdef HAL_FMPI2C_MODULE_ENABLED
+ #include "stm32f4xx_hal_fmpi2c.h"
+#endif /* HAL_FMPI2C_MODULE_ENABLED */
+
+#ifdef HAL_SPDIFRX_MODULE_ENABLED
+ #include "stm32f4xx_hal_spdifrx.h"
+#endif /* HAL_SPDIFRX_MODULE_ENABLED */
+
+#ifdef HAL_DFSDM_MODULE_ENABLED
+ #include "stm32f4xx_hal_dfsdm.h"
+#endif /* HAL_DFSDM_MODULE_ENABLED */
+
+#ifdef HAL_LPTIM_MODULE_ENABLED
+ #include "stm32f4xx_hal_lptim.h"
+#endif /* HAL_LPTIM_MODULE_ENABLED */
+
+#ifdef HAL_MMC_MODULE_ENABLED
+ #include "stm32f4xx_hal_mmc.h"
+#endif /* HAL_MMC_MODULE_ENABLED */
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef USE_FULL_ASSERT
+/**
+ * @brief The assert_param macro is used for function's parameters check.
+ * @param expr If expr is false, it calls assert_failed function
+ * which reports the name of the source file and the source
+ * line number of the call that failed.
+ * If expr is true, it returns no value.
+ * @retval None
+ */
+ #define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(uint8_t *file, uint32_t line);
+#else
+ #define assert_param(expr) ((void)0U)
+#endif /* USE_FULL_ASSERT */
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F4xx_HAL_CONF_H */
+
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_MKS_SKIPR_V1/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_MKS_SKIPR_V1/ldscript.ld
new file mode 100644
index 00000000..df1ed158
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_MKS_SKIPR_V1/ldscript.ld
@@ -0,0 +1,203 @@
+/*
+******************************************************************************
+**
+** File : LinkerScript.ld
+**
+** Abstract : Linker script for STM32F4x7Vx Device with
+** 512/1024KByte FLASH, 192KByte RAM
+**
+** Set heap size, stack size and stack location according
+** to application requirements.
+**
+** Set memory bank area and size if external memory is used.
+**
+** Target : STMicroelectronics STM32
+**
+** Distribution: The file is distributed “as is,” without any warranty
+** of any kind.
+**
+*****************************************************************************
+** @attention
+**
+** Copyright (c) 2019 STMicroelectronics
+**
+** Redistribution and use in source and binary forms, with or without modification,
+** are permitted provided that the following conditions are met:
+** 1. Redistributions of source code must retain the above copyright notice,
+** this list of conditions and the following disclaimer.
+** 2. Redistributions in binary form must reproduce the above copyright notice,
+** this list of conditions and the following disclaimer in the documentation
+** and/or other materials provided with the distribution.
+** 3. Neither the name of STMicroelectronics nor the names of its contributors
+** may be used to endorse or promote products derived from this software
+** without specific prior written permission.
+**
+** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+**
+*****************************************************************************
+*/
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = 0x20000000 + LD_MAX_DATA_SIZE; /* end of RAM */
+/* Generate a link error if heap and stack don't fit into RAM */
+_Min_Heap_Size = 0x200; /* required amount of heap */
+_Min_Stack_Size = 0x400; /* required amount of stack */
+
+/* Specify the memory areas */
+MEMORY
+{
+RAM (xrw) : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE
+CCMRAM (rw) : ORIGIN = 0x10000000, LENGTH = 64K
+FLASH (rx) : ORIGIN = 0x08000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET
+}
+
+/* Define output sections */
+SECTIONS
+{
+ /* The startup code goes first into FLASH */
+ .isr_vector :
+ {
+ . = ALIGN(4);
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(4);
+ } >FLASH
+
+ /* The program code and other data goes into FLASH */
+ .text :
+ {
+ . = ALIGN(4);
+ *(.text) /* .text sections (code) */
+ *(.text*) /* .text* sections (code) */
+ *(.glue_7) /* glue arm to thumb code */
+ *(.glue_7t) /* glue thumb to arm code */
+ *(.eh_frame)
+
+ KEEP (*(.init))
+ KEEP (*(.fini))
+
+ . = ALIGN(4);
+ _etext = .; /* define a global symbols at end of code */
+ } >FLASH
+
+ /* Constant data goes into FLASH */
+ .rodata :
+ {
+ . = ALIGN(4);
+ *(.rodata) /* .rodata sections (constants, strings, etc.) */
+ *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
+ . = ALIGN(4);
+ } >FLASH
+
+ .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
+ .ARM : {
+ __exidx_start = .;
+ *(.ARM.exidx*)
+ __exidx_end = .;
+ } >FLASH
+
+ .preinit_array :
+ {
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array*))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ } >FLASH
+ .init_array :
+ {
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array*))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ } >FLASH
+ .fini_array :
+ {
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT(.fini_array.*)))
+ KEEP (*(.fini_array*))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ } >FLASH
+
+ /* used by the startup to initialize data */
+ _sidata = LOADADDR(.data);
+
+ /* Initialized data sections goes into RAM, load LMA copy after code */
+ .data :
+ {
+ . = ALIGN(4);
+ _sdata = .; /* create a global symbol at data start */
+ *(.data) /* .data sections */
+ *(.data*) /* .data* sections */
+
+ . = ALIGN(4);
+ _edata = .; /* define a global symbol at data end */
+ } >RAM AT> FLASH
+
+ _siccmram = LOADADDR(.ccmram);
+
+ /* CCM-RAM section
+ *
+ * IMPORTANT NOTE!
+ * If initialized variables will be placed in this section,
+ * the startup code needs to be modified to copy the init-values.
+ */
+ .ccmram :
+ {
+ . = ALIGN(4);
+ _sccmram = .; /* create a global symbol at ccmram start */
+ *(.ccmram)
+ *(.ccmram*)
+
+ . = ALIGN(4);
+ _eccmram = .; /* create a global symbol at ccmram end */
+ } >CCMRAM AT> FLASH
+
+
+ /* Uninitialized data section */
+ . = ALIGN(4);
+ .bss :
+ {
+ /* This is used by the startup in order to initialize the .bss section */
+ _sbss = .; /* define a global symbol at bss start */
+ __bss_start__ = _sbss;
+ *(.bss)
+ *(.bss*)
+ *(COMMON)
+
+ . = ALIGN(4);
+ _ebss = .; /* define a global symbol at bss end */
+ __bss_end__ = _ebss;
+ } >RAM
+
+ /* User_heap_stack section, used to check that there is enough RAM left */
+ ._user_heap_stack :
+ {
+ . = ALIGN(8);
+ PROVIDE ( end = . );
+ PROVIDE ( _end = . );
+ . = . + _Min_Heap_Size;
+ . = . + _Min_Stack_Size;
+ . = ALIGN(8);
+ } >RAM
+
+
+ /* Remove information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+}
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_MKS_SKIPR_V1/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_MKS_SKIPR_V1/variant.cpp
new file mode 100644
index 00000000..00c7a90d
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_MKS_SKIPR_V1/variant.cpp
@@ -0,0 +1,288 @@
+/*
+ *******************************************************************************
+ * Copyright (c) 2017, STMicroelectronics
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *******************************************************************************
+ */
+
+#include "pins_arduino.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+// Digital PinName array
+const PinName digitalPin[] = {
+ PA_0, // Digital pin 0
+ PA_1, // Digital pin 1
+ PA_2, // Digital pin 2
+ PA_3, // Digital pin 3
+ PA_4, // Digital pin 4
+ PA_5, // Digital pin 5
+ PA_6, // Digital pin 6
+ PA_7, // Digital pin 7
+ PA_8, // Digital pin 8
+ PA_9, // Digital pin 9
+ PA_10, // Digital pin 10
+ PA_11, // Digital pin 11
+ PA_12, // Digital pin 12
+ PA_13, // Digital pin 13
+ PA_14, // Digital pin 14
+ PA_15, // Digital pin 15
+
+ PB_0, // Digital pin 16
+ PB_1, // Digital pin 17
+ PB_2, // Digital pin 18
+ PB_3, // Digital pin 19
+ PB_4, // Digital pin 20
+ PB_5, // Digital pin 21
+ PB_6, // Digital pin 22
+ PB_7, // Digital pin 23
+ PB_8, // Digital pin 24
+ PB_9, // Digital pin 25
+ PB_10, // Digital pin 26
+ PB_11, // Digital pin 27
+ PB_12, // Digital pin 28
+ PB_13, // Digital pin 29
+ PB_14, // Digital pin 30
+ PB_15, // Digital pin 31
+
+ PC_0, // Digital pin 32
+ PC_1, // Digital pin 33
+ PC_2, // Digital pin 34
+ PC_3, // Digital pin 35
+ PC_4, // Digital pin 36
+ PC_5, // Digital pin 37
+ PC_6, // Digital pin 38
+ PC_7, // Digital pin 39
+ PC_8, // Digital pin 40
+ PC_9, // Digital pin 41
+ PC_10, // Digital pin 42
+ PC_11, // Digital pin 43
+ PC_12, // Digital pin 44
+ PC_13, // Digital pin 45
+ PC_14, // Digital pin 46
+ PC_15, // Digital pin 47
+
+ PD_0, // Digital pin 48
+ PD_1, // Digital pin 49
+ PD_2, // Digital pin 50
+ PD_3, // Digital pin 51
+ PD_4, // Digital pin 52
+ PD_5, // Digital pin 53
+ PD_6, // Digital pin 54
+ PD_7, // Digital pin 55
+ PD_8, // Digital pin 56
+ PD_9, // Digital pin 57
+ PD_10, // Digital pin 58
+ PD_11, // Digital pin 59
+ PD_12, // Digital pin 60
+ PD_13, // Digital pin 61
+ PD_14, // Digital pin 62
+ PD_15, // Digital pin 63
+
+ PE_0, // Digital pin 64
+ PE_1, // Digital pin 65
+ PE_2, // Digital pin 66
+ PE_3, // Digital pin 67
+ PE_4, // Digital pin 68
+ PE_5, // Digital pin 69
+ PE_6, // Digital pin 70
+ PE_7, // Digital pin 71
+ PE_8, // Digital pin 72
+ PE_9, // Digital pin 73
+ PE_10, // Digital pin 74
+ PE_11, // Digital pin 75
+ PE_12, // Digital pin 76
+ PE_13, // Digital pin 77
+ PE_14, // Digital pin 78
+ PE_15, // Digital pin 79
+
+ PH_0, // Digital pin 80, used by the external oscillator
+ PH_1 // Digital pin 81, used by the external oscillator
+};
+
+// Analog (Ax) pin number array
+const uint32_t analogInputPin[] = {
+ 0, // A0, PA0
+ 1, // A1, PA1
+ 2, // A2, PA2
+ 3, // A3, PA3
+ 4, // A4, PA4
+ 5, // A5, PA5
+ 6, // A6, PA6
+ 7, // A7, PA7
+ 16, // A8, PB0
+ 17, // A9, PB1
+ 32, // A10, PC0
+ 33, // A11, PC1
+ 34, // A12, PC2
+ 35, // A13, PC3
+ 36, // A14, PC4
+ 37 // A15, PC5
+};
+
+#ifdef __cplusplus
+}
+#endif
+
+// ----------------------------------------------------------------------------
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/*
+ * @brief Configures the System clock source, PLL Multiplier and Divider factors,
+ * AHB/APBx prescalers and Flash settings
+ * @note This function should be called only once the RCC clock configuration
+ * is reset to the default reset state (done in SystemInit() function).
+ * @param None
+ * @retval None
+ */
+
+/******************************************************************************/
+/* PLL (clocked by HSE) used as System clock source */
+/******************************************************************************/
+static uint8_t SetSysClock_PLL_HSE(uint8_t bypass)
+{
+ RCC_OscInitTypeDef RCC_OscInitStruct;
+ RCC_ClkInitTypeDef RCC_ClkInitStruct;
+
+ /* The voltage scaling allows optimizing the power consumption when the device is
+ clocked below the maximum system frequency, to update the voltage scaling value
+ regarding system frequency refer to product datasheet. */
+ __HAL_RCC_PWR_CLK_ENABLE();
+ __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
+
+ // Enable HSE oscillator and activate PLL with HSE as source
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
+ if (bypass == 0) {
+ RCC_OscInitStruct.HSEState = RCC_HSE_ON; // External 8 MHz xtal on OSC_IN/OSC_OUT
+ } else {
+ RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS; // External 8 MHz clock on OSC_IN
+ }
+
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
+ RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
+ RCC_OscInitStruct.PLL.PLLM = HSE_VALUE / 1000000L; // Expects an 8 MHz external clock by default. Redefine HSE_VALUE if not
+ RCC_OscInitStruct.PLL.PLLN = 336; // VCO output clock = 336 MHz (1 MHz * 336)
+ RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; // PLLCLK = 168 MHz (336 MHz / 2)
+ RCC_OscInitStruct.PLL.PLLQ = 7;
+ if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
+ return 0; // FAIL
+ }
+
+ // Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers
+ RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
+ RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
+ RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; // 168 MHz
+ RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; // 42 MHz
+ RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; // 84 MHz
+ if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK) {
+ return 0; // FAIL
+ }
+
+ /* Output clock on MCO1 pin(PA8) for debugging purpose */
+ /*
+ if (bypass == 0)
+ HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSE, RCC_MCODIV_2); // 4 MHz
+ else
+ HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSE, RCC_MCODIV_1); // 8 MHz
+ */
+
+ return 1; // OK
+}
+
+/******************************************************************************/
+/* PLL (clocked by HSI) used as System clock source */
+/******************************************************************************/
+uint8_t SetSysClock_PLL_HSI(void)
+{
+ RCC_OscInitTypeDef RCC_OscInitStruct;
+ RCC_ClkInitTypeDef RCC_ClkInitStruct;
+
+ /* The voltage scaling allows optimizing the power consumption when the device is
+ clocked below the maximum system frequency, to update the voltage scaling value
+ regarding system frequency refer to product datasheet. */
+ __HAL_RCC_PWR_CLK_ENABLE();
+ __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
+
+ // Enable HSI oscillator and activate PLL with HSI as source
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_HSE;
+ RCC_OscInitStruct.HSIState = RCC_HSI_ON;
+ RCC_OscInitStruct.HSEState = RCC_HSE_OFF;
+ RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
+ RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
+ RCC_OscInitStruct.PLL.PLLM = 16; // VCO input clock = 1 MHz (16 MHz / 16)
+ RCC_OscInitStruct.PLL.PLLN = 336; // VCO output clock = 336 MHz (1 MHz * 336)
+ RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; // PLLCLK = 168 MHz (336 MHz / 2)
+ RCC_OscInitStruct.PLL.PLLQ = 7;
+ if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
+ return 0; // FAIL
+ }
+
+ /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */
+ RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2);
+ RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
+ RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; // 168 MHz
+ RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; // 42 MHz
+ RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; // 84 MHz
+ if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK) {
+ return 0; // FAIL
+ }
+
+ /* Output clock on MCO1 pin(PA8) for debugging purpose */
+ //HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSI, RCC_MCODIV_1); // 16 MHz
+
+ return 1; // OK
+}
+
+WEAK void SystemClock_Config(void)
+{
+ /* 1- If fail try to start with HSE and external xtal */
+ if (SetSysClock_PLL_HSE(0) == 0) {
+ /* 2- Try to start with HSE and external clock */
+ if (SetSysClock_PLL_HSE(1) == 0) {
+ /* 3- If fail start with HSI clock */
+ if (SetSysClock_PLL_HSI() == 0) {
+ Error_Handler();
+ }
+ }
+ }
+
+ /* Ensure CCM RAM clock is enabled */
+ __HAL_RCC_CCMDATARAMEN_CLK_ENABLE();
+
+ /* Output clock on MCO2 pin(PC9) for debugging purpose */
+ //HAL_RCC_MCOConfig(RCC_MCO2, RCC_MCO2SOURCE_SYSCLK, RCC_MCODIV_4);
+}
+
+#ifdef __cplusplus
+}
+#endif
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_MKS_SKIPR_V1/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_MKS_SKIPR_V1/variant.h
new file mode 100644
index 00000000..51a9e922
--- /dev/null
+++ b/buildroot/share/PlatformIO/variants/MARLIN_MKS_SKIPR_V1/variant.h
@@ -0,0 +1,196 @@
+/*
+ *******************************************************************************
+ * Copyright (c) 2017, STMicroelectronics
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *******************************************************************************
+ */
+#pragma once
+
+#ifdef __cplusplus
+extern "C" {
+#endif // __cplusplus
+//
+/*----------------------------------------------------------------------------
+ * Pins
+ *----------------------------------------------------------------------------*/
+ // | DIGITAL | ANALOG IN | ANALOG OUT | UART/USART | TWI | SPI | SPECIAL |
+ // |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------|
+#define PA0 PIN_A0 // | 0 | A0 (ADC1) | | UART4_TX | | | |
+#define PA1 PIN_A1 // | 1 | A1 (ADC1) | | UART4_RX | | | |
+#define PA2 PIN_A2 // | 2 | A2 (ADC1) | | USART2_TX | | | |
+#define PA3 PIN_A3 // | 3 | A3 (ADC1) | | USART2_RX | | | |
+#define PA4 PIN_A4 // | 4 | A4 (ADC1) | DAC_OUT1 | | | SPI1_SS, (SPI3_SS) | |
+#define PA5 PIN_A5 // | 5 | A5 (ADC1) | DAC_OUT2 | | | SPI1_SCK | |
+#define PA6 PIN_A6 // | 6 | A6 (ADC1) | | | | SPI1_MISO | |
+#define PA7 PIN_A7 // | 7 | A7 (ADC1) | | | | SPI1_MOSI | |
+#define PA8 8 // | 8 | | | | TWI3_SCL | | |
+#define PA9 9 // | 9 | | | USART1_TX | | | |
+#define PA10 10 // | 10 | | | USART1_RX | | | |
+#define PA11 11 // | 11 | | | | | | |
+#define PA12 12 // | 12 | | | | | | |
+#define PA13 13 // | 13 | | | | | | SWD_SWDIO |
+#define PA14 14 // | 14 | | | | | | SWD_SWCLK |
+#define PA15 15 // | 15 | | | | | SPI3_SS, (SPI1_SS) | |
+ // |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------|
+#define PB0 PIN_A8 // | 16 | A8 (ADC1) | | | | | |
+#define PB1 PIN_A9 // | 17 | A9 (ADC1) | | | | | |
+#define PB2 18 // | 18 | | | | | | BOOT1 |
+#define PB3 19 // | 19 | | | | | SPI3_SCK, (SPI1_SCK) | |
+#define PB4 20 // | 20 | | | | | SPI3_MISO, (SPI1_MISO) | |
+#define PB5 21 // | 21 | | | | | SPI3_MOSI, (SPI1_MOSI) | |
+#define PB6 22 // | 22 | | | USART1_TX | TWI1_SCL | | |
+#define PB7 23 // | 23 | | | USART1_RX | TWI1_SDA | | |
+#define PB8 24 // | 24 | | | | TWI1_SCL | | |
+#define PB9 25 // | 25 | | | | TWI1_SDA | SPI2_SS | |
+#define PB10 26 // | 26 | | | USART3_TX, (UART4_TX) | TWI2_SCL | SPI2_SCK | |
+#define PB11 27 // | 27 | | | USART3_RX | TWI2_SDA | | |
+#define PB12 28 // | 28 | | | | | SPI2_SS | |
+#define PB13 29 // | 29 | | | | | SPI2_SCK | |
+#define PB14 30 // | 30 | | | | | SPI2_MISO | |
+#define PB15 31 // | 31 | | | | | SPI2_MOSI | |
+ // |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------|
+#define PC0 PIN_A10 // | 32 | A10 (ADC1) | | | | | |
+#define PC1 PIN_A11 // | 33 | A11 (ADC1) | | | | | |
+#define PC2 PIN_A12 // | 34 | A12 (ADC1) | | | | SPI2_MISO | |
+#define PC3 PIN_A13 // | 35 | A13 (ADC1) | | | | SPI2_MOSI | |
+#define PC4 PIN_A14 // | 36 | A14 (ADC1) | | | | | |
+#define PC5 PIN_A15 // | 37 | A15 (ADC1) | | USART3_RX | | | |
+#define PC6 38 // | 38 | | | USART6_TX | | | |
+#define PC7 39 // | 39 | | | USART6_RX | | | |
+#define PC8 40 // | 40 | | | | | | |
+#define PC9 41 // | 41 | | | USART3_TX | TWI3_SDA | | |
+#define PC10 42 // | 42 | | | | | SPI3_SCK | |
+#define PC11 43 // | 43 | | | USART3_RX, (UART4_RX) | | SPI3_MISO | |
+#define PC12 44 // | 44 | | | UART5_TX | | SPI3_MOSI | |
+#define PC13 45 // | 45 | | | | | | |
+#define PC14 46 // | 46 | | | | | | OSC32_IN |
+#define PC15 47 // | 47 | | | | | | OSC32_OUT |
+ // |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------|
+#define PD0 48 // | 48 | | | | | | |
+#define PD1 49 // | 49 | | | | | | |
+#define PD2 50 // | 50 | | | UART5_RX | | | |
+#define PD3 51 // | 51 | | | | | | |
+#define PD4 52 // | 52 | | | | | | |
+#define PD5 53 // | 53 | | | USART2_TX | | | |
+#define PD6 54 // | 54 | | | USART2_RX | | | |
+#define PD7 55 // | 55 | | | | | | |
+#define PD8 56 // | 56 | | | USART3_TX | | | |
+#define PD9 57 // | 57 | | | USART3_RX | | | |
+#define PD10 58 // | 58 | | | | | | |
+#define PD11 59 // | 59 | | | | | | |
+#define PD12 60 // | 60 | | | | | | |
+#define PD13 61 // | 61 | | | | | | |
+#define PD14 62 // | 62 | | | | | | |
+#define PD15 63 // | 63 | | | | | | |
+ // |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------|
+#define PE0 64 // | 64 | | | | | | |
+#define PE1 65 // | 65 | | | | | | |
+#define PE2 66 // | 66 | | | | | | |
+#define PE3 67 // | 67 | | | | | | |
+#define PE4 68 // | 68 | | | | | | |
+#define PE5 69 // | 69 | | | | | | |
+#define PE6 70 // | 70 | | | | | | |
+#define PE7 71 // | 71 | | | | | | |
+#define PE8 72 // | 72 | | | | | | |
+#define PE9 73 // | 73 | | | | | | |
+#define PE10 74 // | 74 | | | | | | |
+#define PE11 75 // | 75 | | | | | | |
+#define PE12 76 // | 76 | | | | | | |
+#define PE13 77 // | 77 | | | | | | |
+#define PE14 78 // | 78 | | | | | | |
+#define PE15 79 // | 79 | | | | | | |
+ // |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------|
+#define PH0 80 // | 80 | | | | | | OSC_IN |
+#define PH1 81 // | 81 | | | | | | OSC_OUT |
+ // |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------|
+
+// This must be a literal
+#define NUM_DIGITAL_PINS 82
+#define NUM_ANALOG_INPUTS 16
+
+// Below SPI and I2C definitions already done in the core
+// Could be redefined here if differs from the default one
+// SPI Definitions
+#define PIN_SPI_SS PC9
+#define PIN_SPI_SCK PC10
+#define PIN_SPI_MISO PC11
+#define PIN_SPI_MOSI PC12
+
+// I2C Definitions
+#define PIN_WIRE_SCL PB8
+#define PIN_WIRE_SDA PB9
+
+// Timer Definitions
+// Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c
+// TIM1 = HEATER0, HEATER1, [SERVO]
+// TIM2 = FAN1, FAN2, [BEEPER]
+// TIM4 = HEATER_BED
+// TIM5 = HEATER2, FAN0
+// Uses default for STM32F4xx STEP_TIMER 6 and TEMP_TIMER 14
+#define TIMER_SERVO TIM1 // TIMER_SERVO must be defined in this file
+#define TIMER_TONE TIM2 // TIMER_TONE must be defined in this file
+#define TIMER_SERIAL TIM3 // TIMER_SERIAL must be defined in this file
+
+// USART1 (direct to RK3328 SoC)
+#define ENABLE_HWSERIAL1
+#define PIN_SERIAL1_TX PA9
+#define PIN_SERIAL1_RX PA10
+
+// USART3 connector
+#define ENABLE_HWSERIAL3
+#define PIN_SERIAL3_TX PB10
+#define PIN_SERIAL3_RX PB11
+
+#ifdef __cplusplus
+} // extern "C"
+#endif
+/*----------------------------------------------------------------------------
+ * Arduino objects - C++ only
+ *----------------------------------------------------------------------------*/
+
+#ifdef __cplusplus
+// These serial port names are intended to allow libraries and architecture-neutral
+// sketches to automatically default to the correct port name for a particular type
+// of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN,
+// the first hardware serial port whose RX/TX pins are not dedicated to another use.
+//
+// SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor
+//
+// SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial
+//
+// SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library
+//
+// SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins.
+//
+// SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX
+// pins are NOT connected to anything by default.
+#define SERIAL_PORT_MONITOR Serial1
+#define SERIAL_PORT_USBVIRTUAL SerialUSB
+#define SERIAL_PORT_HARDWARE Serial1
+#define SERIAL_PORT_HARDWARE1 Serial3
+#define SERIAL_PORT_HARDWARE_OPEN Serial1
+#define SERIAL_PORT_HARDWARE_OPEN1 Serial3
+#endif
diff --git a/buildroot/tests/SAMD21_minitronics20 b/buildroot/tests/SAMD21_minitronics20
new file mode 100755
index 00000000..018d6a70
--- /dev/null
+++ b/buildroot/tests/SAMD21_minitronics20
@@ -0,0 +1,33 @@
+#!/usr/bin/env bash
+#
+# Build tests for SAMD21 (Minitronics 2.0)
+#
+
+# exit on first failure
+set -e
+
+#
+# Build with the default configurations
+#
+restore_configs
+opt_set MOTHERBOARD BOARD_MINITRONICS20 SERIAL_PORT -1 \
+ TEMP_SENSOR_0 11 TEMP_SENSOR_BED 11 \
+ X_DRIVER_TYPE DRV8825 Y_DRIVER_TYPE DRV8825 Z_DRIVER_TYPE DRV8825 E0_DRIVER_TYPE DRV8825 \
+ RESTORE_LEVELING_AFTER_G28 false \
+ LCD_LANGUAGE it \
+ SDCARD_CONNECTION LCD \
+ HOMING_BUMP_MM '{ 0, 0, 0 }'
+opt_enable ENDSTOP_INTERRUPTS_FEATURE BLTOUCH Z_MIN_PROBE_REPEATABILITY_TEST \
+ FILAMENT_RUNOUT_SENSOR G26_MESH_VALIDATION MESH_EDIT_GFX_OVERLAY Z_SAFE_HOMING \
+ EEPROM_SETTINGS NOZZLE_PARK_FEATURE SDSUPPORT SD_CHECK_AND_RETRY \
+ REPRAPWORLD_GRAPHICAL_LCD ADAPTIVE_STEP_SMOOTHING \
+ STATUS_MESSAGE_SCROLLING SET_PROGRESS_MANUALLY SHOW_REMAINING_TIME SET_REMAINING_TIME \
+ LONG_FILENAME_HOST_SUPPORT CUSTOM_FIRMWARE_UPLOAD M20_TIMESTAMP_SUPPORT \
+ SCROLL_LONG_FILENAMES BABYSTEPPING DOUBLECLICK_FOR_Z_BABYSTEPPING \
+ MOVE_Z_WHEN_IDLE BABYSTEP_ZPROBE_OFFSET BABYSTEP_ZPROBE_GFX_OVERLAY \
+ LIN_ADVANCE ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE MONITOR_DRIVER_STATUS SENSORLESS_HOMING \
+ SQUARE_WAVE_STEPPING EXPERIMENTAL_SCURVE
+exec_test $1 $2 "Minitronics 2.0 with assorted features" "$3"
+
+# clean up
+restore_configs
diff --git a/buildroot/tests/mks_robin_nano_v1_3_f4_usbmod b/buildroot/tests/mks_robin_nano_v1_3_f4_usbmod
new file mode 100755
index 00000000..01a47525
--- /dev/null
+++ b/buildroot/tests/mks_robin_nano_v1_3_f4_usbmod
@@ -0,0 +1,19 @@
+#!/usr/bin/env bash
+#
+# Build tests for MKS Robin nano v1.3 with native USB modification
+# (STM32F4 genericSTM32F407VE)
+#
+
+# exit on first failure
+set -e
+
+#
+# MKS/ZNP Robin nano v1.3 with Emulated DOGM FSMC and native USB mod
+#
+use_example_configs Mks/Robin
+opt_add USB_MOD
+opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V1_3_F4 SERIAL_PORT -1
+exec_test $1 $2 "MKS/ZNP Robin nano v1.3 with Emulated DOGM FSMC (native USB mod)" "$3"
+
+# cleanup
+restore_configs
diff --git a/buildroot/tests/mks_robin_nano_v1v2 b/buildroot/tests/mks_robin_nano_v1v2
new file mode 100755
index 00000000..f892d42d
--- /dev/null
+++ b/buildroot/tests/mks_robin_nano_v1v2
@@ -0,0 +1,68 @@
+#!/usr/bin/env bash
+#
+# Build tests for MKS Robin nano
+# (STM32F1 genericSTM32F103VE)
+#
+
+# exit on first failure
+set -e
+
+#
+# MKS Robin nano v1.2 Emulated DOGM FSMC
+#
+use_example_configs Mks/Robin
+opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO
+exec_test $1 $2 "MKS Robin nano v1.2 Emulated DOGM FSMC" "$3"
+
+#
+# MKS Robin nano v2 Emulated DOGM SPI
+# (Robin nano v2 has no FSMC interface)
+#
+use_example_configs Mks/Robin
+opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2
+opt_disable TFT_INTERFACE_FSMC
+opt_enable TFT_INTERFACE_SPI MKS_WIFI_MODULE
+opt_add MKS_TEST
+exec_test $1 $2 "MKS Robin nano v2 Emulated DOGM SPI, MKS_WIFI_MODULE" "$3"
+
+#
+# MKS Robin nano v1.2 LVGL FSMC
+#
+# use_example_configs Mks/Robin
+# opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO
+# opt_disable TFT_CLASSIC_UI TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240
+# opt_enable TFT_LVGL_UI TFT_RES_480x320
+# exec_test $1 $2 "MKS Robin nano v1.2 LVGL FSMC" "$3"
+
+#
+# MKS Robin nano v2 LVGL SPI
+# (Robin nano v2 has no FSMC interface)
+#
+# use_example_configs Mks/Robin
+# opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2
+# opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240
+# opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320
+# exec_test $1 $2 "MKS Robin nano v2 LVGL SPI" "$3"
+
+#
+# MKS Robin nano v2 New Color UI 480x320 SPI
+# (Robin nano v2 has no FSMC interface)
+#
+use_example_configs Mks/Robin
+opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2
+opt_disable TFT_INTERFACE_FSMC TFT_RES_320x240
+opt_enable TFT_INTERFACE_SPI TFT_RES_480x320
+exec_test $1 $2 "MKS Robin nano v2 with New Color UI 480x320 SPI" "$3"
+
+#
+# MKS Robin nano v2 LVGL SPI + TMC
+# (Robin nano v2 has no FSMC interface)
+#
+use_example_configs Mks/Robin
+opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2209
+opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240
+opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320
+exec_test $1 $2 "MKS Robin nano v2 LVGL SPI + TMC" "$3"
+
+# cleanup
+restore_configs
diff --git a/buildroot/tests/mks_robin_nano_v1v2_maple b/buildroot/tests/mks_robin_nano_v1v2_maple
new file mode 100755
index 00000000..ebd5466c
--- /dev/null
+++ b/buildroot/tests/mks_robin_nano_v1v2_maple
@@ -0,0 +1,69 @@
+#!/usr/bin/env bash
+#
+# Build tests for MKS Robin nano with LibMaple STM32F1 HAL
+# (STM32F1 genericSTM32F103VE)
+#
+
+# exit on first failure
+set -e
+
+#
+# MKS Robin nano v1.2 Emulated DOGM FSMC
+#
+use_example_configs Mks/Robin
+opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO
+exec_test $1 $2 "MKS Robin nano v1.2 Emulated DOGM FSMC" "$3"
+
+#
+# MKS Robin v2 nano Emulated DOGM SPI
+# (Robin v2 nano has no FSMC interface)
+#
+use_example_configs Mks/Robin
+opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2
+opt_disable TFT_INTERFACE_FSMC
+opt_enable TFT_INTERFACE_SPI
+exec_test $1 $2 "MKS Robin v2 nano Emulated DOGM SPI" "$3"
+
+#
+# MKS Robin v2 nano LVGL SPI
+# (Robin v2 nano has no FSMC interface)
+#
+use_example_configs Mks/Robin
+opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2
+opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 SERIAL_PORT_2
+opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 MKS_WIFI_MODULE
+opt_add MKS_TEST
+exec_test $1 $2 "MKS Robin v2 nano LVGL SPI w/ WiFi" "$3"
+
+#
+# MKS Robin v2 nano New Color UI 480x320 SPI
+# (Robin v2 nano has no FSMC interface)
+#
+use_example_configs Mks/Robin
+opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2
+opt_disable TFT_INTERFACE_FSMC TFT_RES_320x240
+opt_enable TFT_INTERFACE_SPI TFT_RES_480x320
+opt_enable BINARY_FILE_TRANSFER
+exec_test $1 $2 "MKS Robin v2 nano New Color UI 480x320 SPI + BINARY_FILE_TRANSFER" "$3"
+
+#
+# MKS Robin v2 nano LVGL SPI + TMC
+# (Robin v2 nano has no FSMC interface)
+#
+use_example_configs Mks/Robin
+opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2209
+opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240
+opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320
+exec_test $1 $2 "MKS Robin v2 nano LVGL SPI + TMC" "$3"
+
+#
+# MKS Robin v2 nano New Color UI 480x320 SPI Without Touch Screen
+#
+use_example_configs Mks/Robin
+opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2
+opt_disable TFT_INTERFACE_FSMC TFT_RES_320x240 TOUCH_SCREEN
+opt_enable TFT_INTERFACE_SPI TFT_RES_480x320 TFT_COLOR_UI
+exec_test $1 $2 "MKS Robin v2 nano New Color UI 480x320 SPI without TOUCH_SCREEN" "$3"
+
+# cleanup
+restore_configs
diff --git a/buildroot/tests/mks_robin_nano_v1v2_usbmod b/buildroot/tests/mks_robin_nano_v1v2_usbmod
new file mode 100755
index 00000000..31f04c9a
--- /dev/null
+++ b/buildroot/tests/mks_robin_nano_v1v2_usbmod
@@ -0,0 +1,19 @@
+#!/usr/bin/env bash
+#
+# Build tests for MKS Robin nano V1.2 and V2 with native USB modification
+# (STM32F1 genericSTM32F103VE)
+#
+
+# exit on first failure
+set -e
+
+#
+# MKS/ZNP Robin nano v1.2 with Emulated DOGM FSMC
+#
+use_example_configs Mks/Robin
+opt_add USB_MOD
+opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO SERIAL_PORT -1
+exec_test $1 $2 "MKS/ZNP Robin nano v1.2 with Emulated DOGM FSMC (native USB mod)" "$3"
+
+# cleanup
+restore_configs
diff --git a/ini/samd21.ini b/ini/samd21.ini
new file mode 100644
index 00000000..969ce3b9
--- /dev/null
+++ b/ini/samd21.ini
@@ -0,0 +1,26 @@
+#
+# Marlin Firmware
+# PlatformIO Configuration File
+#
+
+#################################
+# #
+# SAMD21 Architecture #
+# #
+#################################
+
+#
+# Adafruit Grand Central M4 (Atmel SAMD51P20A ARM Cortex-M4)
+#
+[env:SAMD21_minitronics20]
+platform = atmelsam
+board = minitronics20
+build_flags = ${common.build_flags} -std=gnu++17
+ -DUSBCON -DUSBD_USE_CDC -D__SAMD21__ -DARDUINO_SAMD_MINITRONICS20 -Wno-deprecated-declarations -DU8G_HAL_LINKS -DDEBUG
+ -IMarlin/src/HAL/SAMD21/u8g
+build_unflags = -std=gnu++11
+build_src_filter = ${common.default_src_filter} +
+lib_deps = ${common.lib_deps}
+extra_scripts = ${common.extra_scripts}
+ pre:buildroot/share/PlatformIO/scripts/SAMD21_minitronics20.py
+debug_tool = atmel-ice