diff --git a/.aiderignore b/.aiderignore
new file mode 100644
index 000000000000..b80c45944684
--- /dev/null
+++ b/.aiderignore
@@ -0,0 +1,21 @@
+# Build artifacts
+buildroot/
+*.o
+*.a
+*.so
+*.dylib
+*.dll
+*.exe
+
+# Web assets
+*.min.js
+*.min.css
+
+# Generated files
+__pycache__/
+*.pyc
+.DS_Store
+
+# IDE files
+.vscode/
+.idea/
diff --git a/.github/workflows/ci-build-tests.yml b/.github/workflows/ci-build-tests.yml
index cca9a5574ea4..afe9292c19ee 100644
--- a/.github/workflows/ci-build-tests.yml
+++ b/.github/workflows/ci-build-tests.yml
@@ -41,6 +41,9 @@ jobs:
matrix:
test-platform:
+ # RP2040
+ - SKR_Pico
+
# Native
- linux_native
- simulator_linux_release
diff --git a/.gitignore b/.gitignore
index 50a34f97ff81..daa5c5c28898 100755
--- a/.gitignore
+++ b/.gitignore
@@ -169,3 +169,6 @@ __pycache__
tags
*.logs
*.bak
+.aider*
+!.aiderignore
+.env
diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h
index 712597af97e3..c45c75a39d96 100644
--- a/Marlin/Configuration.h
+++ b/Marlin/Configuration.h
@@ -71,6 +71,8 @@
#define MOTHERBOARD BOARD_RAMPS_14_EFB
#endif
+// @section serial
+
/**
* Select the serial port on the board to use for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
@@ -941,7 +943,7 @@
//============================= Mechanical Settings =========================
//===========================================================================
-// @section machine
+// @section kinematics
// Enable one of the options below for CoreXY, CoreXZ, or CoreYZ kinematics,
// either in the usual order or reversed
@@ -965,6 +967,15 @@
// Enable for a belt style printer with endless "Z" motion
//#define BELTPRINTER
+// Articulated robot (arm). Joints are directly mapped to axes with no kinematics.
+//#define ARTICULATED_ROBOT_ARM
+
+// For a hot wire cutter with parallel horizontal axes (X, I) where the heights of the two wire
+// ends are controlled by parallel axes (Y, J). Joints are directly mapped to axes (no kinematics).
+//#define FOAMCUTTER_XYUV
+
+// @section polargraph
+
// Enable for Polargraph Kinematics
//#define POLARGRAPH
#if ENABLED(POLARGRAPH)
@@ -1151,15 +1162,6 @@
#define FEEDRATE_SCALING // Convert XY feedrate from mm/s to degrees/s on the fly
#endif
-// @section machine
-
-// Articulated robot (arm). Joints are directly mapped to axes with no kinematics.
-//#define ARTICULATED_ROBOT_ARM
-
-// For a hot wire cutter with parallel horizontal axes (X, I) where the heights of the two wire
-// ends are controlled by parallel axes (Y, J). Joints are directly mapped to axes (no kinematics).
-//#define FOAMCUTTER_XYUV
-
//===========================================================================
//============================== Endstop Settings ===========================
//===========================================================================
@@ -1769,17 +1771,17 @@
// @section stepper drivers
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
-// :{ 0:'Low', 1:'High' }
-#define X_ENABLE_ON 0
-#define Y_ENABLE_ON 0
-#define Z_ENABLE_ON 0
-#define E_ENABLE_ON 0 // For all extruders
-//#define I_ENABLE_ON 0
-//#define J_ENABLE_ON 0
-//#define K_ENABLE_ON 0
-//#define U_ENABLE_ON 0
-//#define V_ENABLE_ON 0
-//#define W_ENABLE_ON 0
+// :['LOW', 'HIGH']
+#define X_ENABLE_ON LOW
+#define Y_ENABLE_ON LOW
+#define Z_ENABLE_ON LOW
+#define E_ENABLE_ON LOW // For all extruders
+//#define I_ENABLE_ON LOW
+//#define J_ENABLE_ON LOW
+//#define K_ENABLE_ON LOW
+//#define U_ENABLE_ON LOW
+//#define V_ENABLE_ON LOW
+//#define W_ENABLE_ON LOW
// Disable axis steppers immediately when they're not being stepped.
// WARNING: When motors turn off there is a chance of losing position accuracy!
@@ -3458,6 +3460,8 @@
* TFT_ROTATE_180, TFT_ROTATE_180_MIRROR_X, TFT_ROTATE_180_MIRROR_Y,
* TFT_ROTATE_270, TFT_ROTATE_270_MIRROR_X, TFT_ROTATE_270_MIRROR_Y,
* TFT_MIRROR_X, TFT_MIRROR_Y, TFT_NO_ROTATION
+ *
+ * :{ 'TFT_NO_ROTATION':'None', 'TFT_ROTATE_90':'90°', 'TFT_ROTATE_90_MIRROR_X':'90° (Mirror X)', 'TFT_ROTATE_90_MIRROR_Y':'90° (Mirror Y)', 'TFT_ROTATE_180':'180°', 'TFT_ROTATE_180_MIRROR_X':'180° (Mirror X)', 'TFT_ROTATE_180_MIRROR_Y':'180° (Mirror Y)', 'TFT_ROTATE_270':'270°', 'TFT_ROTATE_270_MIRROR_X':'270° (Mirror X)', 'TFT_ROTATE_270_MIRROR_Y':'270° (Mirror Y)', 'TFT_MIRROR_X':'Mirror X', 'TFT_MIRROR_Y':'Mirror Y' }
*/
//#define TFT_ROTATION TFT_NO_ROTATION
diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h
index 3928078d64bc..39cc1d5689c7 100644
--- a/Marlin/Configuration_adv.h
+++ b/Marlin/Configuration_adv.h
@@ -1260,8 +1260,8 @@
#define DISABLE_IDLE_E // Shut down all idle extruders
// Default Minimum Feedrates for printing and travel moves
-#define DEFAULT_MINIMUMFEEDRATE 0.0 // (mm/s. °/s for rotational-only moves) Minimum feedrate. Set with M205 S.
-#define DEFAULT_MINTRAVELFEEDRATE 0.0 // (mm/s. °/s for rotational-only moves) Minimum travel feedrate. Set with M205 T.
+#define DEFAULT_MINIMUMFEEDRATE 0.0 // (mm/s) Minimum feedrate. Set with M205 S.
+#define DEFAULT_MINTRAVELFEEDRATE 0.0 // (mm/s) Minimum travel feedrate. Set with M205 T.
// Minimum time that a segment needs to take as the buffer gets emptied
#define DEFAULT_MINSEGMENTTIME 20000 // (µs) Set with M205 B.
diff --git a/Marlin/Makefile b/Marlin/Makefile
index 0c5d7c227314..63b1029e1b38 100644
--- a/Marlin/Makefile
+++ b/Marlin/Makefile
@@ -1026,7 +1026,7 @@ extcoff: $(TARGET).elf
$(NM) -n $< > $@
# Link: create ELF output file from library.
-
+LDFLAGS+= -Wl,-V
$(BUILD_DIR)/$(TARGET).elf: $(OBJ) Configuration.h
$(Pecho) " CXX $@"
$P $(CXX) $(LD_PREFIX) $(ALL_CXXFLAGS) -o $@ -L. $(OBJ) $(LDFLAGS) $(LD_SUFFIX)
diff --git a/Marlin/Version.h b/Marlin/Version.h
index 55930b97f1a5..d973fcfdf7c3 100644
--- a/Marlin/Version.h
+++ b/Marlin/Version.h
@@ -41,7 +41,7 @@
* here we define this default string as the date where the latest release
* version was tagged.
*/
-//#define STRING_DISTRIBUTION_DATE "2024-10-21"
+//#define STRING_DISTRIBUTION_DATE "2024-11-13"
/**
* The protocol for communication to the host. Protocol indicates communication
diff --git a/Marlin/src/HAL/AVR/pinsDebug.h b/Marlin/src/HAL/AVR/pinsDebug.h
index b4352fdf1fa9..e9bc09a4bf5b 100644
--- a/Marlin/src/HAL/AVR/pinsDebug.h
+++ b/Marlin/src/HAL/AVR/pinsDebug.h
@@ -22,7 +22,23 @@
#pragma once
/**
- * PWM print routines for Atmel 8 bit AVR CPUs
+ * Pins Debugging for Atmel 8 bit AVR CPUs
+ *
+ * - NUMBER_PINS_TOTAL
+ * - MULTI_NAME_PAD
+ * - getPinByIndex(index)
+ * - printPinNameByIndex(index)
+ * - getPinIsDigitalByIndex(index)
+ * - digitalPinToAnalogIndex(pin)
+ * - getValidPinMode(pin)
+ * - isValidPin(pin)
+ * - isAnalogPin(pin)
+ * - digitalRead_mod(pin)
+ * - pwm_status(pin)
+ * - printPinPWM(pin)
+ * - printPinPort(pin)
+ * - printPinNumber(pin)
+ * - printPinAnalog(pin)
*/
#include "../../inc/MarlinConfig.h"
@@ -39,30 +55,30 @@
#include "pinsDebug_Teensyduino.h"
// Can't use the "digitalPinToPort" function from the Teensyduino type IDEs
// portModeRegister takes a different argument
- #define digitalPinToTimer_DEBUG(p) digitalPinToTimer(p)
- #define digitalPinToBitMask_DEBUG(p) digitalPinToBitMask(p)
- #define digitalPinToPort_DEBUG(p) digitalPinToPort(p)
- #define getValidPinMode(pin) (*portModeRegister(pin) & digitalPinToBitMask_DEBUG(pin))
+ #define digitalPinToTimer_DEBUG(P) digitalPinToTimer(P)
+ #define digitalPinToBitMask_DEBUG(P) digitalPinToBitMask(P)
+ #define digitalPinToPort_DEBUG(P) digitalPinToPort(P)
+ #define getValidPinMode(P) (*portModeRegister(P) & digitalPinToBitMask_DEBUG(P))
#elif AVR_ATmega2560_FAMILY_PLUS_70 // So we can access/display all the pins on boards using more than 70
#include "pinsDebug_plus_70.h"
- #define digitalPinToTimer_DEBUG(p) digitalPinToTimer_plus_70(p)
- #define digitalPinToBitMask_DEBUG(p) digitalPinToBitMask_plus_70(p)
- #define digitalPinToPort_DEBUG(p) digitalPinToPort_plus_70(p)
+ #define digitalPinToTimer_DEBUG(P) digitalPinToTimer_plus_70(P)
+ #define digitalPinToBitMask_DEBUG(P) digitalPinToBitMask_plus_70(P)
+ #define digitalPinToPort_DEBUG(P) digitalPinToPort_plus_70(P)
bool getValidPinMode(pin_t pin) {return *portModeRegister(digitalPinToPort_DEBUG(pin)) & digitalPinToBitMask_DEBUG(pin); }
#else
- #define digitalPinToTimer_DEBUG(p) digitalPinToTimer(p)
- #define digitalPinToBitMask_DEBUG(p) digitalPinToBitMask(p)
- #define digitalPinToPort_DEBUG(p) digitalPinToPort(p)
+ #define digitalPinToTimer_DEBUG(P) digitalPinToTimer(P)
+ #define digitalPinToBitMask_DEBUG(P) digitalPinToBitMask(P)
+ #define digitalPinToPort_DEBUG(P) digitalPinToPort(P)
bool getValidPinMode(pin_t pin) {return *portModeRegister(digitalPinToPort_DEBUG(pin)) & digitalPinToBitMask_DEBUG(pin); }
- #define getPinByIndex(p) pgm_read_byte(&pin_array[p].pin)
+ #define getPinByIndex(x) pgm_read_byte(&pin_array[x].pin)
#endif
-#define isValidPin(pin) (pin >= 0 && pin < NUM_DIGITAL_PINS ? 1 : 0)
+#define isValidPin(P) (P >= 0 && P < NUMBER_PINS_TOTAL)
#if AVR_ATmega1284_FAMILY
#define isAnalogPin(P) WITHIN(P, analogInputToDigitalPin(7), analogInputToDigitalPin(0))
#define digitalPinToAnalogIndex(P) int(isAnalogPin(P) ? (P) - analogInputToDigitalPin(7) : -1)
@@ -72,11 +88,11 @@
#define isAnalogPin(P) (_ANALOG1(P) || _ANALOG2(P))
#define digitalPinToAnalogIndex(P) int(_ANALOG1(P) ? (P) - analogInputToDigitalPin(0) : _ANALOG2(P) ? (P) - analogInputToDigitalPin(8) + 8 : -1)
#endif
-#define getPinByIndex(p) pgm_read_byte(&pin_array[p].pin)
+#define getPinByIndex(x) pgm_read_byte(&pin_array[x].pin)
#define MULTI_NAME_PAD 26 // space needed to be pretty if not first name assigned to a pin
-void printPinNameByIndex(uint8_t x) {
- PGM_P const name_mem_pointer = (PGM_P)pgm_read_ptr(&pin_array[x].name);
+void printPinNameByIndex(const uint8_t index) {
+ PGM_P const name_mem_pointer = (PGM_P)pgm_read_ptr(&pin_array[index].name);
for (uint8_t y = 0; y < MAX_NAME_LENGTH; ++y) {
char temp_char = pgm_read_byte(name_mem_pointer + y);
if (temp_char != 0)
@@ -109,7 +125,7 @@ void printPinNameByIndex(uint8_t x) {
* Print a pin's PWM status.
* Return true if it's currently a PWM pin.
*/
-bool pwm_status(uint8_t pin) {
+bool pwm_status(const uint8_t pin) {
char buffer[20]; // for the sprintf statements
switch (digitalPinToTimer_DEBUG(pin)) {
@@ -276,7 +292,7 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N -
if (TEST(*TMSK, TOIE)) err_prob_interrupt();
}
-void printPinPWM(uint8_t pin) {
+void printPinPWM(const uint8_t pin) {
switch (digitalPinToTimer_DEBUG(pin)) {
#if ABTEST(0)
@@ -386,7 +402,7 @@ void printPinPort(const pin_t pin) { // print port number
#endif
}
-#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
-#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
+#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3d "), P); SERIAL_ECHO(buffer); }while(0)
+#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
#undef ABTEST
diff --git a/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h b/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h
index c812d4fb1131..463a77ec1d08 100644
--- a/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h
+++ b/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h
@@ -102,7 +102,7 @@ const uint8_t PROGMEM digital_pin_to_port_PGM[] = {
// digitalPinToBitMask(pin) is OK
-#define digitalRead_mod(p) extDigitalRead(p) // Teensyduino's version of digitalRead doesn't
+#define digitalRead_mod(P) extDigitalRead(P) // Teensyduino's version of digitalRead doesn't
// disable the PWMs so we can use it as is
// portModeRegister(pin) is OK
diff --git a/Marlin/src/HAL/DUE/pinsDebug.h b/Marlin/src/HAL/DUE/pinsDebug.h
index e320189ed955..e9e364dcec77 100644
--- a/Marlin/src/HAL/DUE/pinsDebug.h
+++ b/Marlin/src/HAL/DUE/pinsDebug.h
@@ -19,13 +19,26 @@
* along with this program. If not, see .
*
*/
+#pragma once
/**
- * Support routines for Due
- */
-
-/**
- * Translation of routines & variables used by pinsDebug.h
+ * Pins Debugging for DUE
+ *
+ * - NUMBER_PINS_TOTAL
+ * - MULTI_NAME_PAD
+ * - getPinByIndex(index)
+ * - printPinNameByIndex(index)
+ * - getPinIsDigitalByIndex(index)
+ * - digitalPinToAnalogIndex(pin)
+ * - getValidPinMode(pin)
+ * - isValidPin(pin)
+ * - isAnalogPin(pin)
+ * - digitalRead_mod(pin)
+ * - pwm_status(pin)
+ * - printPinPWM(pin)
+ * - printPinPort(pin)
+ * - printPinNumber(pin)
+ * - printPinAnalog(pin)
*/
#include "../shared/Marduino.h"
@@ -63,20 +76,20 @@
#define NUMBER_PINS_TOTAL PINS_COUNT
-#define digitalRead_mod(p) extDigitalRead(p) // AVR digitalRead disabled PWM before it read the pin
+#define digitalRead_mod(P) extDigitalRead(P) // AVR digitalRead disabled PWM before it read the pin
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
-#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("%02d"), p); SERIAL_ECHO(buffer); }while(0)
-#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
-#define getPinByIndex(p) pin_array[p].pin
-#define getPinIsDigitalByIndex(p) pin_array[p].is_digital
-#define isValidPin(pin) (pin >= 0 && pin < int8_t(NUMBER_PINS_TOTAL))
-#define digitalPinToAnalogIndex(p) int(p - analogInputToDigitalPin(0))
+#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%02d"), P); SERIAL_ECHO(buffer); }while(0)
+#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
+#define getPinByIndex(x) pin_array[x].pin
+#define getPinIsDigitalByIndex(x) pin_array[x].is_digital
+#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL))
+#define digitalPinToAnalogIndex(P) int(P - analogInputToDigitalPin(0))
#define isAnalogPin(P) WITHIN(P, pin_t(analogInputToDigitalPin(0)), pin_t(analogInputToDigitalPin(NUM_ANALOG_INPUTS - 1)))
-#define pwm_status(pin) (((g_pinStatus[pin] & 0xF) == PIN_STATUS_PWM) && \
- ((g_APinDescription[pin].ulPinAttribute & PIN_ATTR_PWM) == PIN_ATTR_PWM))
+#define pwm_status(P) (((g_pinStatus[P] & 0xF) == PIN_STATUS_PWM) && \
+ ((g_APinDescription[P].ulPinAttribute & PIN_ATTR_PWM) == PIN_ATTR_PWM))
#define MULTI_NAME_PAD 14 // space needed to be pretty if not first name assigned to a pin
-bool getValidPinMode(int8_t pin) { // 1: output, 0: input
+bool getValidPinMode(const pin_t pin) { // 1: output, 0: input
volatile Pio* port = g_APinDescription[pin].pPort;
uint32_t mask = g_APinDescription[pin].ulPin;
uint8_t pin_status = g_pinStatus[pin] & 0xF;
@@ -85,7 +98,7 @@ bool getValidPinMode(int8_t pin) { // 1: output, 0: input
|| pwm_status(pin));
}
-void printPinPWM(int32_t pin) {
+void printPinPWM(const int32_t pin) {
if (pwm_status(pin)) {
uint32_t chan = g_APinDescription[pin].ulPWMChannel;
SERIAL_ECHOPGM("PWM = ", PWM_INTERFACE->PWM_CH_NUM[chan].PWM_CDTY);
diff --git a/Marlin/src/HAL/ESP32/fastio.h b/Marlin/src/HAL/ESP32/fastio.h
index c8e3f7e343e9..a85423d76812 100644
--- a/Marlin/src/HAL/ESP32/fastio.h
+++ b/Marlin/src/HAL/ESP32/fastio.h
@@ -37,6 +37,10 @@
// Set pin as output
#define _SET_OUTPUT(IO) pinMode(IO, OUTPUT)
+// TODO: Store set modes in an array and use those to get the mode
+#define _IS_OUTPUT(IO) true
+#define _IS_INPUT(IO) true
+
// Set pin as input with pullup mode
#define _PULLUP(IO, v) pinMode(IO, v ? INPUT_PULLUP : INPUT)
@@ -70,6 +74,9 @@
// Set pin as output and init
#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
+#define IS_OUTPUT(IO) _IS_OUTPUT(IO)
+#define IS_INPUT(IO) _IS_INPUT(IO)
+
// digitalRead/Write wrappers
#define extDigitalRead(IO) digitalRead(IO)
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
diff --git a/Marlin/src/HAL/ESP32/ota.cpp b/Marlin/src/HAL/ESP32/ota.cpp
index 01f5924871ff..be5847b83147 100644
--- a/Marlin/src/HAL/ESP32/ota.cpp
+++ b/Marlin/src/HAL/ESP32/ota.cpp
@@ -22,11 +22,15 @@
#ifdef ARDUINO_ARCH_ESP32
+#include
+
+#undef ENABLED
+#undef DISABLED
+
#include "../../inc/MarlinConfigPre.h"
#if ALL(WIFISUPPORT, OTASUPPORT)
-#include
#include
#include
#include
diff --git a/Marlin/src/HAL/ESP32/pinsDebug.h b/Marlin/src/HAL/ESP32/pinsDebug.h
new file mode 100644
index 000000000000..42304b2a0be0
--- /dev/null
+++ b/Marlin/src/HAL/ESP32/pinsDebug.h
@@ -0,0 +1,71 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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
+
+#error "PINS_DEBUGGING is not yet supported for ESP32!"
+
+/**
+ * Pins Debugging for ESP32
+ *
+ * - NUMBER_PINS_TOTAL
+ * - MULTI_NAME_PAD
+ * - getPinByIndex(index)
+ * - printPinNameByIndex(index)
+ * - getPinIsDigitalByIndex(index)
+ * - digitalPinToAnalogIndex(pin)
+ * - getValidPinMode(pin)
+ * - isValidPin(pin)
+ * - isAnalogPin(pin)
+ * - digitalRead_mod(pin)
+ * - pwm_status(pin)
+ * - printPinPWM(pin)
+ * - printPinPort(pin)
+ * - printPinNumber(pin)
+ * - printPinAnalog(pin)
+ */
+
+#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
+#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
+
+#define digitalRead_mod(P) extDigitalRead(P)
+#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
+#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%02d"), P); SERIAL_ECHO(buffer); }while(0)
+#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
+#define getPinByIndex(x) pin_array[x].pin
+#define getPinIsDigitalByIndex(x) pin_array[x].is_digital
+#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL))
+#define digitalPinToAnalogIndex(P) int(P - analogInputToDigitalPin(0))
+#define isAnalogPin(P) WITHIN(P, pin_t(analogInputToDigitalPin(0)), pin_t(analogInputToDigitalPin(NUM_ANALOG_INPUTS - 1)))
+bool pwm_status(const pin_t) { return false; }
+
+void printPinPort(const pin_t) {}
+
+static bool getValidPinMode(const pin_t pin) {
+ return isValidPin(pin) && !IS_INPUT(pin);
+}
+
+void printPinPWM(const int32_t pin) {
+ if (pwm_status(pin)) {
+ //uint32_t chan = g_APinDescription[pin].ulPWMChannel TODO when fast pwm is operative;
+ //SERIAL_ECHOPGM("PWM = ", duty);
+ }
+}
diff --git a/Marlin/src/HAL/HC32/pinsDebug.h b/Marlin/src/HAL/HC32/pinsDebug.h
index c00ddf3ba252..e80b5a081e4d 100644
--- a/Marlin/src/HAL/HC32/pinsDebug.h
+++ b/Marlin/src/HAL/HC32/pinsDebug.h
@@ -18,41 +18,47 @@
*/
#pragma once
+/**
+ * Pins Debugging for HC32
+ *
+ * - NUMBER_PINS_TOTAL
+ * - MULTI_NAME_PAD
+ * - getPinByIndex(index)
+ * - printPinNameByIndex(index)
+ * - getPinIsDigitalByIndex(index)
+ * - digitalPinToAnalogIndex(pin)
+ * - getValidPinMode(pin)
+ * - isValidPin(pin)
+ * - isAnalogPin(pin)
+ * - digitalRead_mod(pin)
+ * - pwm_status(pin)
+ * - printPinPWM(pin)
+ * - printPinPort(pin)
+ * - printPinNumber(pin)
+ * - printPinAnalog(pin)
+ */
+
#include "../../inc/MarlinConfig.h"
#include "fastio.h"
#include
-//
-// Translation of routines & variables used by pinsDebug.h
-//
#ifndef BOARD_NR_GPIO_PINS
#error "Expected BOARD_NR_GPIO_PINS not found."
#endif
#define NUM_DIGITAL_PINS BOARD_NR_GPIO_PINS
#define NUMBER_PINS_TOTAL BOARD_NR_GPIO_PINS
-#define isValidPin(pin) IS_GPIO_PIN(pin)
+#define isValidPin(P) IS_GPIO_PIN(P)
// Note: pin_array is defined in `Marlin/src/pins/pinsDebug.h`, and since this file is included
// after it, it is available in this file as well.
-#define getPinByIndex(p) pin_t(pin_array[p].pin)
-#define digitalRead_mod(p) extDigitalRead(p)
-#define printPinNumber(p) \
- do { \
- sprintf_P(buffer, PSTR("%3hd "), int16_t(p)); \
- SERIAL_ECHO(buffer); \
- } while (0)
-#define printPinAnalog(p) \
- do { \
- sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); \
- SERIAL_ECHO(buffer); \
- } while (0)
-#define PRINT_PORT(p) printPinPort(p)
-#define printPinNameByIndex(x) \
- do { \
- sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); \
- SERIAL_ECHO(buffer); \
- } while (0)
+#define getPinByIndex(x) pin_t(pin_array[x].pin)
+#define digitalRead_mod(P) extDigitalRead(P)
+
+#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(P)); SERIAL_ECHO(buffer); }while(0)
+#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
+
+#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 21 // Space needed to be pretty if not first name assigned to a pin
@@ -71,13 +77,13 @@
#define M43_NEVER_TOUCH(Q) (IS_HOST_USART_PIN(Q) || IS_OSC_PIN(Q))
#endif
-static int8_t digitalPinToAnalogIndex(pin_t pin) {
+int8_t digitalPinToAnalogIndex(const pin_t pin) {
if (!isValidPin(pin)) return -1;
const int8_t adc_channel = int8_t(PIN_MAP[pin].adc_info.channel);
return pin_t(adc_channel);
}
-static bool isAnalogPin(pin_t pin) {
+bool isAnalogPin(pin_t pin) {
if (!isValidPin(pin)) return false;
if (PIN_MAP[pin].adc_info.channel != ADC_PIN_INVALID)
@@ -86,12 +92,12 @@ static bool isAnalogPin(pin_t pin) {
return false;
}
-static bool getValidPinMode(const pin_t pin) {
+bool getValidPinMode(const pin_t pin) {
return isValidPin(pin) && !IS_INPUT(pin);
}
-static bool getPinIsDigitalByIndex(const int16_t array_pin) {
- const pin_t pin = getPinByIndex(array_pin);
+bool getPinIsDigitalByIndex(const int16_t index) {
+ const pin_t pin = getPinByIndex(index);
return (!isAnalogPin(pin));
}
diff --git a/Marlin/src/HAL/LINUX/include/pinmapping.h b/Marlin/src/HAL/LINUX/include/pinmapping.h
index b766f303886d..9147ef82de74 100644
--- a/Marlin/src/HAL/LINUX/include/pinmapping.h
+++ b/Marlin/src/HAL/LINUX/include/pinmapping.h
@@ -37,29 +37,29 @@ constexpr uint8_t NUM_ANALOG_INPUTS = 16;
constexpr uint8_t analog_offset = NUM_DIGITAL_PINS - NUM_ANALOG_INPUTS;
// Get the digital pin for an analog index
-constexpr pin_t analogInputToDigitalPin(const int8_t p) {
- return (WITHIN(p, 0, NUM_ANALOG_INPUTS) ? analog_offset + p : P_NC);
+constexpr pin_t analogInputToDigitalPin(const int8_t a) {
+ return (WITHIN(a, 0, NUM_ANALOG_INPUTS - 1) ? analog_offset + a : P_NC);
}
// Get the analog index for a digital pin
-constexpr int8_t digitalPinToAnalogIndex(const pin_t p) {
- return (WITHIN(p, analog_offset, NUM_DIGITAL_PINS) ? p - analog_offset : P_NC);
+constexpr int8_t digitalPinToAnalogIndex(const pin_t pin) {
+ return (WITHIN(pin, analog_offset, NUM_DIGITAL_PINS - 1) ? pin - analog_offset : P_NC);
}
// Return the index of a pin number
constexpr int16_t GET_PIN_MAP_INDEX(const pin_t pin) { return pin; }
// Test whether the pin is valid
-constexpr bool isValidPin(const pin_t p) { return WITHIN(p, 0, NUM_DIGITAL_PINS); }
+constexpr bool isValidPin(const pin_t pin) { return WITHIN(pin, 0, NUM_DIGITAL_PINS - 1); }
// Test whether the pin is PWM
-constexpr bool PWM_PIN(const pin_t p) { return false; }
+constexpr bool PWM_PIN(const pin_t) { return false; }
// Test whether the pin is interruptible
-constexpr bool INTERRUPT_PIN(const pin_t p) { return false; }
+constexpr bool INTERRUPT_PIN(const pin_t) { return false; }
// Get the pin number at the given index
-constexpr pin_t GET_PIN_MAP_PIN(const int16_t ind) { return ind; }
+constexpr pin_t GET_PIN_MAP_PIN(const int16_t index) { return pin_t(index); }
// Parse a G-code word into a pin index
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
diff --git a/Marlin/src/HAL/LINUX/pinsDebug.h b/Marlin/src/HAL/LINUX/pinsDebug.h
index 59290df6e05b..aacb626105d1 100644
--- a/Marlin/src/HAL/LINUX/pinsDebug.h
+++ b/Marlin/src/HAL/LINUX/pinsDebug.h
@@ -19,26 +19,46 @@
* along with this program. If not, see .
*
*/
+#pragma once
/**
- * Support routines for X86_64
- */
-
-/**
- * Translation of routines & variables used by pinsDebug.h
+ * Pins Debugging for Linux Native
+ *
+ * - NUMBER_PINS_TOTAL
+ * - MULTI_NAME_PAD
+ * - getPinByIndex(index)
+ * - printPinNameByIndex(index)
+ * - getPinIsDigitalByIndex(index)
+ * - digitalPinToAnalogIndex(pin)
+ * - getValidPinMode(pin)
+ * - isValidPin(pin)
+ * - isAnalogPin(pin)
+ * - digitalRead_mod(pin)
+ * - pwm_status(pin)
+ * - printPinPWM(pin)
+ * - printPinPort(pin)
+ * - printPinNumber(pin)
+ * - printPinAnalog(pin)
*/
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
-#define isAnalogPin(P) (digitalPinToAnalogIndex(P) >= 0 ? 1 : 0)
-#define digitalRead_mod(p) digitalRead(p)
-#define getPinByIndex(p) pin_array[p].pin
-#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
-#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
-#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
+#define getPinByIndex(x) pin_array[x].pin
+
+#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
+
// active ADC function/mode/code values for PINSEL registers
-constexpr int8_t ADC_pin_mode(pin_t pin) { return -1; }
+constexpr int8_t ADC_pin_mode(const pin_t) { return -1; }
+
+// The pin and index are the same on this platform
+bool getPinIsDigitalByIndex(const pin_t pin) {
+ return (!isAnalogPin(pin) || get_pin_mode(pin) != ADC_pin_mode(pin));
+}
+
+#define isAnalogPin(P) (digitalPinToAnalogIndex(P) >= 0)
+
+#define digitalRead_mod(P) digitalRead(P)
int8_t get_pin_mode(const pin_t pin) { return isValidPin(pin) ? 0 : -1; }
@@ -50,11 +70,11 @@ bool getValidPinMode(const pin_t pin) {
return (Gpio::getMode(pin) != 0); // Input/output state
}
-bool getPinIsDigitalByIndex(const pin_t pin) {
- return (!isAnalogPin(pin) || get_pin_mode(pin) != ADC_pin_mode(pin));
-}
-
-void printPinPWM(const pin_t pin) {}
+void printPinPWM(const pin_t) {}
bool pwm_status(const pin_t) { return false; }
void printPinPort(const pin_t) {}
+
+#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3d "), P); SERIAL_ECHO(buffer); }while(0)
+
+#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
diff --git a/Marlin/src/HAL/LPC1768/pinsDebug.h b/Marlin/src/HAL/LPC1768/pinsDebug.h
index a520874e2fc6..5baeadd0dd72 100644
--- a/Marlin/src/HAL/LPC1768/pinsDebug.h
+++ b/Marlin/src/HAL/LPC1768/pinsDebug.h
@@ -19,22 +19,35 @@
* along with this program. If not, see .
*
*/
+#pragma once
/**
- * Support routines for LPC1768
- */
-
-/**
- * Translation of routines & variables used by pinsDebug.h
+ * Pins Debugging for LPC1768/9
+ *
+ * - NUMBER_PINS_TOTAL
+ * - MULTI_NAME_PAD
+ * - getPinByIndex(index)
+ * - printPinNameByIndex(index)
+ * - getPinIsDigitalByIndex(index)
+ * - digitalPinToAnalogIndex(pin)
+ * - getValidPinMode(pin)
+ * - isValidPin(pin)
+ * - isAnalogPin(pin)
+ * - digitalRead_mod(pin)
+ * - pwm_status(pin)
+ * - printPinPWM(pin)
+ * - printPinPort(pin)
+ * - printPinNumber(pin)
+ * - printPinAnalog(pin)
*/
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
-#define isAnalogPin(P) (digitalPinToAnalogIndex(P) >= 0 ? 1 : 0)
-#define digitalRead_mod(p) extDigitalRead(p)
-#define getPinByIndex(p) pin_array[p].pin
+#define isAnalogPin(P) (digitalPinToAnalogIndex(P) >= 0)
+#define digitalRead_mod(P) extDigitalRead(P)
+#define getPinByIndex(x) pin_array[x].pin
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
-#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("P%d_%02d"), LPC176x::pin_port(p), LPC176x::pin_bit(p)); SERIAL_ECHO(buffer); }while(0)
-#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR("_A%d "), LPC176x::pin_get_adc_channel(pin)); SERIAL_ECHO(buffer); }while(0)
+#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("P%d_%02d"), LPC176x::pin_port(P), LPC176x::pin_bit(P)); SERIAL_ECHO(buffer); }while(0)
+#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR("_A%d "), LPC176x::pin_get_adc_channel(P)); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 17 // 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
diff --git a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.cpp b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.cpp
index 6c74821d3039..1354c79b31ef 100644
--- a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.cpp
+++ b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.cpp
@@ -25,7 +25,7 @@
#include "../../inc/MarlinConfig.h"
#include "pinsDebug.h"
-int8_t ADC_pin_mode(pin_t pin) { return -1; }
+int8_t ADC_pin_mode(const pin_t) { return -1; }
int8_t get_pin_mode(const pin_t pin) { return isValidPin(pin) ? 0 : -1; }
@@ -37,6 +37,7 @@ bool getValidPinMode(const pin_t pin) {
return (Gpio::getMode(pin) != 0); // Input/output state
}
+// The pin and index are the same on this platform
bool getPinIsDigitalByIndex(const pin_t pin) {
return !isAnalogPin(pin) || get_pin_mode(pin) != ADC_pin_mode(pin);
}
diff --git a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h
index 8fea5765d8f4..752802d43808 100644
--- a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h
+++ b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h
@@ -19,30 +19,43 @@
* along with this program. If not, see .
*
*/
-
-/**
- * Support routines for X86_64
- */
#pragma once
/**
- * Translation of routines & variables used by pinsDebug.h
+ * Pins Debugging for x86_64
+ *
+ * - NUMBER_PINS_TOTAL
+ * - MULTI_NAME_PAD
+ * - getPinByIndex(index)
+ * - printPinNameByIndex(index)
+ * - getPinIsDigitalByIndex(index)
+ * - digitalPinToAnalogIndex(pin)
+ * - getValidPinMode(pin)
+ * - isValidPin(pin)
+ * - isAnalogPin(pin)
+ * - digitalRead_mod(pin)
+ * - pwm_status(pin)
+ * - printPinPWM(pin)
+ * - printPinPort(pin)
+ * - printPinNumber(pin)
+ * - printPinAnalog(pin)
*/
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
-#define isAnalogPin(P) (digitalPinToAnalogIndex(P) >= 0 ? 1 : 0)
-#define digitalRead_mod(p) digitalRead(p)
-#define getPinByIndex(p) pin_array[p].pin
+#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL))
+#define isAnalogPin(P) (digitalPinToAnalogIndex(P) >= 0)
+#define digitalRead_mod(P) digitalRead(P)
+#define getPinByIndex(x) pin_array[x].pin
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
-#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
-#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
+#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3d "), P); SERIAL_ECHO(buffer); }while(0)
+#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
// Active ADC function/mode/code values for PINSEL registers
-int8_t ADC_pin_mode(pin_t pin);
-int8_t get_pin_mode(const pin_t pin);
-bool getValidPinMode(const pin_t pin);
-bool getPinIsDigitalByIndex(const pin_t pin);
+int8_t ADC_pin_mode(const pin_t);
+int8_t get_pin_mode(const pin_t);
+bool getValidPinMode(const pin_t);
+bool getPinIsDigitalByIndex(const pin_t);
void printPinPort(const pin_t);
void printPinPWM(const pin_t);
bool pwm_status(const pin_t);
diff --git a/Marlin/src/HAL/RP2040/HAL.cpp b/Marlin/src/HAL/RP2040/HAL.cpp
new file mode 100644
index 000000000000..d1af25a84219
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/HAL.cpp
@@ -0,0 +1,188 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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 "../platforms.h"
+
+#ifdef __PLAT_RP2040__
+
+#include "HAL.h"
+//#include "usb_serial.h"
+
+#include "../../inc/MarlinConfig.h"
+#include "../shared/Delay.h"
+
+extern "C" {
+ #include "pico/bootrom.h"
+ #include "hardware/watchdog.h"
+}
+
+#if HAS_SD_HOST_DRIVE
+ #include "msc_sd.h"
+ #include "usbd_cdc_if.h"
+#endif
+
+// ------------------------
+// Public Variables
+// ------------------------
+
+volatile uint16_t adc_result;
+
+// ------------------------
+// Public functions
+// ------------------------
+
+TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
+
+// HAL initialization task
+void MarlinHAL::init() {
+ // Ensure F_CPU is a constant expression.
+ // If the compiler breaks here, it means that delay code that should compute at compile time will not work.
+ // So better safe than sorry here.
+ constexpr int cpuFreq = F_CPU;
+ UNUSED(cpuFreq);
+
+ #undef SDSS
+ #define SDSS 2
+ #define PIN_EXISTS_(P1,P2) (defined(P1##P2) && P1##P2 >= 0)
+ #if HAS_MEDIA && DISABLED(SDIO_SUPPORT) && PIN_EXISTS_(SDSS,)
+ OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up
+ #endif
+
+ #if PIN_EXISTS(LED)
+ OUT_WRITE(LED_PIN, LOW);
+ #endif
+
+ #if ENABLED(SRAM_EEPROM_EMULATION)
+ // __HAL_RCC_PWR_CLK_ENABLE();
+ // HAL_PWR_EnableBkUpAccess(); // Enable access to backup SRAM
+ // __HAL_RCC_BKPSRAM_CLK_ENABLE();
+ // LL_PWR_EnableBkUpRegulator(); // Enable backup regulator
+ // while (!LL_PWR_IsActiveFlag_BRR()); // Wait until backup regulator is initialized
+ #endif
+
+ HAL_timer_init();
+
+ #if ENABLED(EMERGENCY_PARSER) && USBD_USE_CDC
+ USB_Hook_init();
+ #endif
+
+ TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler
+
+ TERN_(HAS_SD_HOST_DRIVE, MSC_SD_init()); // Enable USB SD card access
+
+ #if PIN_EXISTS(USB_CONNECT)
+ OUT_WRITE(USB_CONNECT_PIN, !USB_CONNECT_INVERTING); // USB clear connection
+ delay_ms(1000); // Give OS time to notice
+ WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING);
+ #endif
+}
+
+uint8_t MarlinHAL::get_reset_source() {
+ return watchdog_enable_caused_reboot() ? RST_WATCHDOG : 0;
+}
+
+void MarlinHAL::reboot() { watchdog_reboot(0, 0, 1); }
+
+// ------------------------
+// Watchdog Timer
+// ------------------------
+
+#if ENABLED(USE_WATCHDOG)
+
+ #define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout
+
+ extern "C" {
+ #include "hardware/watchdog.h"
+ }
+
+ void MarlinHAL::watchdog_init() {
+ #if DISABLED(DISABLE_WATCHDOG_INIT)
+ static_assert(WDT_TIMEOUT_US > 1000, "WDT Timout is too small, aborting");
+ watchdog_enable(WDT_TIMEOUT_US/1000, true);
+ #endif
+ }
+
+ void MarlinHAL::watchdog_refresh() {
+ watchdog_update();
+ #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
+ TOGGLE(LED_PIN); // heartbeat indicator
+ #endif
+ }
+
+#endif
+
+// ------------------------
+// ADC
+// ------------------------
+
+volatile bool MarlinHAL::adc_has_result = false;
+
+void MarlinHAL::adc_init() {
+ analogReadResolution(HAL_ADC_RESOLUTION);
+ ::adc_init();
+ adc_fifo_setup(true, false, 1, false, false);
+ irq_set_exclusive_handler(ADC_IRQ_FIFO, adc_exclusive_handler);
+ irq_set_enabled(ADC_IRQ_FIFO, true);
+ adc_irq_set_enabled(true);
+}
+
+void MarlinHAL::adc_enable(const pin_t pin) {
+ if (pin >= A0 && pin <= A3)
+ adc_gpio_init(pin);
+ else if (pin == HAL_ADC_MCU_TEMP_DUMMY_PIN)
+ adc_set_temp_sensor_enabled(true);
+}
+
+void MarlinHAL::adc_start(const pin_t pin) {
+ adc_has_result = false;
+ // Select an ADC input. 0...3 are GPIOs 26...29 respectively.
+ adc_select_input(pin == HAL_ADC_MCU_TEMP_DUMMY_PIN ? 4 : pin - A0);
+ adc_run(true);
+}
+
+void MarlinHAL::adc_exclusive_handler() {
+ adc_run(false); // Disable since we only want one result
+ irq_clear(ADC_IRQ_FIFO); // Clear the IRQ
+
+ if (adc_fifo_get_level() >= 1) {
+ adc_result = adc_fifo_get(); // Pop the result
+ adc_fifo_drain();
+ adc_has_result = true; // Signal the end of the conversion
+ }
+}
+
+uint16_t MarlinHAL::adc_value() { return adc_result; }
+
+// Reset the system to initiate a firmware flash
+void flashFirmware(const int16_t) { hal.reboot(); }
+
+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__);
+}
+
+#endif // __PLAT_RP2040__
diff --git a/Marlin/src/HAL/RP2040/HAL.h b/Marlin/src/HAL/RP2040/HAL.h
new file mode 100644
index 000000000000..fa1a35683e1f
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/HAL.h
@@ -0,0 +1,250 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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 CPU_32_BIT
+
+#ifndef F_CPU
+ #define F_CPU (XOSC_MHZ * 1000000UL)
+#endif
+
+#include "arduino_extras.h"
+#include "../../core/macros.h"
+#include "../shared/Marduino.h"
+#include "../shared/math_32bit.h"
+#include "../shared/HAL_SPI.h"
+#include "fastio.h"
+//#include "Servo.h"
+#include "watchdog.h"
+#include "MarlinSerial.h"
+
+#include "../../inc/MarlinConfigPre.h"
+
+#include
+
+// ------------------------
+// Serial ports
+// ------------------------
+
+#include "../../core/serial_hook.h"
+typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1;
+extern DefaultSerial1 MSerial0;
+
+#define _MSERIAL(X) MSerial##X
+#define MSERIAL(X) _MSERIAL(X)
+
+#if SERIAL_PORT == -1
+ #define MYSERIAL1 MSerial0
+#elif WITHIN(SERIAL_PORT, 0, 6)
+ #define MYSERIAL1 MSERIAL(SERIAL_PORT)
+#else
+ #error "SERIAL_PORT must be from 0 to 6. You can also use -1 if the board supports Native USB."
+#endif
+
+#ifdef SERIAL_PORT_2
+ #if SERIAL_PORT_2 == -1
+ #define MYSERIAL2 MSerial0
+ #elif WITHIN(SERIAL_PORT_2, 0, 6)
+ #define MYSERIAL2 MSERIAL(SERIAL_PORT_2)
+ #else
+ #error "SERIAL_PORT_2 must be from 0 to 6. You can also use -1 if the board supports Native USB."
+ #endif
+#endif
+
+#ifdef SERIAL_PORT_3
+ #if SERIAL_PORT_3 == -1
+ #define MYSERIAL3 MSerial0
+ #elif WITHIN(SERIAL_PORT_3, 0, 6)
+ #define MYSERIAL3 MSERIAL(SERIAL_PORT_3)
+ #else
+ #error "SERIAL_PORT_3 must be from 0 to 6. You can also use -1 if the board supports Native USB."
+ #endif
+#endif
+
+#ifdef MMU2_SERIAL_PORT
+ #if MMU2_SERIAL_PORT == -1
+ #define MMU2_SERIAL MSerial0
+ #elif WITHIN(MMU2_SERIAL_PORT, 0, 6)
+ #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT)
+ #else
+ #error "MMU2_SERIAL_PORT must be from 0 to 6. You can also use -1 if the board supports Native USB."
+ #endif
+#endif
+
+#ifdef LCD_SERIAL_PORT
+ #if LCD_SERIAL_PORT == -1
+ #define LCD_SERIAL MSerial0
+ #elif WITHIN(LCD_SERIAL_PORT, 0, 6)
+ #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT)
+ #else
+ #error "LCD_SERIAL_PORT must be from 0 to 6. You can also use -1 if the board supports Native USB."
+ #endif
+ #if HAS_DGUS_LCD
+ #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite()
+ #endif
+#endif
+
+// ------------------------
+// Defines
+// ------------------------
+
+/**
+ * TODO: review this to return 1 for pins that are not analog input
+ */
+#ifndef analogInputToDigitalPin
+ #define analogInputToDigitalPin(p) (p)
+#endif
+
+#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq()
+#define CRITICAL_SECTION_END() if (!primask) __enable_irq()
+#define cli() __disable_irq()
+#define sei() __enable_irq()
+
+// ------------------------
+// Types
+// ------------------------
+
+template struct IFPIN { typedef R type; };
+template struct IFPIN { typedef L type; };
+typedef IFPIN::type pin_t;
+
+class libServo;
+typedef libServo hal_servo_t;
+#define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos()
+#define RESUME_SERVO_OUTPUT() libServo::resume_all_servos()
+
+// ------------------------
+// ADC
+// ------------------------
+
+#define HAL_ADC_VREF 3.3
+#ifdef ADC_RESOLUTION
+ #define HAL_ADC_RESOLUTION ADC_RESOLUTION
+#else
+ #define HAL_ADC_RESOLUTION 12
+#endif
+// ADC index 4 is the MCU temperature
+#define HAL_ADC_MCU_TEMP_DUMMY_PIN 127
+
+//
+// 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)
+
+#ifndef PLATFORM_M997_SUPPORT
+ #define PLATFORM_M997_SUPPORT
+#endif
+void flashFirmware(const int16_t);
+
+// Maple Compatibility
+typedef void (*systickCallback_t)(void);
+void systick_attach_callback(systickCallback_t cb);
+void HAL_SYSTICK_Callback();
+
+extern volatile uint32_t systick_uptime_millis;
+
+#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment
+#define PWM_FREQUENCY 1000 // Default PWM frequency when set_pwm_duty() is called without set_pwm_frequency()
+
+// ------------------------
+// Class Utilities
+// ------------------------
+
+int freeMemory();
+
+// ------------------------
+// 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() { __enable_irq(); }
+ static void isr_off() { __disable_irq(); }
+
+ 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
+ //
+
+ // 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 pin_t pin);
+
+ // Begin ADC sampling on the given pin. Called from Temperature::isr!
+ static void adc_start(const pin_t pin);
+
+ // This ADC runs a periodic task
+ static void adc_exclusive_handler();
+
+ // Is the ADC ready for reading?
+ static volatile bool adc_has_result;
+ static bool adc_ready() { return adc_has_result; }
+
+ // The current value of the ADC register
+ static uint16_t adc_value();
+
+ /**
+ * Set the PWM duty cycle for the pin to the given value.
+ * Optionally invert the duty cycle [default = false]
+ * Optionally 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 v_size=255, const bool invert=false);
+
+ /**
+ * Set the frequency of the timer for the given pin as close as
+ * possible to the provided desired frequency. Internally calculate
+ * the required waveform generation mode, prescaler, and resolution
+ * values and set timer registers accordingly.
+ * NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B)
+ * NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST_PWM_FAN Settings)
+ */
+ static void set_pwm_frequency(const pin_t pin, const uint16_t f_desired);
+};
diff --git a/Marlin/src/HAL/RP2040/HAL_MinSerial.cpp b/Marlin/src/HAL/RP2040/HAL_MinSerial.cpp
new file mode 100644
index 000000000000..5a651635916b
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/HAL_MinSerial.cpp
@@ -0,0 +1,69 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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 "../platforms.h"
+
+#ifdef __PLAT_RP2040__
+
+#include "../../inc/MarlinConfigPre.h"
+
+#if ENABLED(POSTMORTEM_DEBUGGING)
+
+#include "../shared/HAL_MinSerial.h"
+
+
+static void TXBegin() {
+ #if !WITHIN(SERIAL_PORT, -1, 2)
+ #warning "Using POSTMORTEM_DEBUGGING requires a physical U(S)ART hardware in case of severe error."
+ #warning "Disabling the severe error reporting feature currently because the used serial port is not a HW port."
+ #else
+ #if SERIAL_PORT == -1
+ USBSerial.begin(BAUDRATE);
+ #elif SERIAL_PORT == 0
+ USBSerial.begin(BAUDRATE);
+ #elif SERIAL_PORT == 1
+ Serial1.begin(BAUDRATE);
+ #endif
+ #endif
+}
+
+static void TX(char b){
+ #if SERIAL_PORT == -1
+ USBSerial
+ #elif SERIAL_PORT == 0
+ USBSerial
+ #elif SERIAL_PORT == 1
+ Serial1
+ #endif
+ .write(b);
+}
+
+// A SW memory barrier, to ensure GCC does not overoptimize loops
+#define sw_barrier() __asm__ volatile("": : :"memory");
+
+
+void install_min_serial() {
+ HAL_min_serial_init = &TXBegin;
+ HAL_min_serial_out = &TX;
+}
+
+#endif // POSTMORTEM_DEBUGGING
+#endif // __PLAT_RP2040__
diff --git a/Marlin/src/HAL/RP2040/HAL_SPI.cpp b/Marlin/src/HAL/RP2040/HAL_SPI.cpp
new file mode 100644
index 000000000000..c88b6d1e5b03
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/HAL_SPI.cpp
@@ -0,0 +1,228 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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 "../platforms.h"
+
+#ifdef __PLAT_RP2040__
+
+#include "../../inc/MarlinConfig.h"
+
+#include
+
+// ------------------------
+// Public Variables
+// ------------------------
+
+static SPISettings spiConfig;
+
+// ------------------------
+// Public functions
+// ------------------------
+
+#if ENABLED(SOFTWARE_SPI)
+
+ // ------------------------
+ // Software SPI
+ // ------------------------
+
+ #include "../shared/Delay.h"
+
+ void spiBegin(void) {
+ OUT_WRITE(SD_SS_PIN, HIGH);
+ OUT_WRITE(SD_SCK_PIN, HIGH);
+ SET_INPUT(SD_MISO_PIN);
+ OUT_WRITE(SD_MOSI_PIN, HIGH);
+ }
+
+ // Use function with compile-time value so we can actually reach the desired frequency
+ // Need to adjust this a little bit: on a 72MHz clock, we have 14ns/clock
+ // and we'll use ~3 cycles to jump to the method and going back, so it'll take ~40ns from the given clock here
+ #define CALLING_COST_NS (3U * 1000000000U) / (F_CPU)
+ void (*delaySPIFunc)();
+ void delaySPI_125() { DELAY_NS(125 - CALLING_COST_NS); }
+ void delaySPI_250() { DELAY_NS(250 - CALLING_COST_NS); }
+ void delaySPI_500() { DELAY_NS(500 - CALLING_COST_NS); }
+ void delaySPI_1000() { DELAY_NS(1000 - CALLING_COST_NS); }
+ void delaySPI_2000() { DELAY_NS(2000 - CALLING_COST_NS); }
+ void delaySPI_4000() { DELAY_NS(4000 - CALLING_COST_NS); }
+
+ void spiInit(uint8_t spiRate) {
+ // Use datarates Marlin uses
+ switch (spiRate) {
+ case SPI_FULL_SPEED: delaySPIFunc = &delaySPI_125; break; // desired: 8,000,000 actual: ~1.1M
+ case SPI_HALF_SPEED: delaySPIFunc = &delaySPI_125; break; // desired: 4,000,000 actual: ~1.1M
+ case SPI_QUARTER_SPEED:delaySPIFunc = &delaySPI_250; break; // desired: 2,000,000 actual: ~890K
+ case SPI_EIGHTH_SPEED: delaySPIFunc = &delaySPI_500; break; // desired: 1,000,000 actual: ~590K
+ case SPI_SPEED_5: delaySPIFunc = &delaySPI_1000; break; // desired: 500,000 actual: ~360K
+ case SPI_SPEED_6: delaySPIFunc = &delaySPI_2000; break; // desired: 250,000 actual: ~210K
+ default: delaySPIFunc = &delaySPI_4000; break; // desired: 125,000 actual: ~123K
+ }
+ SPI.begin();
+ }
+
+ // Begin SPI transaction, set clock, bit order, data mode
+ void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { /* do nothing */ }
+
+ uint8_t HAL_SPI_RP2040_SpiTransfer_Mode_3(uint8_t b) { // using Mode 3
+ for (uint8_t bits = 8; bits--;) {
+ WRITE(SD_SCK_PIN, LOW);
+ WRITE(SD_MOSI_PIN, b & 0x80);
+
+ delaySPIFunc();
+ WRITE(SD_SCK_PIN, HIGH);
+ delaySPIFunc();
+
+ b <<= 1; // little setup time
+ b |= (READ(SD_MISO_PIN) != 0);
+ }
+ DELAY_NS(125);
+ return b;
+ }
+
+ // Soft SPI receive byte
+ uint8_t spiRec() {
+ hal.isr_off(); // No interrupts during byte receive
+ const uint8_t data = HAL_SPI_RP2040_SpiTransfer_Mode_3(0xFF);
+ hal.isr_on(); // Enable interrupts
+ return data;
+ }
+
+ // Soft SPI read data
+ void spiRead(uint8_t *buf, uint16_t nbyte) {
+ for (uint16_t i = 0; i < nbyte; i++)
+ buf[i] = spiRec();
+ }
+
+ // Soft SPI send byte
+ void spiSend(uint8_t data) {
+ hal.isr_off(); // No interrupts during byte send
+ HAL_SPI_RP2040_SpiTransfer_Mode_3(data); // Don't care what is received
+ hal.isr_on(); // Enable interrupts
+ }
+
+ // Soft SPI send block
+ void spiSendBlock(uint8_t token, const uint8_t *buf) {
+ spiSend(token);
+ for (uint16_t i = 0; i < 512; i++)
+ spiSend(buf[i]);
+ }
+
+#else
+
+ // ------------------------
+ // Hardware SPI
+ // ------------------------
+
+ /**
+ * VGPV SPI speed start and PCLK2/2, by default 108/2 = 54Mhz
+ */
+
+ /**
+ * @brief Begin SPI port setup
+ *
+ * @return Nothing
+ *
+ * @details Only configures SS pin since stm32duino creates and initialize the SPI object
+ */
+ void spiBegin() {
+ #if PIN_EXISTS(SD_SS)
+ OUT_WRITE(SD_SS_PIN, HIGH);
+ #endif
+ }
+
+ // Configure SPI for specified SPI speed
+ void spiInit(uint8_t spiRate) {
+ // Use datarates Marlin uses
+ uint32_t clock;
+ switch (spiRate) {
+ case SPI_FULL_SPEED: clock = 20000000; break; // 13.9mhz=20000000 6.75mhz=10000000 3.38mhz=5000000 .833mhz=1000000
+ case SPI_HALF_SPEED: clock = 5000000; break;
+ case SPI_QUARTER_SPEED: clock = 2500000; break;
+ case SPI_EIGHTH_SPEED: clock = 1250000; break;
+ case SPI_SPEED_5: clock = 625000; break;
+ case SPI_SPEED_6: clock = 300000; break;
+ default:
+ clock = 4000000; // Default from the SPI library
+ }
+ spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0);
+
+ //SPI.setMISO(SD_MISO_PIN); //todo: implement? bad interface
+ //SPI.setMOSI(SD_MOSI_PIN);
+ //SPI.setSCLK(SD_SCK_PIN);
+
+ SPI.begin();
+ }
+
+ /**
+ * @brief Receives a single byte from the SPI port.
+ *
+ * @return Byte received
+ *
+ * @details
+ */
+ uint8_t spiRec() {
+ uint8_t returnByte = SPI.transfer(0xFF);
+ return returnByte;
+ }
+
+ /**
+ * @brief Receive a number of bytes from the SPI port to a buffer
+ *
+ * @param buf Pointer to starting address of buffer to write to.
+ * @param nbyte Number of bytes to receive.
+ * @return Nothing
+ *
+ * @details Uses DMA
+ */
+ void spiRead(uint8_t *buf, uint16_t nbyte) {
+ if (nbyte == 0) return;
+ memset(buf, 0xFF, nbyte);
+ SPI.transfer(buf, nbyte);
+ }
+
+ /**
+ * @brief Send a single byte on SPI port
+ *
+ * @param b Byte to send
+ *
+ * @details
+ */
+ void spiSend(uint8_t b) {
+ SPI.transfer(b);
+ }
+
+ /**
+ * @brief Write token and then write from 512 byte buffer to SPI (for SD card)
+ *
+ * @param buf Pointer with buffer start address
+ * @return Nothing
+ *
+ * @details Use DMA
+ */
+ void spiSendBlock(uint8_t token, const uint8_t *buf) {
+ //uint8_t rxBuf[512];
+ //SPI.transfer(token);
+ SPI.transfer((uint8_t*)buf, 512); //implement? bad interface
+ }
+
+#endif // SOFTWARE_SPI
+
+#endif // __PLAT_RP2040__
diff --git a/Marlin/src/HAL/RP2040/MarlinSerial.cpp b/Marlin/src/HAL/RP2040/MarlinSerial.cpp
new file mode 100644
index 000000000000..dd01edd83044
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/MarlinSerial.cpp
@@ -0,0 +1,39 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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 "../platforms.h"
+
+#ifdef __PLAT_RP2040__
+
+#include "../../inc/MarlinConfig.h"
+#include "MarlinSerial.h"
+
+#if ENABLED(EMERGENCY_PARSER)
+ #include "../../feature/e_parser.h"
+#endif
+
+#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
+#define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X)
+#if WITHIN(SERIAL_PORT, 0, 3)
+ IMPLEMENT_SERIAL(SERIAL_PORT);
+#endif
+
+#endif // __PLAT_RP2040__
diff --git a/Marlin/src/HAL/RP2040/MarlinSerial.h b/Marlin/src/HAL/RP2040/MarlinSerial.h
new file mode 100644
index 000000000000..c5924c90621d
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/MarlinSerial.h
@@ -0,0 +1,52 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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 "../../inc/MarlinConfigPre.h"
+
+#if ENABLED(EMERGENCY_PARSER)
+ #include "../../feature/e_parser.h"
+#endif
+
+#include "../../core/serial_hook.h"
+
+#define Serial0 Serial
+#define _DECLARE_SERIAL(X) \
+ typedef ForwardSerial1Class DefaultSerial##X; \
+ extern DefaultSerial##X MSerial##X
+#define DECLARE_SERIAL(X) _DECLARE_SERIAL(X)
+
+typedef ForwardSerial1Class USBSerialType;
+extern USBSerialType USBSerial;
+
+#define _MSERIAL(X) MSerial##X
+#define MSERIAL(X) _MSERIAL(X)
+
+#if SERIAL_PORT == -1
+ // #define MYSERIAL1 USBSerial this is already done in the HAL
+#elif WITHIN(SERIAL_PORT, 0, 3)
+ #define MYSERIAL1 MSERIAL(SERIAL_PORT)
+ DECLARE_SERIAL(SERIAL_PORT);
+#else
+ #error "SERIAL_PORT must be from 0 to 3, or -1 for Native USB."
+#endif
+
diff --git a/Marlin/src/HAL/RP2040/README.md b/Marlin/src/HAL/RP2040/README.md
new file mode 100644
index 000000000000..4f9f70b8c9e4
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/README.md
@@ -0,0 +1 @@
+# RP2040 Hardware Interface
diff --git a/Marlin/src/HAL/RP2040/Servo.cpp b/Marlin/src/HAL/RP2040/Servo.cpp
new file mode 100644
index 000000000000..2b1b2a1744b6
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/Servo.cpp
@@ -0,0 +1,93 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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 "../platforms.h"
+
+#ifdef __PLAT_RP2040__
+
+#include "../../inc/MarlinConfig.h"
+
+#if HAS_SERVOS
+
+#include "Servo.h"
+
+static uint_fast8_t servoCount = 0;
+static libServo *servos[NUM_SERVOS] = {0};
+constexpr millis_t servoDelay[] = SERVO_DELAY;
+static_assert(COUNT(servoDelay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
+
+libServo::libServo()
+: delay(servoDelay[servoCount]),
+ was_attached_before_pause(false),
+ value_before_pause(0)
+{
+ servos[servoCount++] = this;
+}
+
+int8_t libServo::attach(const int pin) {
+ if (servoCount >= MAX_SERVOS) return -1;
+ if (pin > 0) servo_pin = pin;
+ auto result = pico_servo.attach(servo_pin);
+ return result;
+}
+
+int8_t libServo::attach(const int pin, const int min, const int max) {
+ if (servoCount >= MAX_SERVOS) return -1;
+ if (pin > 0) servo_pin = pin;
+ auto result = pico_servo.attach(servo_pin, min, max);
+ return result;
+}
+
+void libServo::move(const int value) {
+ if (attach(0) >= 0) {
+ pico_servo.write(value);
+ safe_delay(delay);
+ TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
+ }
+}
+
+void libServo::pause() {
+ was_attached_before_pause = pico_servo.attached();
+ if (was_attached_before_pause) {
+ value_before_pause = pico_servo.read();
+ pico_servo.detach();
+ }
+}
+
+void libServo::resume() {
+ if (was_attached_before_pause) {
+ attach();
+ move(value_before_pause);
+ }
+}
+
+void libServo::pause_all_servos() {
+ for (auto& servo : servos)
+ if (servo) servo->pause();
+}
+
+void libServo::resume_all_servos() {
+ for (auto& servo : servos)
+ if (servo) servo->resume();
+}
+
+#endif // HAS_SERVOS
+#endif // __PLAT_RP2040__
diff --git a/Marlin/src/HAL/RP2040/Servo.h b/Marlin/src/HAL/RP2040/Servo.h
new file mode 100644
index 000000000000..031610fd1df1
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/Servo.h
@@ -0,0 +1,77 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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
+
+#if 1
+
+#include "../../core/millis_t.h"
+
+// Inherit and expand on the official library
+class libServo {
+ public:
+ libServo();
+ int8_t attach(const int pin = 0); // pin == 0 uses value from previous call
+ int8_t attach(const int pin, const int min, const int max);
+ void detach() { pico_servo.detach(); }
+ int read() { return pico_servo.read(); }
+ void move(const int value);
+
+ void pause();
+ void resume();
+
+ static void pause_all_servos();
+ static void resume_all_servos();
+ static void setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority);
+
+ private:
+ Servo pico_servo;
+
+ int servo_pin = 0;
+ millis_t delay = 0;
+
+ bool was_attached_before_pause;
+ int value_before_pause;
+};
+
+#else
+
+class libServo: public Servo {
+ public:
+ void move(const int value) {
+ constexpr uint16_t servo_delay[] = SERVO_DELAY;
+ static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
+
+ if (attach(servo_info[servoIndex].Pin.nbr) >= 0) { // try to reattach
+ write(value);
+ safe_delay(servo_delay[servoIndex]); // delay to allow servo to reach position
+ TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
+ }
+
+ }
+};
+
+class libServo;
+typedef libServo hal_servo_t;
+
+#endif
diff --git a/Marlin/src/HAL/RP2040/arduino_extras.cpp b/Marlin/src/HAL/RP2040/arduino_extras.cpp
new file mode 100644
index 000000000000..cdc0a0abf2ef
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/arduino_extras.cpp
@@ -0,0 +1,33 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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 .
+ *
+ */
+#ifdef __PLAT_RP2040__
+
+#include
+
+char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s) {
+ char format_string[20];
+ snprintf(format_string, 20, "%%%d.%df", __width, __prec);
+ sprintf(__s, format_string, __val);
+ return __s;
+}
+
+#endif // __PLAT_RP2040__
diff --git a/Marlin/src/HAL/RP2040/arduino_extras.h b/Marlin/src/HAL/RP2040/arduino_extras.h
new file mode 100644
index 000000000000..9794140212a6
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/arduino_extras.h
@@ -0,0 +1,29 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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
+// #include
+// #include
+// #include
+
+char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s);
diff --git a/Marlin/src/HAL/RP2040/eeprom_flash.cpp b/Marlin/src/HAL/RP2040/eeprom_flash.cpp
new file mode 100644
index 000000000000..5b1131ed436c
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/eeprom_flash.cpp
@@ -0,0 +1,88 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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 "../platforms.h"
+
+#ifdef __PLAT_RP2040__
+
+#include "../../inc/MarlinConfig.h"
+
+#if ENABLED(FLASH_EEPROM_EMULATION)
+
+#include "../shared/eeprom_api.h"
+
+// NOTE: The Bigtreetech SKR Pico has an onboard W25Q16 flash module
+
+// Use EEPROM.h for compatibility, for now.
+#include
+
+static bool eeprom_data_written = false;
+
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE size_t(E2END + 1)
+#endif
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+
+bool PersistentStore::access_start() {
+ EEPROM.begin(); // Avoid EEPROM.h warning (do nothing)
+ eeprom_buffer_fill();
+ return true;
+}
+
+bool PersistentStore::access_finish() {
+ if (eeprom_data_written) {
+ TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT());
+ hal.isr_off();
+ eeprom_buffer_flush();
+ hal.isr_on();
+ TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT());
+ eeprom_data_written = false;
+ }
+ return true;
+}
+
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ while (size--) {
+ uint8_t v = *value;
+ if (v != eeprom_buffered_read_byte(pos)) {
+ eeprom_buffered_write_byte(pos, v);
+ eeprom_data_written = true;
+ }
+ crc16(crc, &v, 1);
+ pos++;
+ value++;
+ }
+ return false;
+}
+
+bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
+ do {
+ const uint8_t c = eeprom_buffered_read_byte(pos);
+ if (writing) *value = c;
+ crc16(crc, &c, 1);
+ pos++;
+ value++;
+ } while (--size);
+ return false;
+}
+
+#endif // FLASH_EEPROM_EMULATION
+#endif // __PLAT_RP2040__
diff --git a/Marlin/src/HAL/RP2040/eeprom_wired.cpp b/Marlin/src/HAL/RP2040/eeprom_wired.cpp
new file mode 100644
index 000000000000..974f6f8dc137
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/eeprom_wired.cpp
@@ -0,0 +1,79 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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 "../platforms.h"
+
+#ifdef __PLAT_RP2040__
+
+#include "../../inc/MarlinConfig.h"
+
+#if USE_WIRED_EEPROM
+
+/**
+ * PersistentStore for Arduino-style EEPROM interface
+ * with simple implementations supplied by Marlin.
+ */
+
+#include "../shared/eeprom_if.h"
+#include "../shared/eeprom_api.h"
+
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE size_t(E2END + 1)
+#endif
+size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
+
+bool PersistentStore::access_start() { eeprom_init(); return true; }
+bool PersistentStore::access_finish() { return true; }
+
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
+ uint16_t written = 0;
+ while (size--) {
+ 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*/) {
+ do {
+ // Read from either external EEPROM, program flash or Backup SRAM
+ const uint8_t c = eeprom_read_byte((uint8_t*)pos);
+ if (writing) *value = c;
+ crc16(crc, &c, 1);
+ pos++;
+ value++;
+ } while (--size);
+ return false;
+}
+
+#endif // USE_WIRED_EEPROM
+#endif // __PLAT_RP2040__
diff --git a/Marlin/src/HAL/RP2040/endstop_interrupts.h b/Marlin/src/HAL/RP2040/endstop_interrupts.h
new file mode 100644
index 000000000000..af538406b8c7
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/endstop_interrupts.h
@@ -0,0 +1,60 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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 "../../module/endstops.h"
+
+// One ISR for all EXT-Interrupts
+void endstop_ISR() { endstops.update(); }
+
+void setup_endstop_interrupts() {
+ #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
+ TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN));
+ TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN));
+ TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN));
+ TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN));
+ TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN));
+ TERN_(HAS_Z_MIN_PIN, _ATTACH(Z_MIN_PIN));
+ TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN));
+ TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN));
+ TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN));
+ TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN));
+ TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN));
+ TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN));
+ TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN));
+ TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN));
+ TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN));
+ TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN));
+ TERN_(USE_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
+ TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN));
+ TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN));
+ TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN));
+ TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN));
+ TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN));
+ TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN));
+ TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN));
+ TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN));
+ TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN));
+ TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN));
+ TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN));
+ TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN));
+}
diff --git a/Marlin/src/HAL/RP2040/fast_pwm.cpp b/Marlin/src/HAL/RP2040/fast_pwm.cpp
new file mode 100644
index 000000000000..1349a1d59ef7
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/fast_pwm.cpp
@@ -0,0 +1,43 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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 "../platforms.h"
+
+#ifdef __PLAT_RP2040__
+
+#include "../../inc/MarlinConfigPre.h"
+
+#include "HAL.h"
+#include "pinDefinitions.h"
+
+void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
+ analogWrite(pin, v);
+}
+
+void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) {
+ mbed::PwmOut* pwm = digitalPinToPwm(pin);
+ if (pwm != NULL) delete pwm;
+ pwm = new mbed::PwmOut(digitalPinToPinName(pin));
+ digitalPinToPwm(pin) = pwm;
+ pwm->period_ms(1000 / f_desired);
+}
+
+#endif // __PLAT_RP2040__
diff --git a/Marlin/src/HAL/RP2040/fastio.cpp b/Marlin/src/HAL/RP2040/fastio.cpp
new file mode 100644
index 000000000000..fa77106cef9d
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/fastio.cpp
@@ -0,0 +1,32 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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 "../platforms.h"
+
+#ifdef __PLAT_RP2040__
+
+#include "../../inc/MarlinConfig.h"
+
+void FastIO_init() {
+
+}
+
+#endif // __PLAT_RP2040__
diff --git a/Marlin/src/HAL/RP2040/fastio.h b/Marlin/src/HAL/RP2040/fastio.h
new file mode 100644
index 000000000000..e84d2e77784f
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/fastio.h
@@ -0,0 +1,87 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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
+
+/**
+ * Fast I/O interfaces for RP2040
+ * These use GPIO register access for fast port manipulation.
+ */
+
+// ------------------------
+// Public Variables
+// ------------------------
+
+
+// ------------------------
+// Public functions
+// ------------------------
+
+void FastIO_init(); // Must be called before using fast io macros
+#define FASTIO_INIT() FastIO_init()
+
+// ------------------------
+// Defines
+// ------------------------
+
+#define _BV32(b) (1UL << (b))
+
+#ifndef PWM
+ #define PWM OUTPUT
+#endif
+
+#define _WRITE(IO, V) digitalWrite((IO), (V))
+
+#define _READ(IO) digitalRead(IO)
+#define _TOGGLE(IO) digitalWrite(IO, !digitalRead(IO))
+
+#define _GET_MODE(IO)
+#define _SET_MODE(IO,M) pinMode(IO, M)
+#define _SET_OUTPUT(IO) pinMode(IO, OUTPUT) //!< Output Push Pull Mode & GPIO_NOPULL
+#define _SET_OUTPUT_OD(IO) pinMode(IO, OUTPUT_OPEN_DRAIN)
+
+#define WRITE(IO,V) _WRITE(IO,V)
+#define READ(IO) _READ(IO)
+#define TOGGLE(IO) _TOGGLE(IO)
+
+#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
+#define OUT_WRITE_OD(IO,V) do{ _SET_OUTPUT_OD(IO); WRITE(IO,V); }while(0)
+
+#define SET_INPUT(IO) _SET_MODE(IO, INPUT) //!< Input Floating Mode
+#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) //!< Input with Pull-up activation
+#define SET_INPUT_PULLDOWN(IO) _SET_MODE(IO, INPUT_PULLDOWN) //!< Input with Pull-down activation
+#define SET_OUTPUT(IO) OUT_WRITE(IO, LOW)
+#define SET_PWM(IO) _SET_MODE(IO, PWM)
+
+#define IS_INPUT(IO)
+#define IS_OUTPUT(IO)
+
+#define PWM_PIN(P) true //digitalPinHasPWM(P)
+#define NO_COMPILE_TIME_PWM
+
+// digitalRead/Write wrappers
+#define extDigitalRead(IO) digitalRead(IO)
+#define extDigitalWrite(IO,V) digitalWrite(IO,V)
+
+#undef I2C_SDA
+#define I2C_SDA_PIN PIN_WIRE_SDA
+#undef I2C_SCL
+#define I2C_SCL_PIN PIN_WIRE_SCL
diff --git a/Marlin/src/HAL/RP2040/inc/Conditionals_LCD.h b/Marlin/src/HAL/RP2040/inc/Conditionals_LCD.h
new file mode 100644
index 000000000000..82f95a10357f
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/inc/Conditionals_LCD.h
@@ -0,0 +1,22 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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
diff --git a/Marlin/src/HAL/RP2040/inc/Conditionals_adv.h b/Marlin/src/HAL/RP2040/inc/Conditionals_adv.h
new file mode 100644
index 000000000000..442639e130b3
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/inc/Conditionals_adv.h
@@ -0,0 +1,35 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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
+
+#if ALL(SDSUPPORT, USBD_USE_CDC_MSC) && DISABLED(NO_SD_HOST_DRIVE)
+ #define HAS_SD_HOST_DRIVE 1
+#endif
+
+// Fix F_CPU not being a compile-time constant in RP2040 framework
+#ifdef BOARD_F_CPU
+ #undef F_CPU
+ #define F_CPU BOARD_F_CPU
+#endif
+
+// The Sensitive Pins array is not optimizable
+#define RUNTIME_ONLY_ANALOG_TO_DIGITAL
diff --git a/Marlin/src/HAL/RP2040/inc/Conditionals_post.h b/Marlin/src/HAL/RP2040/inc/Conditionals_post.h
new file mode 100644
index 000000000000..ef7853b98736
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/inc/Conditionals_post.h
@@ -0,0 +1,29 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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
+
+// If no real or emulated EEPROM selected, fall back to SD emulation
+#if USE_FALLBACK_EEPROM
+ #define SDCARD_EEPROM_EMULATION
+#elif ANY(I2C_EEPROM, SPI_EEPROM)
+ #define USE_SHARED_EEPROM 1
+#endif
diff --git a/Marlin/src/HAL/RP2040/inc/Conditionals_type.h b/Marlin/src/HAL/RP2040/inc/Conditionals_type.h
new file mode 100644
index 000000000000..82f95a10357f
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/inc/Conditionals_type.h
@@ -0,0 +1,22 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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
diff --git a/Marlin/src/HAL/RP2040/inc/SanityCheck.h b/Marlin/src/HAL/RP2040/inc/SanityCheck.h
new file mode 100644
index 000000000000..29175f8bbb7d
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/inc/SanityCheck.h
@@ -0,0 +1,60 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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
+
+/**
+ * Test RP2040-specific configuration values for errors at compile-time.
+ */
+//#if ENABLED(SPINDLE_LASER_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11)
+// #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector"
+//#endif
+
+#if ENABLED(SDCARD_EEPROM_EMULATION) && DISABLED(SDSUPPORT)
+ #undef SDCARD_EEPROM_EMULATION // Avoid additional error noise
+ #if USE_FALLBACK_EEPROM
+ #warning "EEPROM type not specified. Fallback is SDCARD_EEPROM_EMULATION."
+ #endif
+ #error "SDCARD_EEPROM_EMULATION requires SDSUPPORT. Enable SDSUPPORT or choose another EEPROM emulation."
+#endif
+
+#if ENABLED(SRAM_EEPROM_EMULATION)
+ #error "SRAM_EEPROM_EMULATION is not supported for RP2040."
+#endif
+
+#if ALL(PRINTCOUNTER, FLASH_EEPROM_EMULATION)
+ #warning "FLASH_EEPROM_EMULATION may cause long delays when writing and should not be used while printing."
+ #error "Disable PRINTCOUNTER or choose another EEPROM emulation."
+#endif
+
+#if ENABLED(FLASH_EEPROM_LEVELING)
+ #error "FLASH_EEPROM_LEVELING is not supported for RP2040."
+#endif
+
+#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
+ #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on RP2040."
+#elif ENABLED(SERIAL_STATS_DROPPED_RX)
+ #error "SERIAL_STATS_DROPPED_RX is not supported on RP2040."
+#endif
+
+#if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI)
+ #error "TFT_COLOR_UI, TFT_LVGL_UI and TFT_CLASSIC_UI are not supported for RP2040."
+#endif
diff --git a/Marlin/src/HAL/RP2040/msc_sd.cpp b/Marlin/src/HAL/RP2040/msc_sd.cpp
new file mode 100644
index 000000000000..bc945c199920
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/msc_sd.cpp
@@ -0,0 +1,136 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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 "../platforms.h"
+
+#ifdef __PLAT_RP2040__
+
+#include "../../inc/MarlinConfigPre.h"
+
+#if HAS_SD_HOST_DRIVE
+
+#include "../shared/Marduino.h"
+#include "msc_sd.h"
+#include "usbd_core.h"
+
+#include "../../sd/cardreader.h"
+
+#include
+#include
+
+#define BLOCK_SIZE 512
+#define PRODUCT_ID 0x29
+
+class Sd2CardUSBMscHandler : public USBMscHandler {
+public:
+ DiskIODriver* diskIODriver() {
+ #if ENABLED(MULTI_VOLUME)
+ #if SHARED_VOLUME_IS(SD_ONBOARD)
+ return &card.media_driver_sdcard;
+ #elif SHARED_VOLUME_IS(USB_FLASH_DRIVE)
+ return &card.media_driver_usbFlash;
+ #endif
+ #else
+ return card.diskIODriver();
+ #endif
+ }
+
+ bool GetCapacity(uint32_t *pBlockNum, uint16_t *pBlockSize) {
+ *pBlockNum = diskIODriver()->cardSize();
+ *pBlockSize = BLOCK_SIZE;
+ return true;
+ }
+
+ bool Write(uint8_t *pBuf, uint32_t blkAddr, uint16_t blkLen) {
+ auto sd2card = diskIODriver();
+ // single block
+ if (blkLen == 1) {
+ watchdog_refresh();
+ sd2card->writeBlock(blkAddr, pBuf);
+ return true;
+ }
+
+ // multi block optimization
+ sd2card->writeStart(blkAddr, blkLen);
+ while (blkLen--) {
+ watchdog_refresh();
+ sd2card->writeData(pBuf);
+ pBuf += BLOCK_SIZE;
+ }
+ sd2card->writeStop();
+ return true;
+ }
+
+ bool Read(uint8_t *pBuf, uint32_t blkAddr, uint16_t blkLen) {
+ auto sd2card = diskIODriver();
+ // single block
+ if (blkLen == 1) {
+ watchdog_refresh();
+ sd2card->readBlock(blkAddr, pBuf);
+ return true;
+ }
+
+ // multi block optimization
+ sd2card->readStart(blkAddr);
+ while (blkLen--) {
+ watchdog_refresh();
+ sd2card->readData(pBuf);
+ pBuf += BLOCK_SIZE;
+ }
+ sd2card->readStop();
+ return true;
+ }
+
+ bool IsReady() {
+ return diskIODriver()->isReady();
+ }
+};
+
+Sd2CardUSBMscHandler usbMscHandler;
+
+/* USB Mass storage Standard Inquiry Data */
+uint8_t Marlin_STORAGE_Inquirydata[] = { /* 36 */
+ /* LUN 0 */
+ 0x00,
+ 0x80,
+ 0x02,
+ 0x02,
+ (STANDARD_INQUIRY_DATA_LEN - 5),
+ 0x00,
+ 0x00,
+ 0x00,
+ 'M', 'A', 'R', 'L', 'I', 'N', ' ', ' ', /* Manufacturer : 8 bytes */
+ 'P', 'r', 'o', 'd', 'u', 'c', 't', ' ', /* Product : 16 Bytes */
+ ' ', ' ', ' ', ' ', ' ', ' ', ' ', ' ',
+ '0', '.', '0', '1', /* Version : 4 Bytes */
+};
+
+USBMscHandler *pSingleMscHandler = &usbMscHandler;
+
+void MSC_SD_init() {
+ USBDevice.end();
+ delay(200);
+ USBDevice.registerMscHandlers(1, &pSingleMscHandler, Marlin_STORAGE_Inquirydata);
+ USBDevice.begin();
+}
+
+#endif // HAS_SD_HOST_DRIVE
+#endif // __PLAT_RP2040__
diff --git a/Marlin/src/HAL/RP2040/msc_sd.h b/Marlin/src/HAL/RP2040/msc_sd.h
new file mode 100644
index 000000000000..1c13f5578dad
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/msc_sd.h
@@ -0,0 +1,24 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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
+
+void MSC_SD_init();
diff --git a/Marlin/src/HAL/RP2040/pinsDebug.h b/Marlin/src/HAL/RP2040/pinsDebug.h
new file mode 100644
index 000000000000..50d7391f9279
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/pinsDebug.h
@@ -0,0 +1,146 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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
+#include "HAL.h"
+
+#ifndef NUM_DIGITAL_PINS
+ #error "Expected NUM_DIGITAL_PINS not found"
+#endif
+
+/**
+ * Life gets complicated if you want an easy to use 'M43 I' output (in port/pin order)
+ * because the variants in this platform do not always define all the I/O port/pins
+ * that a CPU has.
+ *
+ * VARIABLES:
+ * Ard_num - Arduino pin number - defined by the platform. It is used by digitalRead and
+ * digitalWrite commands and by M42.
+ * - does not contain port/pin info
+ * - is not in port/pin order
+ * - typically a variant will only assign Ard_num to port/pins that are actually used
+ * Index - M43 counter - only used to get Ard_num
+ * x - a parameter/argument used to search the pin_array to try to find a signal name
+ * associated with a Ard_num
+ * Port_pin - port number and pin number for use with CPU registers and printing reports
+ *
+ * Since M43 uses digitalRead and digitalWrite commands, only the Port_pins with an Ard_num
+ * are accessed and/or displayed.
+ *
+ * Three arrays are used.
+ *
+ * digitalPin[] is provided by the platform. It consists of the Port_pin numbers in
+ * Arduino pin number order.
+ *
+ * pin_array is a structure generated by the pins/pinsDebug.h header file. It is generated by
+ * the preprocessor. Only the signals associated with enabled options are in this table.
+ * It contains:
+ * - name of the signal
+ * - the Ard_num assigned by the pins_YOUR_BOARD.h file using the platform defines.
+ * EXAMPLE: "#define KILL_PIN PB1" results in Ard_num of 57. 57 is then used as the
+ * argument to digitalPinToPinName(IO) to get the Port_pin number
+ * - if it is a digital or analog signal. PWMs are considered digital here.
+ *
+ * pin_xref is a structure generated by this header file. It is generated by the
+ * preprocessor. It is in port/pin order. It contains just the port/pin numbers defined by the
+ * platform for this variant.
+ * - Ard_num
+ * - printable version of Port_pin
+ *
+ * Routines with an "x" as a parameter/argument are used to search the pin_array to try to
+ * find a signal name associated with a port/pin.
+ *
+ * NOTE - the Arduino pin number is what is used by the M42 command, NOT the port/pin for that
+ * signal. The Arduino pin number is listed by the M43 I command.
+ */
+
+#define NUM_ANALOG_FIRST A0
+
+#define MODE_PIN_INPUT 0 // Input mode (reset state)
+#define MODE_PIN_OUTPUT 1 // General purpose output mode
+#define MODE_PIN_ALT 2 // Alternate function mode
+#define MODE_PIN_ANALOG 3 // Analog mode
+
+#define PIN_NUM(P) (P & 0x000F)
+#define PIN_NUM_ALPHA_LEFT(P) (((P & 0x000F) < 10) ? ('0' + (P & 0x000F)) : '1')
+#define PIN_NUM_ALPHA_RIGHT(P) (((P & 0x000F) > 9) ? ('0' + (P & 0x000F) - 10) : 0 )
+#define PORT_NUM(P) ((P >> 4) & 0x0007)
+#define PORT_ALPHA(P) ('A' + (P >> 4))
+
+/**
+ * Translation of routines & variables used by pinsDebug.h
+ */
+#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
+#define VALID_PIN(ANUM) (pin_t(ANUM) >= 0 && pin_t(ANUM) < NUMBER_PINS_TOTAL)
+#define digitalRead_mod(Ard_num) extDigitalRead(Ard_num) // must use Arduino pin numbers when doing reads
+#define PRINT_PIN(Q)
+#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
+#define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine
+
+// x is a variable used to search pin_array
+#define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital)
+#define GET_ARRAY_PIN(x) ((pin_t) pin_array[x].pin)
+#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
+#define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin
+
+uint8_t get_pin_mode(const pin_t Ard_num) {
+
+ uint dir = gpio_get_dir( Ard_num);
+
+ if(dir) return MODE_PIN_OUTPUT;
+ else return MODE_PIN_INPUT;
+
+}
+
+bool GET_PINMODE(const pin_t Ard_num) {
+ const uint8_t pin_mode = get_pin_mode(Ard_num);
+ return pin_mode == MODE_PIN_OUTPUT || pin_mode == MODE_PIN_ALT; // assume all alt definitions are PWM
+}
+
+int8_t digital_pin_to_analog_pin(pin_t Ard_num) {
+ Ard_num -= NUM_ANALOG_FIRST;
+ return (Ard_num >= 0 && Ard_num < NUM_ANALOG_INPUTS) ? Ard_num : -1;
+}
+
+bool IS_ANALOG(const pin_t Ard_num) {
+ return digital_pin_to_analog_pin(Ard_num) != -1;
+}
+
+bool is_digital(const pin_t x) {
+ const uint8_t pin_mode = get_pin_mode(x);
+ return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT;
+}
+
+void print_port(const pin_t Ard_num) {
+ SERIAL_ECHOPGM("Pin: ");
+ SERIAL_ECHO(Ard_num);
+}
+
+bool pwm_status(const pin_t Ard_num) {
+ return get_pin_mode(Ard_num) == MODE_PIN_ALT;
+}
+
+void pwm_details(const pin_t Ard_num) {
+ if (PWM_PIN(Ard_num)) {
+ }
+}
diff --git a/Marlin/src/HAL/RP2040/spi_pins.h b/Marlin/src/HAL/RP2040/spi_pins.h
new file mode 100644
index 000000000000..e6ee840b5544
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/spi_pins.h
@@ -0,0 +1,38 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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 SPI Pins: SCK, MISO, MOSI, SS
+ */
+#ifndef SD_SCK_PIN
+ #define SD_SCK_PIN PIN_SPI_SCK
+#endif
+#ifndef SD_MISO_PIN
+ #define SD_MISO_PIN PIN_SPI_MISO
+#endif
+#ifndef SD_MOSI_PIN
+ #define SD_MOSI_PIN PIN_SPI_MOSI
+#endif
+#ifndef SD_SS_PIN
+ #define SD_SS_PIN PIN_SPI_SS
+#endif
diff --git a/Marlin/src/HAL/RP2040/timers.cpp b/Marlin/src/HAL/RP2040/timers.cpp
new file mode 100644
index 000000000000..88d5af29839f
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/timers.cpp
@@ -0,0 +1,126 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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 "../platforms.h"
+
+#ifdef __PLAT_RP2040__
+
+#include "../../inc/MarlinConfig.h"
+
+alarm_pool_t* HAL_timer_pool_0;
+alarm_pool_t* HAL_timer_pool_1;
+alarm_pool_t* HAL_timer_pool_2;
+alarm_pool_t* HAL_timer_pool_3;
+
+struct repeating_timer HAL_timer_0;
+struct repeating_timer HAL_timer_1;
+struct repeating_timer HAL_timer_2;
+struct repeating_timer HAL_timer_3;
+
+volatile bool HAL_timer_irq_en[4] = { false, false, false, false };
+
+void HAL_timer_init() {
+ //reserve all the available alarm pools to use as "pseudo" hardware timers
+ //HAL_timer_pool_0 = alarm_pool_create(0,2);
+ HAL_timer_pool_1 = alarm_pool_create(1, 6);
+ HAL_timer_pool_0 = HAL_timer_pool_1;
+ HAL_timer_pool_2 = alarm_pool_create(2, 6);
+ HAL_timer_pool_3 = HAL_timer_pool_2;
+ //HAL_timer_pool_3 = alarm_pool_create(3, 6);
+
+ irq_set_priority(TIMER_IRQ_0, 0xC0);
+ irq_set_priority(TIMER_IRQ_1, 0x80);
+ irq_set_priority(TIMER_IRQ_2, 0x40);
+ irq_set_priority(TIMER_IRQ_3, 0x00);
+
+ //alarm_pool_init_default();
+}
+
+void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
+ const int64_t freq = (int64_t)frequency,
+ us = (1000000ll / freq) * -1ll;
+ bool result;
+ switch (timer_num) {
+ case 0:
+ result = alarm_pool_add_repeating_timer_us(HAL_timer_pool_0, us, HAL_timer_repeating_0_callback, NULL, &HAL_timer_0);
+ break;
+ case 1:
+ result = alarm_pool_add_repeating_timer_us(HAL_timer_pool_1, us, HAL_timer_repeating_1_callback, NULL, &HAL_timer_1);
+ break;
+ case 2:
+ result = alarm_pool_add_repeating_timer_us(HAL_timer_pool_2, us, HAL_timer_repeating_2_callback, NULL, &HAL_timer_2);
+ break;
+ case 3:
+ result = alarm_pool_add_repeating_timer_us(HAL_timer_pool_3, us, HAL_timer_repeating_3_callback, NULL, &HAL_timer_3);
+ break;
+ }
+ UNUSED(result);
+}
+
+void HAL_timer_stop(const uint8_t timer_num) {
+ switch (timer_num) {
+ case 0: cancel_repeating_timer(&HAL_timer_0); break;
+ case 1: cancel_repeating_timer(&HAL_timer_1); break;
+ case 2: cancel_repeating_timer(&HAL_timer_2); break;
+ case 3: cancel_repeating_timer(&HAL_timer_3); break;
+ }
+}
+
+int64_t HAL_timer_alarm_pool_0_callback(long int, void*) {
+ if (HAL_timer_irq_en[0]) HAL_timer_0_callback();
+ return 0;
+}
+int64_t HAL_timer_alarm_pool_1_callback(long int, void*) {
+ if (HAL_timer_irq_en[1]) HAL_timer_1_callback();
+ return 0;
+}
+int64_t HAL_timer_alarm_pool_2_callback(long int, void*) {
+ if (HAL_timer_irq_en[2]) HAL_timer_2_callback();
+ return 0;
+}
+int64_t HAL_timer_alarm_pool_3_callback(long int, void*) {
+ if (HAL_timer_irq_en[3]) HAL_timer_3_callback();
+ return 0;
+}
+
+bool HAL_timer_repeating_0_callback(repeating_timer* timer) {
+ if (HAL_timer_irq_en[0]) HAL_timer_0_callback();
+ return true;
+}
+bool HAL_timer_repeating_1_callback(repeating_timer* timer) {
+ if (HAL_timer_irq_en[1]) HAL_timer_1_callback();
+ return true;
+}
+bool HAL_timer_repeating_2_callback(repeating_timer* timer) {
+ if (HAL_timer_irq_en[2]) HAL_timer_2_callback();
+ return true;
+}
+bool HAL_timer_repeating_3_callback(repeating_timer* timer) {
+ if (HAL_timer_irq_en[3]) HAL_timer_3_callback();
+ return true;
+}
+
+void __attribute__((weak)) HAL_timer_0_callback() {}
+void __attribute__((weak)) HAL_timer_1_callback() {}
+void __attribute__((weak)) HAL_timer_2_callback() {}
+void __attribute__((weak)) HAL_timer_3_callback() {}
+
+#endif // __PLAT_RP2040__
diff --git a/Marlin/src/HAL/RP2040/timers.h b/Marlin/src/HAL/RP2040/timers.h
new file mode 100644
index 000000000000..83fdc0a2fcf4
--- /dev/null
+++ b/Marlin/src/HAL/RP2040/timers.h
@@ -0,0 +1,177 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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
+
+#include "../../core/macros.h"
+
+#ifdef PICO_TIME_DEFAULT_ALARM_POOL_DISABLED
+ #undef PICO_TIME_DEFAULT_ALARM_POOL_DISABLED
+ #define PICO_TIME_DEFAULT_ALARM_POOL_DISABLED 0
+#else
+ #define PICO_TIME_DEFAULT_ALARM_POOL_DISABLED 0
+#endif
+
+// ------------------------
+// Defines
+// ------------------------
+
+//#define _HAL_TIMER(T) _CAT(LPC_TIM, T)
+//#define _HAL_TIMER_IRQ(T) TIMER##T##_IRQn
+//#define __HAL_TIMER_ISR(T) extern "C" alarm_callback_t HAL_timer_alarm_pool_##T##_callback()
+#define __HAL_TIMER_ISR(T) extern void HAL_timer_##T##_callback()
+#define _HAL_TIMER_ISR(T) __HAL_TIMER_ISR(T)
+
+typedef uint64_t hal_timer_t;
+#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFFFFFFFFF
+
+#define HAL_TIMER_RATE (1000000ull) // fixed value as we use a microsecond timesource
+#ifndef MF_TIMER_STEP
+ #define MF_TIMER_STEP 0 // 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 1 // Timer Index for Temperature
+#endif
+#ifndef MF_TIMER_PWM
+ #define MF_TIMER_PWM 3 // Timer Index for PWM
+#endif
+
+#define TEMP_TIMER_RATE HAL_TIMER_RATE
+#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
+
+#define STEPPER_TIMER_RATE HAL_TIMER_RATE / 10 // 100khz roughly
+#define STEPPER_TIMER_TICKS_PER_US (0.1) // fixed value as we use a microsecond timesource
+#define STEPPER_TIMER_PRESCALE (10)
+
+#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
+#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
+#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
+
+#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(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)
+
+#ifndef HAL_STEP_TIMER_ISR
+ #define HAL_STEP_TIMER_ISR() _HAL_TIMER_ISR(MF_TIMER_STEP)
+#endif
+#ifndef HAL_TEMP_TIMER_ISR
+ #define HAL_TEMP_TIMER_ISR() _HAL_TIMER_ISR(MF_TIMER_TEMP)
+#endif
+
+// Timer references by index
+//#define STEP_TIMER_PTR _HAL_TIMER(MF_TIMER_STEP)
+//#define TEMP_TIMER_PTR _HAL_TIMER(MF_TIMER_TEMP)
+
+extern alarm_pool_t* HAL_timer_pool_0;
+extern alarm_pool_t* HAL_timer_pool_1;
+extern alarm_pool_t* HAL_timer_pool_2;
+extern alarm_pool_t* HAL_timer_pool_3;
+
+extern struct repeating_timer HAL_timer_0;
+
+void HAL_timer_0_callback();
+void HAL_timer_1_callback();
+void HAL_timer_2_callback();
+void HAL_timer_3_callback();
+
+int64_t HAL_timer_alarm_pool_0_callback(long int, void*);
+int64_t HAL_timer_alarm_pool_1_callback(long int, void*);
+int64_t HAL_timer_alarm_pool_2_callback(long int, void*);
+int64_t HAL_timer_alarm_pool_3_callback(long int, void*);
+
+bool HAL_timer_repeating_0_callback(repeating_timer* timer);
+bool HAL_timer_repeating_1_callback(repeating_timer* timer);
+bool HAL_timer_repeating_2_callback(repeating_timer* timer);
+bool HAL_timer_repeating_3_callback(repeating_timer* timer);
+
+extern volatile bool HAL_timer_irq_en[4];
+
+// ------------------------
+// Public functions
+// ------------------------
+
+void HAL_timer_init();
+void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
+void HAL_timer_stop(const uint8_t timer_num);
+
+FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, hal_timer_t compare) {
+
+ if (timer_num == MF_TIMER_STEP){
+ if (compare == HAL_TIMER_TYPE_MAX){
+ HAL_timer_stop(timer_num);
+ return;
+ }
+ }
+
+ compare = compare *10; //Dirty fix, figure out a proper way
+
+ switch (timer_num) {
+ case 0:
+ alarm_pool_add_alarm_in_us(HAL_timer_pool_0 ,compare , HAL_timer_alarm_pool_0_callback ,0 ,false );
+ break;
+
+ case 1:
+ alarm_pool_add_alarm_in_us(HAL_timer_pool_1 ,compare , HAL_timer_alarm_pool_1_callback ,0 ,false );
+ break;
+
+ case 2:
+ alarm_pool_add_alarm_in_us(HAL_timer_pool_2 ,compare , HAL_timer_alarm_pool_2_callback ,0 ,false );
+ break;
+
+ case 3:
+ alarm_pool_add_alarm_in_us(HAL_timer_pool_3 ,compare , HAL_timer_alarm_pool_3_callback ,0 ,false );
+ break;
+ }
+}
+
+FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
+ return 0;
+}
+
+FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
+ if (timer_num == MF_TIMER_STEP) return 0ull;
+ return time_us_64();
+}
+
+
+FORCE_INLINE static void HAL_timer_enable_interrupt(const uint8_t timer_num) {
+ HAL_timer_irq_en[timer_num] = 1;
+}
+
+FORCE_INLINE static void HAL_timer_disable_interrupt(const uint8_t timer_num) {
+ HAL_timer_irq_en[timer_num] = 0;
+}
+
+FORCE_INLINE static bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
+ return HAL_timer_irq_en[timer_num]; //lucky coincidence that timer_num and rp2040 irq num matches
+}
+
+FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
+ return;
+}
+
+#define HAL_timer_isr_epilogue(T) NOOP
diff --git a/Marlin/src/HAL/SAMD21/HAL_SPI.cpp b/Marlin/src/HAL/SAMD21/HAL_SPI.cpp
index e01f540cf8a1..d41f868cdb0a 100644
--- a/Marlin/src/HAL/SAMD21/HAL_SPI.cpp
+++ b/Marlin/src/HAL/SAMD21/HAL_SPI.cpp
@@ -108,7 +108,6 @@
SPI.beginTransaction(spiConfig);
SPI.transfer(buf, nbyte);
SPI.endTransaction();
-
}
/**
diff --git a/Marlin/src/HAL/SAMD21/pinsDebug.h b/Marlin/src/HAL/SAMD21/pinsDebug.h
index cc20f289f6d7..387516aa7930 100644
--- a/Marlin/src/HAL/SAMD21/pinsDebug.h
+++ b/Marlin/src/HAL/SAMD21/pinsDebug.h
@@ -22,41 +22,57 @@
#pragma once
/**
- * SAMD21 HAL developed by Bart Meijer (brupje)
- * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
+ * Pins Debugging for SAMD21
+ *
+ * - NUMBER_PINS_TOTAL
+ * - MULTI_NAME_PAD
+ * - getPinByIndex(index)
+ * - printPinNameByIndex(index)
+ * - getPinIsDigitalByIndex(index)
+ * - digitalPinToAnalogIndex(pin)
+ * - getValidPinMode(pin)
+ * - isValidPin(pin)
+ * - isAnalogPin(pin)
+ * - digitalRead_mod(pin)
+ * - pwm_status(pin)
+ * - printPinPWM(pin)
+ * - printPinPort(pin)
+ * - printPinNumber(pin)
+ * - printPinAnalog(pin)
*/
#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 digitalRead_mod(P) extDigitalRead(P)
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
-#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
-#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
-#define getPinByIndex(p) pin_array[p].pin
-#define getPinIsDigitalByIndex(p) pin_array[p].is_digital
-#define isValidPin(pin) (pin >= 0 && pin < (int8_t)NUMBER_PINS_TOTAL)
-#define isAnalogPin(P) (digitalPinToAnalogIndex(P)!=-1)
-#define pwm_status(pin) digitalPinHasPWM(pin)
+#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3d "), P); SERIAL_ECHO(buffer); }while(0)
+#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
+#define getPinByIndex(x) pin_array[x].pin
+#define getPinIsDigitalByIndex(x) pin_array[x].is_digital
+#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL))
+#define isAnalogPin(P) (digitalPinToAnalogIndex(P) != -1)
+#define pwm_status(P) digitalPinHasPWM(P)
#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 getValidPinMode(int8_t pin) { // 1: output, 0: input
+bool getValidPinMode(const 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 printPinPWM(int32_t pin) {
+void printPinPWM(const int32_t pin) {
if (pwm_status(pin)) {
//uint32_t chan = g_APinDescription[pin].ulPWMChannel TODO when fast pwm is operative;
//SERIAL_ECHOPGM("PWM = ", duty);
}
}
+void printPinPort(const pin_t) {}
+
/**
* SAMD21 Board pin| PORT | Label
* ----------------+--------+-------
diff --git a/Marlin/src/HAL/SAMD51/pinsDebug.h b/Marlin/src/HAL/SAMD51/pinsDebug.h
index 00f246f21a5d..1518c615c934 100644
--- a/Marlin/src/HAL/SAMD51/pinsDebug.h
+++ b/Marlin/src/HAL/SAMD51/pinsDebug.h
@@ -22,40 +22,57 @@
#pragma once
/**
- * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
+ * Pins Debugging for SAMD51
+ *
+ * - NUMBER_PINS_TOTAL
+ * - MULTI_NAME_PAD
+ * - getPinByIndex(index)
+ * - printPinNameByIndex(index)
+ * - getPinIsDigitalByIndex(index)
+ * - digitalPinToAnalogIndex(pin)
+ * - getValidPinMode(pin)
+ * - isValidPin(pin)
+ * - isAnalogPin(pin)
+ * - digitalRead_mod(pin)
+ * - pwm_status(pin)
+ * - printPinPWM(pin)
+ * - printPinPort(pin)
+ * - printPinNumber(pin)
+ * - printPinAnalog(pin)
*/
#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 digitalRead_mod(P) extDigitalRead(P)
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
-#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
-#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
-#define getPinByIndex(p) pin_array[p].pin
-#define getPinIsDigitalByIndex(p) pin_array[p].is_digital
-#define isValidPin(pin) (pin >= 0 && pin < int8_t(NUMBER_PINS_TOTAL))
-#define isAnalogPin(P) (digitalPinToAnalogIndex(P)!=-1)
-#define pwm_status(pin) digitalPinHasPWM(pin)
+#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3d "), P); SERIAL_ECHO(buffer); }while(0)
+#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
+#define getPinByIndex(x) pin_array[x].pin
+#define getPinIsDigitalByIndex(x) pin_array[x].is_digital
+#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL))
+#define isAnalogPin(P) (digitalPinToAnalogIndex(P) != -1)
+#define pwm_status(P) digitalPinHasPWM(P)
#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 getValidPinMode(int8_t pin) { // 1: output, 0: input
+bool getValidPinMode(const 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 printPinPWM(int32_t pin) {
+void printPinPWM(const int32_t pin) {
if (pwm_status(pin)) {
//uint32_t chan = g_APinDescription[pin].ulPWMChannel TODO when fast pwm is operative;
//SERIAL_ECHOPGM("PWM = ", duty);
}
}
+void printPinPort(const pin_t) {}
+
/**
* AGCM4 Board pin | PORT | Label
* ----------------+--------+-------
diff --git a/Marlin/src/HAL/STM32/pinsDebug.h b/Marlin/src/HAL/STM32/pinsDebug.h
index cce705410c72..21cd2de39fef 100644
--- a/Marlin/src/HAL/STM32/pinsDebug.h
+++ b/Marlin/src/HAL/STM32/pinsDebug.h
@@ -21,6 +21,26 @@
*/
#pragma once
+/**
+ * Pins Debugging for STM32
+ *
+ * - NUMBER_PINS_TOTAL
+ * - MULTI_NAME_PAD
+ * - getPinByIndex(index)
+ * - printPinNameByIndex(index)
+ * - getPinIsDigitalByIndex(index)
+ * - digitalPinToAnalogIndex(pin)
+ * - getValidPinMode(pin)
+ * - isValidPin(pin)
+ * - isAnalogPin(pin)
+ * - digitalRead_mod(pin)
+ * - pwm_status(pin)
+ * - printPinPWM(pin)
+ * - printPinPort(pin)
+ * - printPinNumber(pin)
+ * - printPinAnalog(pin)
+ */
+
#include
#ifndef NUM_DIGITAL_PINS
@@ -34,11 +54,11 @@
* that a CPU has.
*
* VARIABLES:
- * Ard_num - Arduino pin number - defined by the platform. It is used by digitalRead and
- * digitalWrite commands and by M42.
- * - does not contain port/pin info
- * - is not in port/pin order
- * - typically a variant will only assign Ard_num to port/pins that are actually used
+ * A - Arduino pin number - defined by the platform. It is used by digitalRead and
+ * digitalWrite commands and by M42.
+ * - does not contain port/pin info
+ * - is not in port/pin order
+ * - typically a variant will only assign Ard_num to port/pins that are actually used
* Index - M43 counter - only used to get Ard_num
* x - a parameter/argument used to search the pin_array to try to find a signal name
* associated with a Ard_num
@@ -98,15 +118,11 @@ const XrefInfo pin_xref[] PROGMEM = {
#define MODE_PIN_ALT 2 // Alternate function mode
#define MODE_PIN_ANALOG 3 // Analog mode
-#define PIN_NUM(P) (P & 0x000F)
-#define PIN_NUM_ALPHA_LEFT(P) (((P & 0x000F) < 10) ? ('0' + (P & 0x000F)) : '1')
-#define PIN_NUM_ALPHA_RIGHT(P) (((P & 0x000F) > 9) ? ('0' + (P & 0x000F) - 10) : 0 )
-#define PORT_NUM(P) ((P >> 4) & 0x0007)
-#define PORT_ALPHA(P) ('A' + (P >> 4))
-
-/**
- * Translation of routines & variables used by pinsDebug.h
- */
+#define PIN_NUM(P) ((P) & 0x000F)
+#define PIN_NUM_ALPHA_LEFT(P) ((((P) & 0x000F) < 10) ? ('0' + ((P) & 0x000F)) : '1')
+#define PIN_NUM_ALPHA_RIGHT(P) ((((P) & 0x000F) > 9) ? ('0' + ((P) & 0x000F) - 10) : 0 )
+#define PORT_NUM(P) (((P) >> 4) & 0x0007)
+#define PORT_ALPHA(P) ('A' + ((P) >> 4))
#if NUM_ANALOG_FIRST >= NUM_DIGITAL_PINS
#define HAS_HIGH_ANALOG_PINS 1
@@ -116,10 +132,10 @@ const XrefInfo pin_xref[] PROGMEM = {
#endif
#define NUMBER_PINS_TOTAL ((NUM_DIGITAL_PINS) + TERN0(HAS_HIGH_ANALOG_PINS, NUM_ANALOG_INPUTS))
#define isValidPin(P) (WITHIN(P, 0, (NUM_DIGITAL_PINS) - 1) || TERN0(HAS_HIGH_ANALOG_PINS, WITHIN(P, NUM_ANALOG_FIRST, NUM_ANALOG_LAST)))
-#define digitalRead_mod(Ard_num) extDigitalRead(Ard_num) // must use Arduino pin numbers when doing reads
+#define digitalRead_mod(A) extDigitalRead(A) // must use Arduino pin numbers when doing reads
#define printPinNumber(Q)
-#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
-#define digitalPinToAnalogIndex(ANUM) -1 // will report analog pin number in the print port routine
+#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
+#define digitalPinToAnalogIndex(P) -1 // will report analog pin number in the print port routine
// x is a variable used to search pin_array
#define getPinIsDigitalByIndex(x) ((bool) pin_array[x].is_digital)
@@ -130,27 +146,27 @@ const XrefInfo pin_xref[] PROGMEM = {
//
// Pin Mapping for M43
//
-#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num
+#define GET_PIN_MAP_PIN_M43(x) pin_xref[x].Ard_num
#ifndef M43_NEVER_TOUCH
- #define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP)
+ #define _M43_NEVER_TOUCH(x) WITHIN(x, 9, 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP)
#ifdef KILL_PIN
- #define M43_NEVER_TOUCH(Index) m43_never_touch(Index)
+ #define M43_NEVER_TOUCH(x) m43_never_touch(x)
- bool m43_never_touch(const pin_t Index) {
+ bool m43_never_touch(const pin_t index) {
static pin_t M43_kill_index = -1;
if (M43_kill_index < 0)
for (M43_kill_index = 0; M43_kill_index < NUMBER_PINS_TOTAL; M43_kill_index++)
if (KILL_PIN == GET_PIN_MAP_PIN_M43(M43_kill_index)) break;
- return _M43_NEVER_TOUCH(Index) || Index == M43_kill_index; // KILL_PIN and SERIAL/USB
+ return _M43_NEVER_TOUCH(index) || index == M43_kill_index; // KILL_PIN and SERIAL/USB
}
#else
- #define M43_NEVER_TOUCH(Index) _M43_NEVER_TOUCH(Index)
+ #define M43_NEVER_TOUCH(index) _M43_NEVER_TOUCH(index)
#endif
#endif
-uint8_t get_pin_mode(const pin_t Ard_num) {
- const PinName dp = digitalPinToPinName(Ard_num);
+uint8_t get_pin_mode(const pin_t pin) {
+ const PinName dp = digitalPinToPinName(pin);
uint32_t ll_pin = STM_LL_GPIO_PIN(dp);
GPIO_TypeDef *port = get_GPIO_Port(STM_PORT(dp));
uint32_t mode = LL_GPIO_GetPinMode(port, ll_pin);
@@ -164,41 +180,41 @@ uint8_t get_pin_mode(const pin_t Ard_num) {
}
}
-bool getValidPinMode(const pin_t Ard_num) {
- const uint8_t pin_mode = get_pin_mode(Ard_num);
+bool getValidPinMode(const pin_t pin) {
+ const uint8_t pin_mode = get_pin_mode(pin);
return pin_mode == MODE_PIN_OUTPUT || pin_mode == MODE_PIN_ALT; // assume all alt definitions are PWM
}
-int8_t digital_pin_to_analog_pin(const pin_t Ard_num) {
- if (WITHIN(Ard_num, NUM_ANALOG_FIRST, NUM_ANALOG_LAST))
- return Ard_num - NUM_ANALOG_FIRST;
+int8_t digital_pin_to_analog_pin(const pin_t pin) {
+ if (WITHIN(pin, NUM_ANALOG_FIRST, NUM_ANALOG_LAST))
+ return pin - NUM_ANALOG_FIRST;
- const int8_t ind = digitalPinToAnalogIndex(Ard_num);
+ const int8_t ind = digitalPinToAnalogIndex(pin);
return (ind < NUM_ANALOG_INPUTS) ? ind : -1;
}
-bool isAnalogPin(const pin_t Ard_num) {
- return get_pin_mode(Ard_num) == MODE_PIN_ANALOG;
+bool isAnalogPin(const pin_t pin) {
+ return get_pin_mode(pin) == MODE_PIN_ANALOG;
}
-bool is_digital(const pin_t Ard_num) {
- const uint8_t pin_mode = get_pin_mode(pin_array[Ard_num].pin);
+bool is_digital(const pin_t pin) {
+ const uint8_t pin_mode = get_pin_mode(pin_array[pin].pin);
return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT;
}
-void printPinPort(const pin_t Ard_num) {
+void printPinPort(const pin_t pin) {
char buffer[16];
- pin_t Index;
- for (Index = 0; Index < NUMBER_PINS_TOTAL; Index++)
- if (Ard_num == GET_PIN_MAP_PIN_M43(Index)) break;
+ pin_t index;
+ for (index = 0; index < NUMBER_PINS_TOTAL; index++)
+ if (pin == GET_PIN_MAP_PIN_M43(index)) break;
- const char * ppa = pin_xref[Index].Port_pin_alpha;
+ const char * ppa = pin_xref[index].Port_pin_alpha;
sprintf_P(buffer, PSTR("%s"), ppa);
SERIAL_ECHO(buffer);
if (ppa[3] == '\0') SERIAL_CHAR(' ');
// print analog pin number
- const int8_t Port_pin = digital_pin_to_analog_pin(Ard_num);
+ const int8_t Port_pin = digital_pin_to_analog_pin(pin);
if (Port_pin >= 0) {
sprintf_P(buffer, PSTR(" (A%d) "), Port_pin);
SERIAL_ECHO(buffer);
@@ -208,8 +224,8 @@ void printPinPort(const pin_t Ard_num) {
SERIAL_ECHO_SP(7);
// Print number to be used with M42
- int calc_p = Ard_num;
- if (Ard_num > NUM_DIGITAL_PINS) {
+ int calc_p = pin;
+ if (pin > NUM_DIGITAL_PINS) {
calc_p -= NUM_ANALOG_FIRST;
if (calc_p > 7) calc_p += 8;
}
@@ -222,15 +238,15 @@ void printPinPort(const pin_t Ard_num) {
}
}
-bool pwm_status(const pin_t Ard_num) {
- return get_pin_mode(Ard_num) == MODE_PIN_ALT;
+bool pwm_status(const pin_t pin) {
+ return get_pin_mode(pin) == MODE_PIN_ALT;
}
-void printPinPWM(const pin_t Ard_num) {
+void printPinPWM(const pin_t pin) {
#ifndef STM32F1xx
- if (pwm_status(Ard_num)) {
+ if (pwm_status(pin)) {
uint32_t alt_all = 0;
- const PinName dp = digitalPinToPinName(Ard_num);
+ const PinName dp = digitalPinToPinName(pin);
pin_t pin_number = uint8_t(PIN_NUM(dp));
const bool over_7 = pin_number >= 8;
const uint8_t ind = over_7 ? 1 : 0;
diff --git a/Marlin/src/HAL/STM32F1/pinsDebug.h b/Marlin/src/HAL/STM32F1/pinsDebug.h
index ab8bc8816eae..9191614587b4 100644
--- a/Marlin/src/HAL/STM32F1/pinsDebug.h
+++ b/Marlin/src/HAL/STM32F1/pinsDebug.h
@@ -22,11 +22,23 @@
#pragma once
/**
- * Support routines for MAPLE_STM32F1
- */
-
-/**
- * Translation of routines & variables used by pinsDebug.h
+ * Pins Debugging for Maple STM32F1
+ *
+ * - NUMBER_PINS_TOTAL
+ * - MULTI_NAME_PAD
+ * - getPinByIndex(index)
+ * - printPinNameByIndex(index)
+ * - getPinIsDigitalByIndex(index)
+ * - digitalPinToAnalogIndex(pin)
+ * - getValidPinMode(pin)
+ * - isValidPin(pin)
+ * - isAnalogPin(pin)
+ * - digitalRead_mod(pin)
+ * - pwm_status(pin)
+ * - printPinPWM(pin)
+ * - printPinPort(pin)
+ * - printPinNumber(pin)
+ * - printPinAnalog(pin)
*/
#ifndef BOARD_NR_GPIO_PINS // Only in MAPLE_STM32F1
@@ -39,11 +51,11 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS];
#define NUM_DIGITAL_PINS BOARD_NR_GPIO_PINS
#define NUMBER_PINS_TOTAL BOARD_NR_GPIO_PINS
-#define isValidPin(pin) (pin >= 0 && pin < BOARD_NR_GPIO_PINS)
-#define getPinByIndex(p) pin_t(pin_array[p].pin)
-#define digitalRead_mod(p) extDigitalRead(p)
-#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(p)); SERIAL_ECHO(buffer); }while(0)
-#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
+#define isValidPin(P) (P >= 0 && P < BOARD_NR_GPIO_PINS)
+#define getPinByIndex(x) pin_t(pin_array[x].pin)
+#define digitalRead_mod(P) extDigitalRead(P)
+#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(P)); SERIAL_ECHO(buffer); }while(0)
+#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 21 // space needed to be pretty if not first name assigned to a pin
@@ -78,8 +90,8 @@ bool getValidPinMode(const pin_t pin) {
return isValidPin(pin) && !IS_INPUT(pin);
}
-bool getPinIsDigitalByIndex(const int16_t array_pin) {
- const pin_t pin = getPinByIndex(array_pin);
+bool getPinIsDigitalByIndex(const int16_t index) {
+ const pin_t pin = getPinByIndex(index);
return (!isAnalogPin(pin)
#ifdef NUM_ANALOG_INPUTS
|| PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS
diff --git a/Marlin/src/HAL/TEENSY31_32/pinsDebug.h b/Marlin/src/HAL/TEENSY31_32/pinsDebug.h
index d4a91ce801c2..741909bf0a40 100644
--- a/Marlin/src/HAL/TEENSY31_32/pinsDebug.h
+++ b/Marlin/src/HAL/TEENSY31_32/pinsDebug.h
@@ -1 +1,71 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2019 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
+
#error "PINS_DEBUGGING is not yet supported for Teensy 3.1 / 3.2!"
+
+/**
+ * Pins Debugging for ESP32
+ *
+ * - NUMBER_PINS_TOTAL
+ * - MULTI_NAME_PAD
+ * - getPinByIndex(index)
+ * - printPinNameByIndex(index)
+ * - getPinIsDigitalByIndex(index)
+ * - digitalPinToAnalogIndex(pin)
+ * - getValidPinMode(pin)
+ * - isValidPin(pin)
+ * - isAnalogPin(pin)
+ * - digitalRead_mod(pin)
+ * - pwm_status(pin)
+ * - printPinPWM(pin)
+ * - printPinPort(pin)
+ * - printPinNumber(pin)
+ * - printPinAnalog(pin)
+ */
+
+#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
+#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
+
+#define digitalRead_mod(P) extDigitalRead(P)
+#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
+#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%02d"), P); SERIAL_ECHO(buffer); }while(0)
+#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
+#define getPinByIndex(x) pin_array[x].pin
+#define getPinIsDigitalByIndex(x) pin_array[x].is_digital
+#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL))
+#define digitalPinToAnalogIndex(P) int(P - analogInputToDigitalPin(0))
+#define isAnalogPin(P) WITHIN(P, pin_t(analogInputToDigitalPin(0)), pin_t(analogInputToDigitalPin(NUM_ANALOG_INPUTS - 1)))
+bool pwm_status(const pin_t) { return false; }
+
+void printPinPort(const pin_t) {}
+
+static bool getValidPinMode(const pin_t pin) {
+ return isValidPin(pin) /* && !IS_INPUT(pin) */ ;
+}
+
+void printPinPWM(const int32_t pin) {
+ if (pwm_status(pin)) {
+ //uint32_t chan = g_APinDescription[pin].ulPWMChannel TODO when fast pwm is operative;
+ //SERIAL_ECHOPGM("PWM = ", duty);
+ }
+}
diff --git a/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h b/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h
index 843905a8510a..8f2651d3ed43 100644
--- a/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h
+++ b/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h
@@ -48,3 +48,7 @@
#if USING_PULLDOWNS
#error "PULLDOWN pin mode is not available for Teensy 3.5/3.6."
#endif
+
+#if ENABLED(PINS_DEBUGGING)
+ #error "PINS_DEBUGGING is not yet supported for Teensy 3.5/3.6. Needs is_output(pin), etc."
+#endif
diff --git a/Marlin/src/HAL/TEENSY35_36/pinsDebug.h b/Marlin/src/HAL/TEENSY35_36/pinsDebug.h
index 34efc18ccc11..f0f61b8bbe8f 100644
--- a/Marlin/src/HAL/TEENSY35_36/pinsDebug.h
+++ b/Marlin/src/HAL/TEENSY35_36/pinsDebug.h
@@ -22,7 +22,23 @@
#pragma once
/**
- * HAL Pins Debugging for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
+ * Pins Debugging for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
+ *
+ * - NUMBER_PINS_TOTAL
+ * - MULTI_NAME_PAD
+ * - getPinByIndex(index)
+ * - printPinNameByIndex(index)
+ * - getPinIsDigitalByIndex(index)
+ * - digitalPinToAnalogIndex(pin)
+ * - getValidPinMode(pin)
+ * - isValidPin(pin)
+ * - isAnalogPin(pin)
+ * - digitalRead_mod(pin)
+ * - pwm_status(pin)
+ * - printPinPWM(pin)
+ * - printPinPort(pin)
+ * - printPinNumber(pin)
+ * - printPinAnalog(pin)
*/
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
@@ -53,6 +69,15 @@
#define TPM1_CH1_PIN 17
#endif
+#define getPinByIndex(x) pin_array[x].pin
+#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
+#define getPinIsDigitalByIndex(x) pin_array[x].is_digital
+#define digitalPinToAnalogIndex(P) int(P - analogInputToDigitalPin(0))
+#define getValidPinMode(P) (isValidPin(P) && IS_OUTPUT(P))
+#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL))
+#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%02d"), P); SERIAL_ECHO(buffer); }while(0)
+#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
+
#define isAnalogPin(P) ((P) >= analogInputToDigitalPin(0) && (P) <= analogInputToDigitalPin(9)) || ((P) >= analogInputToDigitalPin(12) && (P) <= analogInputToDigitalPin(20))
void printAnalogPin(char buffer[], int8_t pin) {
@@ -77,7 +102,7 @@ void analog_pin_state(char buffer[], int8_t pin) {
* Print a pin's PWM status.
* Return true if it's currently a PWM pin.
*/
-bool pwm_status(int8_t pin) {
+bool pwm_status(const int8_t pin) {
char buffer[20]; // for the sprintf statements
switch (pin) {
FTM_CASE(0,0);
@@ -108,4 +133,6 @@ bool pwm_status(int8_t pin) {
SERIAL_ECHOPGM(" ");
}
-void printPinPWM(uint8_t pin) { /* TODO */ }
+void printPinPWM(const pin_t) { /* TODO */ }
+
+void printPinPort(const pin_t) {}
diff --git a/Marlin/src/HAL/TEENSY40_41/pinsDebug.h b/Marlin/src/HAL/TEENSY40_41/pinsDebug.h
index 40565491d66c..3307b3f71fd6 100644
--- a/Marlin/src/HAL/TEENSY40_41/pinsDebug.h
+++ b/Marlin/src/HAL/TEENSY40_41/pinsDebug.h
@@ -22,25 +22,40 @@
#pragma once
/**
- * HAL Pins Debugging for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
+ * Pins Debugging for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
+ *
+ * - NUMBER_PINS_TOTAL
+ * - MULTI_NAME_PAD
+ * - getPinByIndex(index)
+ * - printPinNameByIndex(index)
+ * - getPinIsDigitalByIndex(index)
+ * - digitalPinToAnalogIndex(pin)
+ * - getValidPinMode(pin)
+ * - isValidPin(pin)
+ * - isAnalogPin(pin)
+ * - digitalRead_mod(pin)
+ * - pwm_status(pin)
+ * - printPinPWM(pin)
+ * - printPinPort(pin)
+ * - printPinNumber(pin)
+ * - printPinAnalog(pin)
*/
#warning "PINS_DEBUGGING is not fully supported for Teensy 4.0 / 4.1 so 'M43' may cause hangs."
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
-#define digitalRead_mod(p) extDigitalRead(p) // AVR digitalRead disabled PWM before it read the pin
+#define getPinByIndex(x) pin_array[x].pin
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
-#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("%02d"), p); SERIAL_ECHO(buffer); }while(0)
-#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
-#define getPinByIndex(p) pin_array[p].pin
-#define getPinIsDigitalByIndex(p) pin_array[p].is_digital
-#define isValidPin(pin) (pin >= 0 && pin < int8_t(NUMBER_PINS_TOTAL))
-#define digitalPinToAnalogIndex(p) int(p - analogInputToDigitalPin(0))
-#define getValidPinMode(PIN) (isValidPin(pin) && IS_OUTPUT(pin))
-#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
-
+#define getPinIsDigitalByIndex(x) pin_array[x].is_digital
+#define digitalPinToAnalogIndex(P) int(P - analogInputToDigitalPin(0))
+#define getValidPinMode(P) (isValidPin(P) && IS_OUTPUT(P))
+#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL))
#define isAnalogPin(P) (pin_t(P) >= analogInputToDigitalPin(0) && pin_t(P) <= analogInputToDigitalPin(13)) || (pin_t(P) >= analogInputToDigitalPin(14) && pin_t(P) <= analogInputToDigitalPin(17))
+#define digitalRead_mod(P) extDigitalRead(P) // AVR digitalRead disabled PWM before it read the pin
+#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%02d"), P); SERIAL_ECHO(buffer); }while(0)
+#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
+#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
struct pwm_pin_info_struct {
uint8_t type; // 0=no pwm, 1=flexpwm, 2=quad
diff --git a/Marlin/src/HAL/platforms.h b/Marlin/src/HAL/platforms.h
index 9eaf7cea9894..36fb79277676 100644
--- a/Marlin/src/HAL/platforms.h
+++ b/Marlin/src/HAL/platforms.h
@@ -54,6 +54,8 @@
#define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/SAMD51/NAME)
#elif defined(__SAMD21__)
#define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/SAMD21/NAME)
+#elif defined(__PLAT_RP2040__)
+ #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/RP2040/NAME)
#else
#error "Unsupported Platform!"
#endif
diff --git a/Marlin/src/HAL/shared/servo.h b/Marlin/src/HAL/shared/servo.h
index 786c1e6a7231..fa75445ed72a 100644
--- a/Marlin/src/HAL/shared/servo.h
+++ b/Marlin/src/HAL/shared/servo.h
@@ -82,13 +82,15 @@
#include "../STM32/Servo.h"
#elif defined(ARDUINO_ARCH_ESP32)
#include "../ESP32/Servo.h"
+#elif defined(__PLAT_RP2040__)
+ #include "../RP2040/Servo.h"
#else
#include
- #if defined(__AVR__) || defined(ARDUINO_ARCH_SAM) || defined(__SAMD51__) || defined(__SAMD21__)
+ #if defined(__AVR__) || defined(ARDUINO_ARCH_SAM) || defined(__SAMD51__) || defined(__SAMD21__) || defined(__PLAT_RP2040__)
// we're good to go
#else
- #error "This library only supports boards with an AVR, SAM3X, SAMD21 or SAMD51 processor."
+ #error "This library only supports boards with an AVR, SAM3X, SAMD21, SAMD51, or RP2040 processor."
#endif
#define Servo_VERSION 2 // software version of this library
diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h
index f48f6d28e183..eadb0bf8d7f1 100644
--- a/Marlin/src/core/boards.h
+++ b/Marlin/src/core/boards.h
@@ -170,19 +170,19 @@
#define BOARD_GT2560_V3_A20 1319 // Geeetech GT2560 Rev B for A20(M/T/D)
#define BOARD_GT2560_V4 1320 // Geeetech GT2560 Rev B for A10(M/T/D)
#define BOARD_GT2560_V4_A20 1321 // Geeetech GT2560 Rev B for A20(M/T/D)
-#define BOARD_EINSTART_S 1322 // Einstart retrofit
-#define BOARD_WANHAO_ONEPLUS 1323 // Wanhao 0ne+ i3 Mini
-#define BOARD_OVERLORD 1324 // Overlord/Overlord Pro
-#define BOARD_HJC2560C_REV1 1325 // ADIMLab Gantry v1
-#define BOARD_HJC2560C_REV2 1326 // ADIMLab Gantry v2
-#define BOARD_LEAPFROG_XEED2015 1327 // Leapfrog Xeed 2015
-#define BOARD_PICA_REVB 1328 // PICA Shield (original version)
-#define BOARD_PICA 1329 // PICA Shield (rev C or later)
-#define BOARD_INTAMSYS40 1330 // Intamsys 4.0 (Funmat HT)
-#define BOARD_MALYAN_M180 1331 // Malyan M180 Mainboard Version 2 (no display function, direct G-code only)
-#define BOARD_PROTONEER_CNC_SHIELD_V3 1332 // Mega controller & Protoneer CNC Shield V3.00
-#define BOARD_WEEDO_62A 1333 // WEEDO 62A board (TINA2, Monoprice Cadet, etc.)
-#define BOARD_GT2560_V41B 1334 // Geeetech GT2560 V4.1B for A10(M/T/D)
+#define BOARD_GT2560_V41B 1322 // Geeetech GT2560 V4.1B for A10(M/T/D)
+#define BOARD_EINSTART_S 1323 // Einstart retrofit
+#define BOARD_WANHAO_ONEPLUS 1324 // Wanhao 0ne+ i3 Mini
+#define BOARD_OVERLORD 1325 // Overlord/Overlord Pro
+#define BOARD_HJC2560C_REV1 1326 // ADIMLab Gantry v1
+#define BOARD_HJC2560C_REV2 1327 // ADIMLab Gantry v2
+#define BOARD_LEAPFROG_XEED2015 1328 // Leapfrog Xeed 2015
+#define BOARD_PICA_REVB 1329 // PICA Shield (original version)
+#define BOARD_PICA 1330 // PICA Shield (rev C or later)
+#define BOARD_INTAMSYS40 1331 // Intamsys 4.0 (Funmat HT)
+#define BOARD_MALYAN_M180 1332 // Malyan M180 Mainboard Version 2 (no display function, direct G-code only)
+#define BOARD_PROTONEER_CNC_SHIELD_V3 1333 // Mega controller & Protoneer CNC Shield V3.00
+#define BOARD_WEEDO_62A 1334 // WEEDO 62A board (TINA2, Monoprice Cadet, etc.)
//
// ATmega1281, ATmega2561
@@ -534,6 +534,13 @@
#define BOARD_AQUILA_V101 7200 // Voxelab Aquila V1.0.0/V1.0.1/V1.0.2/V1.0.3 as found in the Voxelab Aquila X2 and C2
#define BOARD_CREALITY_ENDER2P_V24S4 7201 // Creality Ender 2 Pro v2.4.S4_170 (HC32f460kcta)
+//
+// Raspberry Pi
+//
+
+#define BOARD_RP2040 6200 // Generic RP2040 Test board
+#define BOARD_BTT_SKR_PICO 6201 // BigTreeTech SKR Pico 1.x
+
//
// Custom board
//
diff --git a/Marlin/src/core/drivers.h b/Marlin/src/core/drivers.h
index c4417aab7531..c54e42c8fe1d 100644
--- a/Marlin/src/core/drivers.h
+++ b/Marlin/src/core/drivers.h
@@ -188,3 +188,16 @@
|| HAS_DRIVER(TMC5130_STANDALONE) || HAS_DRIVER(TMC5160_STANDALONE)
#define HAS_DIAG_PINS 1
#endif
+
+// Hybrid Threshold ranges
+#define THRS_TMC2100 65535
+#define THRS_TMC2130 65535
+#define THRS_TMC2160 255
+#define THRS_TMC2208 255
+#define THRS_TMC2209 255
+#define THRS_TMC2660 65535
+#define THRS_TMC5130 65535
+#define THRS_TMC5160 65535
+
+#define _DRIVER_THRS(V) CAT(THRS_, V)
+#define STEPPER_MAX_THRS(S) _DRIVER_THRS(S##_DRIVER_TYPE)
diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h
index 3a9a24a51c28..f64c7513dfce 100644
--- a/Marlin/src/core/language.h
+++ b/Marlin/src/core/language.h
@@ -324,6 +324,7 @@
#define STR_TEMPERATURE_UNITS "Temperature Units"
#define STR_USER_THERMISTORS "User thermistors"
#define STR_DELAYED_POWEROFF "Delayed poweroff"
+#define STR_STORED_MACROS "Stored macros"
//
// General axis names
diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp
index 5373f5efd624..8a8378330f5c 100644
--- a/Marlin/src/core/serial.cpp
+++ b/Marlin/src/core/serial.cpp
@@ -27,6 +27,8 @@
#include "../feature/ethernet.h"
#endif
+#include // dtostrf
+
// Echo commands to the terminal by default in dev mode
uint8_t marlin_debug_flags = TERN(MARLIN_DEV_MODE, MARLIN_DEBUG_ECHO, MARLIN_DEBUG_NONE);
diff --git a/Marlin/src/feature/cancel_object.cpp b/Marlin/src/feature/cancel_object.cpp
index 0040f6ed9df8..818661b1f0d7 100644
--- a/Marlin/src/feature/cancel_object.cpp
+++ b/Marlin/src/feature/cancel_object.cpp
@@ -30,23 +30,20 @@
CancelObject cancelable;
-int8_t CancelObject::object_count, // = 0
- CancelObject::active_object = -1;
-uint32_t CancelObject::canceled; // = 0x0000
-bool CancelObject::skipping; // = false
+cancel_state_t CancelObject::state;
void CancelObject::set_active_object(const int8_t obj) {
- active_object = obj;
+ state.active_object = obj;
if (WITHIN(obj, 0, 31)) {
- if (obj >= object_count) object_count = obj + 1;
- skipping = TEST(canceled, obj);
+ if (obj >= state.object_count) state.object_count = obj + 1;
+ state.skipping = TEST(state.canceled, obj);
}
else
- skipping = false;
+ state.skipping = false;
#if ALL(HAS_STATUS_MESSAGE, CANCEL_OBJECTS_REPORTING)
- if (active_object >= 0)
- ui.set_status(MString<30>(GET_TEXT_F(MSG_PRINTING_OBJECT), ' ', active_object));
+ if (state.active_object >= 0)
+ ui.set_status(MString<30>(GET_TEXT_F(MSG_PRINTING_OBJECT), ' ', state.active_object));
else
ui.reset_status();
#endif
@@ -54,29 +51,29 @@ void CancelObject::set_active_object(const int8_t obj) {
void CancelObject::cancel_object(const int8_t obj) {
if (WITHIN(obj, 0, 31)) {
- SBI(canceled, obj);
- if (obj == active_object) skipping = true;
+ SBI(state.canceled, obj);
+ if (obj == state.active_object) state.skipping = true;
}
}
void CancelObject::uncancel_object(const int8_t obj) {
if (WITHIN(obj, 0, 31)) {
- CBI(canceled, obj);
- if (obj == active_object) skipping = false;
+ CBI(state.canceled, obj);
+ if (obj == state.active_object) state.skipping = false;
}
}
void CancelObject::report() {
- if (active_object >= 0)
- SERIAL_ECHO_MSG("Active Object: ", active_object);
+ if (state.active_object >= 0)
+ SERIAL_ECHO_MSG("Active Object: ", state.active_object);
- if (canceled) {
- SERIAL_ECHO_START();
- SERIAL_ECHOPGM("Canceled:");
- for (int i = 0; i < object_count; i++)
- if (TEST(canceled, i)) { SERIAL_CHAR(' '); SERIAL_ECHO(i); }
- SERIAL_EOL();
- }
+ if (state.canceled == 0x0000) return;
+
+ SERIAL_ECHO_START();
+ SERIAL_ECHOPGM("Canceled:");
+ for (int i = 0; i < state.object_count; i++)
+ if (TEST(state.canceled, i)) { SERIAL_CHAR(' '); SERIAL_ECHO(i); }
+ SERIAL_EOL();
}
#endif // CANCEL_OBJECTS
diff --git a/Marlin/src/feature/cancel_object.h b/Marlin/src/feature/cancel_object.h
index 62548a371937..7f04612d13b1 100644
--- a/Marlin/src/feature/cancel_object.h
+++ b/Marlin/src/feature/cancel_object.h
@@ -23,19 +23,23 @@
#include
+typedef struct CancelState {
+ bool skipping = false;
+ int8_t object_count = 0, active_object = 0;
+ uint32_t canceled = 0x0000;
+} cancel_state_t;
+
class CancelObject {
public:
- static bool skipping;
- static int8_t object_count, active_object;
- static uint32_t canceled;
- static void set_active_object(const int8_t obj);
+ static cancel_state_t state;
+ static void set_active_object(const int8_t obj=state.active_object);
static void cancel_object(const int8_t obj);
static void uncancel_object(const int8_t obj);
static void report();
- static bool is_canceled(const int8_t obj) { return TEST(canceled, obj); }
+ static bool is_canceled(const int8_t obj) { return TEST(state.canceled, obj); }
static void clear_active_object() { set_active_object(-1); }
- static void cancel_active_object() { cancel_object(active_object); }
- static void reset() { canceled = 0x0000; object_count = 0; clear_active_object(); }
+ static void cancel_active_object() { cancel_object(state.active_object); }
+ static void reset() { state.canceled = 0x0000; state.object_count = 0; clear_active_object(); }
};
extern CancelObject cancelable;
diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp
index 135178456b73..55bde4ca62d7 100644
--- a/Marlin/src/feature/encoder_i2c.cpp
+++ b/Marlin/src/feature/encoder_i2c.cpp
@@ -36,7 +36,7 @@
#include "../module/stepper.h"
#include "../gcode/parser.h"
-#include "../feature/babystep.h"
+#include "babystep.h"
#include
diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp
index 2f0e5d9292ed..0c70253dc807 100644
--- a/Marlin/src/feature/leds/leds.cpp
+++ b/Marlin/src/feature/leds/leds.cpp
@@ -31,7 +31,7 @@
#include "leds.h"
#if ANY(CASE_LIGHT_USE_RGB_LED, CASE_LIGHT_USE_NEOPIXEL)
- #include "../../feature/caselight.h"
+ #include "../caselight.h"
#endif
#if ENABLED(LED_COLOR_PRESETS)
diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp
index 11a0b21891fa..d5f115e74c2a 100644
--- a/Marlin/src/feature/mmu/mmu2.cpp
+++ b/Marlin/src/feature/mmu/mmu2.cpp
@@ -43,7 +43,7 @@ MMU2 mmu2;
#include "../../MarlinCore.h"
#if ENABLED(HOST_PROMPT_SUPPORT)
- #include "../../feature/host_actions.h"
+ #include "../host_actions.h"
#endif
#if ENABLED(EXTENSIBLE_UI)
diff --git a/Marlin/src/feature/mmu3/mmu3_fsensor.cpp b/Marlin/src/feature/mmu3/mmu3_fsensor.cpp
index ad860c44b920..32d2fac3f60b 100644
--- a/Marlin/src/feature/mmu3/mmu3_fsensor.cpp
+++ b/Marlin/src/feature/mmu3/mmu3_fsensor.cpp
@@ -28,7 +28,7 @@
#if HAS_PRUSA_MMU3
-#include "../../feature/runout.h"
+#include "../runout.h"
#include "mmu3_fsensor.h"
namespace MMU3 {
diff --git a/Marlin/src/feature/mmu3/mmu3_marlin1.cpp b/Marlin/src/feature/mmu3/mmu3_marlin1.cpp
index 5eaf178393a2..be54695c7403 100644
--- a/Marlin/src/feature/mmu3/mmu3_marlin1.cpp
+++ b/Marlin/src/feature/mmu3/mmu3_marlin1.cpp
@@ -34,7 +34,7 @@
#include "../../module/planner.h"
#include "../../module/temperature.h"
-#include "../../feature/pause.h"
+#include "../pause.h"
#include "../../libs/nozzle.h"
#include "mmu3_marlin.h"
diff --git a/Marlin/src/feature/mmu3/mmu3_reporting.cpp b/Marlin/src/feature/mmu3/mmu3_reporting.cpp
index 38ae4354d7ec..4bf2088d2785 100644
--- a/Marlin/src/feature/mmu3/mmu3_reporting.cpp
+++ b/Marlin/src/feature/mmu3/mmu3_reporting.cpp
@@ -43,7 +43,7 @@
#include "../../core/language.h"
#include "../../gcode/gcode.h"
-#include "../../feature/host_actions.h"
+#include "../host_actions.h"
#include "../../lcd/marlinui.h"
#include "../../lcd/menu/menu.h"
#include "../../lcd/menu/menu_item.h"
diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp
index 6c35de7cb5cc..a97887773c51 100644
--- a/Marlin/src/feature/powerloss.cpp
+++ b/Marlin/src/feature/powerloss.cpp
@@ -99,7 +99,7 @@ PrintJobRecovery recovery;
/**
* Clear the recovery info
*/
-void PrintJobRecovery::init() { memset(&info, 0, sizeof(info)); }
+void PrintJobRecovery::init() { info = {}; }
/**
* Enable or disable then call changed()
@@ -215,6 +215,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW
info.zraise = zraise;
info.flag.raised = raised; // Was Z raised before power-off?
+ TERN_(CANCEL_OBJECTS, info.cancel_state = cancelable.state);
TERN_(GCODE_REPEAT_MARKERS, info.stored_repeat = repeat);
TERN_(HAS_HOME_OFFSET, info.home_offset = home_offset);
TERN_(HAS_WORKSPACE_OFFSET, info.workspace_offset = workspace_offset);
@@ -575,6 +576,11 @@ void PrintJobRecovery::resume() {
// Restore E position with G92.9
PROCESS_SUBCOMMANDS_NOW(TS(F("G92.9E"), p_float_t(resume_pos.e, 3)));
+ #if ENABLED(CANCEL_OBJECTS)
+ cancelable.state = info.cancel_state;
+ cancelable.set_active_object(); // Sets the status message
+ #endif
+
TERN_(GCODE_REPEAT_MARKERS, repeat = info.stored_repeat);
TERN_(HAS_HOME_OFFSET, home_offset = info.home_offset);
TERN_(HAS_WORKSPACE_OFFSET, workspace_offset = info.workspace_offset);
@@ -613,6 +619,14 @@ void PrintJobRecovery::resume() {
DEBUG_ECHOLNPGM("zraise: ", info.zraise, " ", info.flag.raised ? "(before)" : "");
+ #if ENABLED(CANCEL_OBJECTS)
+ const cancel_state_t cs = info.cancel_state;
+ DEBUG_ECHOPGM("Canceled:");
+ for (int i = 0; i < cs.object_count; i++)
+ if (TEST(cs.canceled, i)) { DEBUG_CHAR(' '); DEBUG_ECHO(i); }
+ DEBUG_EOL();
+ #endif
+
#if ENABLED(GCODE_REPEAT_MARKERS)
const uint8_t ind = info.stored_repeat.count();
DEBUG_ECHOLNPGM("repeat markers: ", ind);
diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h
index 238f276c1bc8..8e1e299ac0ce 100644
--- a/Marlin/src/feature/powerloss.h
+++ b/Marlin/src/feature/powerloss.h
@@ -30,12 +30,16 @@
#include "../inc/MarlinConfig.h"
+#if ENABLED(CANCEL_OBJECTS)
+ #include "cancel_object.h"
+#endif
+
#if ENABLED(GCODE_REPEAT_MARKERS)
- #include "../feature/repeat.h"
+ #include "repeat.h"
#endif
#if ENABLED(MIXING_EXTRUDER)
- #include "../feature/mixing.h"
+ #include "mixing.h"
#endif
#if !defined(POWER_LOSS_STATE) && PIN_EXISTS(POWER_LOSS)
@@ -64,6 +68,11 @@ typedef struct {
float zraise;
+ // Canceled objects
+ #if ENABLED(CANCEL_OBJECTS)
+ cancel_state_t cancel_state;
+ #endif
+
// Repeat information
#if ENABLED(GCODE_REPEAT_MARKERS)
Repeat stored_repeat;
diff --git a/Marlin/src/feature/runout.cpp b/Marlin/src/feature/runout.cpp
index 2bcb47e99a83..cb7c6279bc48 100644
--- a/Marlin/src/feature/runout.cpp
+++ b/Marlin/src/feature/runout.cpp
@@ -59,7 +59,7 @@ bool FilamentMonitorBase::enabled = true,
// Filament Runout event handler
//
#include "../MarlinCore.h"
-#include "../feature/pause.h"
+#include "pause.h"
#include "../gcode/queue.h"
#if ENABLED(HOST_ACTION_COMMANDS)
diff --git a/Marlin/src/feature/runout.h b/Marlin/src/feature/runout.h
index c95c39f27387..a152bd1e779e 100644
--- a/Marlin/src/feature/runout.h
+++ b/Marlin/src/feature/runout.h
@@ -30,7 +30,7 @@
#include "../module/planner.h"
#include "../module/stepper.h" // for block_t
#include "../gcode/queue.h"
-#include "../feature/pause.h" // for did_pause_print
+#include "pause.h" // for did_pause_print
#include "../MarlinCore.h" // for printingIsActive()
#include "../inc/MarlinConfig.h"
diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp
index c0635c72206f..b83c1c17972f 100644
--- a/Marlin/src/feature/spindle_laser.cpp
+++ b/Marlin/src/feature/spindle_laser.cpp
@@ -35,7 +35,7 @@
#endif
#if ENABLED(I2C_AMMETER)
- #include "../feature/ammeter.h"
+ #include "ammeter.h"
#endif
SpindleLaser cutter;
diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h
index 12f3a38d3038..0c4b78e43505 100644
--- a/Marlin/src/feature/tmc_util.h
+++ b/Marlin/src/feature/tmc_util.h
@@ -77,8 +77,8 @@ class TMCStorage {
struct {
OPTCODE(HAS_STEALTHCHOP, bool stealthChop_enabled = false)
- OPTCODE(HYBRID_THRESHOLD, uint8_t hybrid_thrs = 0)
- OPTCODE(USE_SENSORLESS, int16_t homing_thrs = 0)
+ OPTCODE(HYBRID_THRESHOLD, uint16_t hybrid_thrs = 0)
+ OPTCODE(USE_SENSORLESS, int16_t homing_thrs = 0)
} stored;
};
diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp
index e4272c1a7b46..8c26ca4e8fd4 100644
--- a/Marlin/src/gcode/bedlevel/G26.cpp
+++ b/Marlin/src/gcode/bedlevel/G26.cpp
@@ -102,7 +102,7 @@
#define G26_OK false
#define G26_ERR true
-#include "../../gcode/gcode.h"
+#include "../gcode.h"
#include "../../feature/bedlevel/bedlevel.h"
#include "../../MarlinCore.h"
diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp
index c695cd328fdf..893607792acd 100644
--- a/Marlin/src/gcode/config/M43.cpp
+++ b/Marlin/src/gcode/config/M43.cpp
@@ -71,11 +71,13 @@ inline void toggle_pins() {
else {
hal.watchdog_refresh();
printPinStateExt(pin, ignore_protection, true, F("Pulsing "));
- #ifdef __STM32F1__
- const auto prior_mode = _GET_MODE(i);
- #else
- const bool prior_mode = getValidPinMode(pin);
- #endif
+ const auto prior_mode = (
+ #ifdef __STM32F1__
+ _GET_MODE(i)
+ #else
+ getValidPinMode(pin)
+ #endif
+ );
#if AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO
if (pin == TEENSY_E2) {
SET_OUTPUT(TEENSY_E2);
diff --git a/Marlin/src/gcode/feature/cancel/M486.cpp b/Marlin/src/gcode/feature/cancel/M486.cpp
index c1e90d1b9610..37347e9d43c2 100644
--- a/Marlin/src/gcode/feature/cancel/M486.cpp
+++ b/Marlin/src/gcode/feature/cancel/M486.cpp
@@ -41,7 +41,7 @@ void GcodeSuite::M486() {
if (parser.seen('T')) {
cancelable.reset();
- cancelable.object_count = parser.intval('T', 1);
+ cancelable.state.object_count = parser.intval('T', 1);
}
if (parser.seenval('S'))
diff --git a/Marlin/src/gcode/feature/macro/M820.cpp b/Marlin/src/gcode/feature/macro/M820.cpp
new file mode 100644
index 000000000000..9759f482ec12
--- /dev/null
+++ b/Marlin/src/gcode/feature/macro/M820.cpp
@@ -0,0 +1,52 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2019 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 ENABLED(GCODE_MACROS)
+
+#include "../../gcode.h"
+#include "../../queue.h"
+#include "../../parser.h"
+
+extern char gcode_macros[GCODE_MACROS_SLOTS][GCODE_MACROS_SLOT_SIZE + 1];
+
+/**
+ * M820: List defined M810 - M819 macros
+ */
+void GcodeSuite::M820() {
+ SERIAL_ECHOLNPGM(STR_STORED_MACROS);
+ bool some = false;
+ for (uint8_t i = 0; i < GCODE_MACROS_SLOTS; ++i) {
+ const char *cmd = gcode_macros[i];
+ if (*cmd) {
+ SERIAL_ECHO(F("M81"), i, C(' '));
+ char c;
+ while ((c = *cmd++)) SERIAL_CHAR(c == '\n' ? '|' : c);
+ SERIAL_EOL();
+ some = true;
+ }
+ }
+ if (!some) SERIAL_ECHOLNPGM("None");
+}
+
+#endif // GCODE_MACROS
diff --git a/Marlin/src/gcode/feature/pause/G61.cpp b/Marlin/src/gcode/feature/pause/G61.cpp
index 08b4a99b7de5..7f2a45bc933f 100644
--- a/Marlin/src/gcode/feature/pause/G61.cpp
+++ b/Marlin/src/gcode/feature/pause/G61.cpp
@@ -75,7 +75,9 @@ void GcodeSuite::G61(int8_t slot/*=-1*/) {
// No XYZ...E parameters, move to stored position
- float epos = stored_position[slot].e;
+ #if HAS_EXTRUDERS
+ float epos = stored_position[slot].e;
+ #endif
if (!parser.seen_axis()) {
DEBUG_ECHOLNPGM(STR_RESTORING_POSITION, slot, " (all axes)");
// Move to the saved position, all axes except E
diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp
index 32125752554b..9fed4dcada3f 100644
--- a/Marlin/src/gcode/gcode.cpp
+++ b/Marlin/src/gcode/gcode.cpp
@@ -165,7 +165,7 @@ void GcodeSuite::get_destination_from_command() {
xyze_bool_t seen{false};
#if ENABLED(CANCEL_OBJECTS)
- const bool &skip_move = cancelable.skipping;
+ const bool &skip_move = cancelable.state.skipping;
#else
constexpr bool skip_move = false;
#endif
@@ -1010,6 +1010,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
case 810: case 811: case 812: case 813: case 814:
case 815: case 816: case 817: case 818: case 819:
M810_819(); break; // M810-M819: Define/execute G-code macro
+ case 820: M820(); break; // M820: Report macros to serial output
#endif
#if HAS_BED_PROBE
diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h
index 2f725649971a..c6b4a40d9f69 100644
--- a/Marlin/src/gcode/gcode.h
+++ b/Marlin/src/gcode/gcode.h
@@ -1194,6 +1194,7 @@ class GcodeSuite {
#if ENABLED(GCODE_MACROS)
static void M810_819();
+ static void M820();
#endif
#if HAS_BED_PROBE
diff --git a/Marlin/src/gcode/host/M360.cpp b/Marlin/src/gcode/host/M360.cpp
index 8d6bb4771a0e..535ed4803959 100644
--- a/Marlin/src/gcode/host/M360.cpp
+++ b/Marlin/src/gcode/host/M360.cpp
@@ -61,7 +61,9 @@ void GcodeSuite::M360() {
PGMSTR(X_STR, "X");
PGMSTR(Y_STR, "Y");
PGMSTR(Z_STR, "Z");
- PGMSTR(JERK_STR, "Jerk");
+ #if ANY(CLASSIC_JERK, HAS_LINEAR_E_JERK)
+ PGMSTR(JERK_STR, "Jerk");
+ #endif
//
// Basics and Enabled items
diff --git a/Marlin/src/inc/Conditionals-4-adv.h b/Marlin/src/inc/Conditionals-4-adv.h
index 291c140bfc07..b6981e59a2b6 100644
--- a/Marlin/src/inc/Conditionals-4-adv.h
+++ b/Marlin/src/inc/Conditionals-4-adv.h
@@ -610,23 +610,6 @@
#endif
#endif
-#if TEMP_SENSOR_IS_MAX_TC(0) || TEMP_SENSOR_IS_MAX_TC(1) || TEMP_SENSOR_IS_MAX_TC(2) || TEMP_SENSOR_IS_MAX_TC(BED) || TEMP_SENSOR_IS_MAX_TC(REDUNDANT)
- #define HAS_MAX_TC 1
-#endif
-#if TEMP_SENSOR_0_IS_MAX6675 || TEMP_SENSOR_1_IS_MAX6675 || TEMP_SENSOR_2_IS_MAX6675 || TEMP_SENSOR_BED_IS_MAX6675 || TEMP_SENSOR_REDUNDANT_IS_MAX6675
- #define HAS_MAX6675 1
-#endif
-#if TEMP_SENSOR_0_IS_MAX31855 || TEMP_SENSOR_1_IS_MAX31855 || TEMP_SENSOR_2_IS_MAX31855 || TEMP_SENSOR_BED_IS_MAX31855 || TEMP_SENSOR_REDUNDANT_IS_MAX31855
- #define HAS_MAX31855 1
-#endif
-#if TEMP_SENSOR_0_IS_MAX31865 || TEMP_SENSOR_1_IS_MAX31865 || TEMP_SENSOR_2_IS_MAX31865 || TEMP_SENSOR_BED_IS_MAX31865 || TEMP_SENSOR_REDUNDANT_IS_MAX31865
- #define HAS_MAX31865 1
-#endif
-
-#if !HAS_MAX_TC
- #undef THERMOCOUPLE_MAX_ERRORS
-#endif
-
#if TEMP_SENSOR_3 == -4
#define TEMP_SENSOR_3_IS_AD8495 1
#elif TEMP_SENSOR_3 == -3
@@ -745,6 +728,23 @@
#endif
#endif
+#if TEMP_SENSOR_IS_MAX_TC(0) || TEMP_SENSOR_IS_MAX_TC(1) || TEMP_SENSOR_IS_MAX_TC(2) || TEMP_SENSOR_IS_MAX_TC(BED) || TEMP_SENSOR_IS_MAX_TC(REDUNDANT)
+ #define HAS_MAX_TC 1
+#endif
+#if TEMP_SENSOR_0_IS_MAX6675 || TEMP_SENSOR_1_IS_MAX6675 || TEMP_SENSOR_2_IS_MAX6675 || TEMP_SENSOR_BED_IS_MAX6675 || TEMP_SENSOR_REDUNDANT_IS_MAX6675
+ #define HAS_MAX6675 1
+#endif
+#if TEMP_SENSOR_0_IS_MAX31855 || TEMP_SENSOR_1_IS_MAX31855 || TEMP_SENSOR_2_IS_MAX31855 || TEMP_SENSOR_BED_IS_MAX31855 || TEMP_SENSOR_REDUNDANT_IS_MAX31855
+ #define HAS_MAX31855 1
+#endif
+#if TEMP_SENSOR_0_IS_MAX31865 || TEMP_SENSOR_1_IS_MAX31865 || TEMP_SENSOR_2_IS_MAX31865 || TEMP_SENSOR_BED_IS_MAX31865 || TEMP_SENSOR_REDUNDANT_IS_MAX31865
+ #define HAS_MAX31865 1
+#endif
+
+#if !HAS_MAX_TC
+ #undef THERMOCOUPLE_MAX_ERRORS
+#endif
+
#if TEMP_SENSOR_CHAMBER == -4
#define TEMP_SENSOR_CHAMBER_IS_AD8495 1
#elif TEMP_SENSOR_CHAMBER == -3
@@ -1371,7 +1371,7 @@
#if MB(MKS_MONSTER8_V1, BTT_SKR_MINI_E3_V1_0, BTT_SKR_MINI_E3_V1_2, BTT_SKR_MINI_E3_V2_0, BTT_SKR_MINI_E3_V3_0, BTT_SKR_MINI_E3_V3_0_1, BTT_SKR_E3_TURBO, BTT_OCTOPUS_V1_1, BTT_SKR_V3_0, BTT_SKR_V3_0_EZ, AQUILA_V101)
#define LCD_SERIAL_PORT 1
- #elif MB(CREALITY_V24S1_301, CREALITY_V24S1_301F4, CREALITY_F401RE, CREALITY_V423, CREALITY_CR4NTXXC10, MKS_ROBIN, PANOWIN_CUTLASS, KODAMA_BARDO)
+ #elif MB(CREALITY_V24S1_301, CREALITY_V24S1_301F4, CREALITY_F401RE, CREALITY_V423, CREALITY_CR4NTXXC10, CREALITY_CR4NS, MKS_ROBIN, PANOWIN_CUTLASS, KODAMA_BARDO)
#define LCD_SERIAL_PORT 2
#else
#define LCD_SERIAL_PORT 3
diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h
index 1e27c1fd1c7f..9ec17b28089e 100644
--- a/Marlin/src/inc/SanityCheck.h
+++ b/Marlin/src/inc/SanityCheck.h
@@ -3059,49 +3059,69 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i
#define INVALID_TMC_UART(ST) (AXIS_HAS_UART(ST) && !(defined(ST##_HARDWARE_SERIAL) || (PINS_EXIST(ST##_SERIAL_RX, ST##_SERIAL_TX))))
#if INVALID_TMC_UART(X)
#error "TMC2208 or TMC2209 on X requires X_HARDWARE_SERIAL or X_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(X2)
+#endif
+#if INVALID_TMC_UART(X2)
#error "TMC2208 or TMC2209 on X2 requires X2_HARDWARE_SERIAL or X2_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(Y)
+#endif
+#if INVALID_TMC_UART(Y)
#error "TMC2208 or TMC2209 on Y requires Y_HARDWARE_SERIAL or Y_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(Y2)
+#endif
+#if INVALID_TMC_UART(Y2)
#error "TMC2208 or TMC2209 on Y2 requires Y2_HARDWARE_SERIAL or Y2_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(Z)
+#endif
+#if INVALID_TMC_UART(Z)
#error "TMC2208 or TMC2209 on Z requires Z_HARDWARE_SERIAL or Z_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(Z2)
+#endif
+#if INVALID_TMC_UART(Z2)
#error "TMC2208 or TMC2209 on Z2 requires Z2_HARDWARE_SERIAL or Z2_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(Z3)
+#endif
+#if INVALID_TMC_UART(Z3)
#error "TMC2208 or TMC2209 on Z3 requires Z3_HARDWARE_SERIAL or Z3_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(Z4)
+#endif
+#if INVALID_TMC_UART(Z4)
#error "TMC2208 or TMC2209 on Z4 requires Z4_HARDWARE_SERIAL or Z4_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(E0)
+#endif
+#if INVALID_TMC_UART(E0)
#error "TMC2208 or TMC2209 on E0 requires E0_HARDWARE_SERIAL or E0_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(E1)
+#endif
+#if INVALID_TMC_UART(E1)
#error "TMC2208 or TMC2209 on E1 requires E1_HARDWARE_SERIAL or E1_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(E2)
+#endif
+#if INVALID_TMC_UART(E2)
#error "TMC2208 or TMC2209 on E2 requires E2_HARDWARE_SERIAL or E2_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(E3)
+#endif
+#if INVALID_TMC_UART(E3)
#error "TMC2208 or TMC2209 on E3 requires E3_HARDWARE_SERIAL or E3_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(E4)
+#endif
+#if INVALID_TMC_UART(E4)
#error "TMC2208 or TMC2209 on E4 requires E4_HARDWARE_SERIAL or E4_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(E5)
+#endif
+#if INVALID_TMC_UART(E5)
#error "TMC2208 or TMC2209 on E5 requires E5_HARDWARE_SERIAL or E5_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(E6)
+#endif
+#if INVALID_TMC_UART(E6)
#error "TMC2208 or TMC2209 on E6 requires E6_HARDWARE_SERIAL or E6_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(E7)
+#endif
+#if INVALID_TMC_UART(E7)
#error "TMC2208 or TMC2209 on E7 requires E7_HARDWARE_SERIAL or E7_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(I)
+#endif
+#if INVALID_TMC_UART(I)
#error "TMC2208 or TMC2209 on I requires I_HARDWARE_SERIAL or I_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(J)
+#endif
+#if INVALID_TMC_UART(J)
#error "TMC2208 or TMC2209 on J requires J_HARDWARE_SERIAL or J_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(K)
+#endif
+#if INVALID_TMC_UART(K)
#error "TMC2208 or TMC2209 on K requires K_HARDWARE_SERIAL or K_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(U)
+#endif
+#if INVALID_TMC_UART(U)
#error "TMC2208 or TMC2209 on U requires U_HARDWARE_SERIAL or U_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(V)
+#endif
+#if INVALID_TMC_UART(V)
#error "TMC2208 or TMC2209 on V requires V_HARDWARE_SERIAL or V_SERIAL_(RX|TX)_PIN."
-#elif INVALID_TMC_UART(W)
+#endif
+#if INVALID_TMC_UART(W)
#error "TMC2208 or TMC2209 on W requires W_HARDWARE_SERIAL or W_SERIAL_(RX|TX)_PIN."
-
#endif
#undef INVALID_TMC_UART
@@ -4309,6 +4329,17 @@ static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive."
#error "SDSUPPORT, BINARY_FILE_TRANSFER, and CUSTOM_FIRMWARE_UPLOAD are required for custom upload."
#endif
+/**
+ * Direct Stepping requirements
+ */
+#if ENABLED(DIRECT_STEPPING)
+ #if ENABLED(CPU_32_BIT)
+ #error "Direct Stepping is not supported on 32-bit boards."
+ #elif !IS_FULL_CARTESIAN
+ #error "Direct Stepping is incompatible with enabled kinematics."
+ #endif
+#endif
+
/**
* Input Shaping requirements
*/
diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h
index 100e4c306296..359f6daecd14 100644
--- a/Marlin/src/inc/Version.h
+++ b/Marlin/src/inc/Version.h
@@ -42,7 +42,7 @@
* version was tagged.
*/
#ifndef STRING_DISTRIBUTION_DATE
- #define STRING_DISTRIBUTION_DATE "2024-10-21"
+ #define STRING_DISTRIBUTION_DATE "2024-11-13"
#endif
/**
diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp
index 0ccc9d6acf68..229755c6d0ab 100644
--- a/Marlin/src/inc/Warnings.cpp
+++ b/Marlin/src/inc/Warnings.cpp
@@ -729,8 +729,12 @@
#endif
#endif
-#if ENABLED(QUICK_HOME) && (X_SPI_SENSORLESS || Y_SPI_SENSORLESS)
- #warning "SPI_ENDSTOPS may be unreliable with QUICK_HOME. Adjust SENSORLESS_BACKOFF_MM for better results."
+#if ENABLED(QUICK_HOME)
+ #if X_SPI_SENSORLESS || Y_SPI_SENSORLESS
+ #warning "If SPI_ENDSTOPS are unreliable with QUICK_HOME try adjusting SENSORLESS_BACKOFF_MM, Travel Acceleration (M204 T), Homing Feedrate (M210 XY), or disable QUICK_HOME."
+ #elif X_SENSORLESS || Y_SENSORLESS
+ #warning "If SENSORLESS_HOMING is unreliable with QUICK_HOME try adjusting SENSORLESS_BACKOFF_MM, Travel Acceleration (M204 T), Homing Feedrate (M210 XY), or disable QUICK_HOME."
+ #endif
#endif
#if HIGHER_CURRENT_HOME_WARNING
diff --git a/Marlin/src/lcd/e3v2/common/limits.h b/Marlin/src/lcd/e3v2/common/limits.h
index 409b735dc898..560c8735a7c6 100644
--- a/Marlin/src/lcd/e3v2/common/limits.h
+++ b/Marlin/src/lcd/e3v2/common/limits.h
@@ -115,9 +115,9 @@ constexpr xyze_float_t max_steps_edit_values =
constexpr xyz_uint_t min_homing_edit_values = NUM_AXIS_ARRAY_1(MIN_HOMING_EDIT_VALUE);
#ifdef DEFAULT_MAX_MULTIPLIER
- constexpr xyz_uint_t default_homing = HOMING_FEEDRATE_MM_M;
+ constexpr xyz_long_t default_homing = HOMING_FEEDRATE_MM_M;
#endif
- constexpr xyz_uint_t max_homing_edit_values =
+ constexpr xyz_long_t max_homing_edit_values =
#ifdef DEFAULT_MAX_MULTIPLIER
default_homing * DEFAULT_MAX_MULTIPLIER
#else
diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp
index e483d4a5ce41..f4b5ba5339ac 100644
--- a/Marlin/src/lcd/e3v2/proui/dwin.cpp
+++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp
@@ -2672,7 +2672,7 @@ void applyMaxAccel() { planner.set_max_acceleration(hmiValue.axis, menuData.valu
default: break;
}
}
- void applyHomingFR() { updateHomingFR(HMI_value.axis, MenuData.Value); }
+ void applyHomingFR() { updateHomingFR(hmiValue.axis, menuData.value); }
#if HAS_X_AXIS
void setHomingX() { hmiValue.axis = X_AXIS; setIntOnClick(min_homing_edit_values.x, max_homing_edit_values.x, homing_feedrate_mm_m.x, applyHomingFR); }
#endif
@@ -3799,15 +3799,15 @@ void drawMaxAccelMenu() {
if (SET_MENU(homingFRMenu, MSG_HOMING_FEEDRATE, 4)) {
BACK_ITEM(drawMotionMenu);
#if HAS_X_AXIS
- static uint16_t xhome = static_cast(homing_feedrate_mm_m.x);
+ uint16_t xhome = static_cast(homing_feedrate_mm_m.x);
EDIT_ITEM(ICON_MaxSpeedJerkX, MSG_HOMING_FEEDRATE_X, onDrawPIntMenu, setHomingX, &xhome);
#endif
#if HAS_Y_AXIS
- static uint16_t yhome = static_cast(homing_feedrate_mm_m.y);
+ uint16_t yhome = static_cast(homing_feedrate_mm_m.y);
EDIT_ITEM(ICON_MaxSpeedJerkY, MSG_HOMING_FEEDRATE_Y, onDrawPIntMenu, setHomingY, &yhome);
#endif
#if HAS_Z_AXIS
- static uint16_t zhome = static_cast(homing_feedrate_mm_m.z);
+ uint16_t zhome = static_cast(homing_feedrate_mm_m.z);
EDIT_ITEM(ICON_MaxSpeedJerkZ, MSG_HOMING_FEEDRATE_Z, onDrawPIntMenu, setHomingZ, &zhome);
#endif
}
diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h
index 29b5a1bed396..71a7a6869d48 100644
--- a/Marlin/src/lcd/language/language_en.h
+++ b/Marlin/src/lcd/language/language_en.h
@@ -449,10 +449,10 @@ namespace LanguageNarrow_en {
LSTR MSG_A_RETRACT = _UxGT("Retract Accel");
LSTR MSG_A_TRAVEL = _UxGT("Travel Accel");
LSTR MSG_INPUT_SHAPING = _UxGT("Input Shaping");
- LSTR MSG_SHAPING_ENABLE = _UxGT("Enable @ shaping");
- LSTR MSG_SHAPING_DISABLE = _UxGT("Disable @ shaping");
- LSTR MSG_SHAPING_FREQ = _UxGT("@ frequency");
- LSTR MSG_SHAPING_ZETA = _UxGT("@ damping");
+ LSTR MSG_SHAPING_ENABLE_N = _UxGT("Enable @ shaping");
+ LSTR MSG_SHAPING_DISABLE_N = _UxGT("Disable @ shaping");
+ LSTR MSG_SHAPING_FREQ_N = _UxGT("@ frequency");
+ LSTR MSG_SHAPING_ZETA_N = _UxGT("@ damping");
LSTR MSG_SHAPING_A_FREQ = STR_A _UxGT(" frequency"); // ProUI
LSTR MSG_SHAPING_B_FREQ = STR_B _UxGT(" frequency"); // ProUI
LSTR MSG_SHAPING_C_FREQ = STR_C _UxGT(" frequency"); // ProUI
diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h
index 2244fa344322..005f0b45a465 100644
--- a/Marlin/src/lcd/language/language_it.h
+++ b/Marlin/src/lcd/language/language_it.h
@@ -424,10 +424,10 @@ namespace LanguageNarrow_it {
LSTR MSG_A_RETRACT = _UxGT("A-Ritrazione");
LSTR MSG_A_TRAVEL = _UxGT("A-Spostamento");
LSTR MSG_INPUT_SHAPING = _UxGT("Input shaping");
- LSTR MSG_SHAPING_ENABLE = _UxGT("Abilita shaping @");
- LSTR MSG_SHAPING_DISABLE = _UxGT("Disabil. shaping @");
- LSTR MSG_SHAPING_FREQ = _UxGT("Frequenza @");
- LSTR MSG_SHAPING_ZETA = _UxGT("Smorzamento @");
+ LSTR MSG_SHAPING_ENABLE_N = _UxGT("Abilita shaping @");
+ LSTR MSG_SHAPING_DISABLE_N = _UxGT("Disabil. shaping @");
+ LSTR MSG_SHAPING_FREQ_N = _UxGT("Frequenza @");
+ LSTR MSG_SHAPING_ZETA_N = _UxGT("Smorzamento @");
LSTR MSG_SHAPING_A_FREQ = _UxGT("Frequenza ") STR_A; // ProUI
LSTR MSG_SHAPING_B_FREQ = _UxGT("Frequenza ") STR_B; // ProUI
LSTR MSG_SHAPING_C_FREQ = _UxGT("Frequenza ") STR_C; // ProUI
diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h
index aef39952cf39..9d6509d70d02 100644
--- a/Marlin/src/lcd/language/language_ru.h
+++ b/Marlin/src/lcd/language/language_ru.h
@@ -721,10 +721,10 @@ namespace LanguageNarrow_ru {
LSTR MSG_MPC_AMBIENT_XFER_COEFF_FAN = _UxGT("Коэфф.кулера");
LSTR MSG_MPC_AMBIENT_XFER_COEFF_FAN_E = _UxGT("Коэфф.кулер *");
LSTR MSG_INPUT_SHAPING = _UxGT("Input Shaping");
- LSTR MSG_SHAPING_ENABLE = _UxGT("Включить шейпинг @");
- LSTR MSG_SHAPING_DISABLE = _UxGT("Выключить шейпинг @");
- LSTR MSG_SHAPING_FREQ = _UxGT("@ частота");
- LSTR MSG_SHAPING_ZETA = _UxGT("@ подавление");
+ LSTR MSG_SHAPING_ENABLE_N = _UxGT("Включить шейпинг @");
+ LSTR MSG_SHAPING_DISABLE_N = _UxGT("Выключить шейпинг @");
+ LSTR MSG_SHAPING_FREQ_N = _UxGT("@ частота");
+ LSTR MSG_SHAPING_ZETA_N = _UxGT("@ подавление");
LSTR MSG_FILAMENT_EN = _UxGT("Филамент *");
LSTR MSG_SEGMENTS_PER_SECOND = _UxGT("Сегментов/сек");
LSTR MSG_DRAW_MIN_X = _UxGT("Рисовать мин X");
diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h
index b3a9e3368ef1..50729dfbd046 100644
--- a/Marlin/src/lcd/language/language_sk.h
+++ b/Marlin/src/lcd/language/language_sk.h
@@ -392,10 +392,10 @@ namespace LanguageNarrow_sk {
LSTR MSG_A_RETRACT = _UxGT("A-retrakt");
LSTR MSG_A_TRAVEL = _UxGT("A-prejazd");
LSTR MSG_INPUT_SHAPING = _UxGT("Tvarov. vstupu");
- LSTR MSG_SHAPING_ENABLE = _UxGT("Povol. tvarov. @");
- LSTR MSG_SHAPING_DISABLE = _UxGT("Zakáz. tvarov. @");
- LSTR MSG_SHAPING_FREQ = _UxGT("Frekvencia @");
- LSTR MSG_SHAPING_ZETA = _UxGT("Tlmenie @");
+ LSTR MSG_SHAPING_ENABLE_N = _UxGT("Povol. tvarov. @");
+ LSTR MSG_SHAPING_DISABLE_N = _UxGT("Zakáz. tvarov. @");
+ LSTR MSG_SHAPING_FREQ_N = _UxGT("Frekvencia @");
+ LSTR MSG_SHAPING_ZETA_N = _UxGT("Tlmenie @");
LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Max. frekvencia");
LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Min. posun");
LSTR MSG_STEPS_PER_MM = _UxGT("Kroky/mm");
diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h
index 830d0adaa41d..e22a4c75d0f9 100644
--- a/Marlin/src/lcd/language/language_tr.h
+++ b/Marlin/src/lcd/language/language_tr.h
@@ -397,10 +397,10 @@ namespace LanguageNarrow_tr {
LSTR MSG_A_RETRACT = _UxGT("G.Çekme Hızı");
LSTR MSG_A_TRAVEL = _UxGT("Gezinme Hızı");
LSTR MSG_INPUT_SHAPING = _UxGT("Input Shaping");
- LSTR MSG_SHAPING_ENABLE = _UxGT("@ Biçimlemeyi Aç");
- LSTR MSG_SHAPING_DISABLE = _UxGT("@ Biçimlemeyi Kapat");
- LSTR MSG_SHAPING_FREQ = _UxGT("@ frekans");
- LSTR MSG_SHAPING_ZETA = _UxGT("@ sönümleme");
+ LSTR MSG_SHAPING_ENABLE_N = _UxGT("@ Biçimlemeyi Aç");
+ LSTR MSG_SHAPING_DISABLE_N = _UxGT("@ Biçimlemeyi Kapat");
+ LSTR MSG_SHAPING_FREQ_N = _UxGT("@ frekans");
+ LSTR MSG_SHAPING_ZETA_N = _UxGT("@ sönümleme");
LSTR MSG_SHAPING_A_FREQ = STR_A _UxGT(" frekansı"); // ProUI
LSTR MSG_SHAPING_B_FREQ = STR_B _UxGT(" frekansı"); // ProUI
LSTR MSG_SHAPING_C_FREQ = STR_C _UxGT(" frekansı"); // ProUI
diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp
index e1072f3ee41c..2724b1d54e9f 100644
--- a/Marlin/src/lcd/menu/menu_advanced.cpp
+++ b/Marlin/src/lcd/menu/menu_advanced.cpp
@@ -559,20 +559,20 @@ void menu_backlash();
BACK_ITEM(MSG_ADVANCED_SETTINGS);
// M593 F Frequency and D Damping ratio
- #define SHAPING_MENU_FOR_AXIS(AXIS) \
- editable.decimal = stepper.get_shaping_frequency(AXIS); \
- if (editable.decimal) { \
- ACTION_ITEM_N(AXIS, MSG_SHAPING_DISABLE, []{ stepper.set_shaping_frequency(AXIS, 0.0f); ui.refresh(); }); \
- EDIT_ITEM_FAST_N(float41, AXIS, MSG_SHAPING_FREQ, &editable.decimal, min_frequency, 200.0f, []{ stepper.set_shaping_frequency(AXIS, editable.decimal); }); \
- editable.decimal = stepper.get_shaping_damping_ratio(AXIS); \
- EDIT_ITEM_FAST_N(float42_52, AXIS, MSG_SHAPING_ZETA, &editable.decimal, 0.0f, 1.0f, []{ stepper.set_shaping_damping_ratio(AXIS, editable.decimal); }); \
- } \
- else \
- ACTION_ITEM_N(AXIS, MSG_SHAPING_ENABLE, []{ stepper.set_shaping_frequency(AXIS, (SHAPING_FREQ_X) ?: (SHAPING_MIN_FREQ)); ui.refresh(); });
-
- TERN_(INPUT_SHAPING_X, SHAPING_MENU_FOR_AXIS(X_AXIS))
- TERN_(INPUT_SHAPING_Y, SHAPING_MENU_FOR_AXIS(Y_AXIS))
- TERN_(INPUT_SHAPING_Z, SHAPING_MENU_FOR_AXIS(Z_AXIS))
+ #define SHAPING_MENU_FOR_AXIS(A) \
+ editable.decimal = stepper.get_shaping_frequency(_AXIS(A)); \
+ if (editable.decimal) { \
+ ACTION_ITEM_N(_AXIS(A), MSG_SHAPING_DISABLE_N, []{ stepper.set_shaping_frequency(_AXIS(A), 0.0f); ui.refresh(); }); \
+ EDIT_ITEM_FAST_N(float41, _AXIS(A), MSG_SHAPING_FREQ_N, &editable.decimal, min_frequency, 200.0f, []{ stepper.set_shaping_frequency(_AXIS(A), editable.decimal); }); \
+ editable.decimal = stepper.get_shaping_damping_ratio(_AXIS(A)); \
+ EDIT_ITEM_FAST_N(float42_52, _AXIS(A), MSG_SHAPING_ZETA_N, &editable.decimal, 0.0f, 1.0f, []{ stepper.set_shaping_damping_ratio(_AXIS(A), editable.decimal); }); \
+ } \
+ else \
+ ACTION_ITEM_N(_AXIS(A), MSG_SHAPING_ENABLE_N, []{ stepper.set_shaping_frequency(_AXIS(A), (SHAPING_FREQ_##A) ?: (SHAPING_MIN_FREQ)); ui.refresh(); });
+
+ TERN_(INPUT_SHAPING_X, SHAPING_MENU_FOR_AXIS(X))
+ TERN_(INPUT_SHAPING_Y, SHAPING_MENU_FOR_AXIS(Y))
+ TERN_(INPUT_SHAPING_Z, SHAPING_MENU_FOR_AXIS(Z))
END_MENU();
}
diff --git a/Marlin/src/lcd/menu/menu_cancelobject.cpp b/Marlin/src/lcd/menu/menu_cancelobject.cpp
index bcbd90ee3a60..f55a95feeae1 100644
--- a/Marlin/src/lcd/menu/menu_cancelobject.cpp
+++ b/Marlin/src/lcd/menu/menu_cancelobject.cpp
@@ -53,13 +53,13 @@ static void lcd_cancel_object_confirm() {
}
void menu_cancelobject() {
- const int8_t ao = cancelable.active_object;
+ const int8_t ao = cancelable.state.active_object;
START_MENU();
BACK_ITEM(MSG_MAIN_MENU);
// Draw cancelable items in a loop
- for (int8_t i = -1; i < cancelable.object_count; i++) {
+ for (int8_t i = -1; i < cancelable.state.object_count; i++) {
if (i == ao) continue; // Active is drawn on -1 index
const int8_t j = i < 0 ? ao : i; // Active or index item
if (!cancelable.is_canceled(j)) { // Not canceled already?
diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp
index d7eeab3cb3d2..632c75629dba 100644
--- a/Marlin/src/lcd/menu/menu_configuration.cpp
+++ b/Marlin/src/lcd/menu/menu_configuration.cpp
@@ -410,17 +410,17 @@ void menu_advanced_settings();
#if ENABLED(MENUS_ALLOW_INCH_UNITS)
#define _EDIT_HOMING_FR(A) do{ \
+ const float minfr = MMS_TO_MMM(planner.settings.min_feedrate_mm_s); \
const float maxfr = MMS_TO_MMM(planner.settings.max_feedrate_mm_s[_AXIS(A)]); \
editable.decimal = A##_AXIS_UNIT(homing_feedrate_mm_m.A); \
- EDIT_ITEM(float5, MSG_HOMING_FEEDRATE_N, &editable.decimal, \
- A##_AXIS_UNIT(10), A##_AXIS_UNIT(maxfr), []{ \
+ EDIT_ITEM_FAST_N(float5, _AXIS(A), MSG_HOMING_FEEDRATE_N, &editable.decimal, \
+ A##_AXIS_UNIT(minfr), A##_AXIS_UNIT(maxfr), []{ \
homing_feedrate_mm_m.A = parser.axis_value_to_mm(_AXIS(A), editable.decimal); \
}); \
}while(0);
#else
- #define _EDIT_HOMING_FR(A) do{ \
- EDIT_ITEM(float5, MSG_HOMING_FEEDRATE_N, &homing_feedrate_mm_m.A, 10, MMS_TO_MMM(planner.settings.max_feedrate_mm_s[_AXIS(A)])); \
- }while(0);
+ #define _EDIT_HOMING_FR(A) \
+ EDIT_ITEM_FAST_N(float5, _AXIS(A), MSG_HOMING_FEEDRATE_N, &homing_feedrate_mm_m.A, MMS_TO_MMM(planner.settings.min_feedrate_mm_s), MMS_TO_MMM(planner.settings.max_feedrate_mm_s[_AXIS(A)]));
#endif
MAIN_AXIS_MAP(_EDIT_HOMING_FR);
diff --git a/Marlin/src/lcd/menu/menu_tmc.cpp b/Marlin/src/lcd/menu/menu_tmc.cpp
index c3503ede41cd..c708bb5fa2b3 100644
--- a/Marlin/src/lcd/menu/menu_tmc.cpp
+++ b/Marlin/src/lcd/menu/menu_tmc.cpp
@@ -90,7 +90,7 @@ void menu_tmc_current() {
#if ENABLED(HYBRID_THRESHOLD)
- #define TMC_EDIT_STORED_HYBRID_THRS(ST, STR) EDIT_ITEM_F(uint8, F(STR), &stepper##ST.stored.hybrid_thrs, 0, 255, []{ stepper##ST.refresh_hybrid_thrs(); });
+ #define TMC_EDIT_STORED_HYBRID_THRS(ST, STR) EDIT_ITEM_F(uint16_3, F(STR), &stepper##ST.stored.hybrid_thrs, 0, STEPPER_MAX_THRS(ST), []{ stepper##ST.refresh_hybrid_thrs(); });
void menu_tmc_hybrid_thrs() {
START_MENU();
diff --git a/Marlin/src/libs/numtostr.cpp b/Marlin/src/libs/numtostr.cpp
index 6f4e4a480bfb..b9503cb242cc 100644
--- a/Marlin/src/libs/numtostr.cpp
+++ b/Marlin/src/libs/numtostr.cpp
@@ -25,6 +25,8 @@
#include "../inc/MarlinConfigPre.h"
#include "../core/utility.h"
+#pragma GCC diagnostic ignored "-Wimplicit-fallthrough"
+
constexpr char DIGIT(const uint8_t n) { return '0' + n; }
template
diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp
index 42b4c8060b5c..630557180ba2 100644
--- a/Marlin/src/module/planner.cpp
+++ b/Marlin/src/module/planner.cpp
@@ -135,8 +135,8 @@ uint8_t Planner::delay_before_delivering; // Delay block delivery so initi
#if ENABLED(EDITABLE_STEPS_PER_UNIT)
float Planner::mm_per_step[DISTINCT_AXES]; // (mm) Millimeters per step
#else
- constexpr float PlannerSettings::axis_steps_per_mm[DISTINCT_AXES];
- constexpr float Planner::mm_per_step[DISTINCT_AXES];
+ constexpr float PlannerSettings::axis_steps_per_mm[DISTINCT_AXES],
+ Planner::mm_per_step[DISTINCT_AXES];
#endif
planner_settings_t Planner::settings; // Initialized by settings.load
@@ -179,8 +179,8 @@ uint32_t Planner::max_acceleration_steps_per_s2[DISTINCT_AXES]; // (steps/s^2) D
#endif
#if DISABLED(NO_VOLUMETRICS)
+ float Planner::volumetric_area_nominal = CIRCLE_AREA(float(DEFAULT_NOMINAL_FILAMENT_DIA) * 0.5f); // Nominal cross-sectional area
float Planner::filament_size[EXTRUDERS], // diameter of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder
- Planner::volumetric_area_nominal = CIRCLE_AREA(float(DEFAULT_NOMINAL_FILAMENT_DIA) * 0.5f), // Nominal cross-sectional area
Planner::volumetric_multiplier[EXTRUDERS]; // Reciprocal of cross-sectional area of filament (in mm^2). Pre-calculated to reduce computation in the planner
#endif
@@ -782,9 +782,9 @@ block_t* Planner::get_current_block() {
* sqrt(block->acceleration_steps_per_s2 / 2). This is ensured through
* minimum_planner_speed_sqr / min_entry_speed_sqr though note there's one
* exception in recalculate_trapezoids().
- **
+ *
* ############ VERY IMPORTANT ############
- * NOTE that the PRECONDITION to call this function is that the block is
+ * NOTE: The PRECONDITION to call this function is that the block is
* NOT BUSY and it is marked as RECALCULATE. That WARRANTIES the Stepper ISR
* is not and will not use the block while we modify it.
*/
@@ -1542,7 +1542,7 @@ void Planner::check_axes_activity() {
else if (z_full_fade >= z_fade_height) // Above the fade height?
raw.z = z_full_fade; // Nothing more to unapply.
else // Within the fade zone?
- raw.z = z_no_fade / (1.0f - z_correction * inverse_z_fade_height); // Unapply the faded Z offset
+ raw.z = z_no_fade / (1.0f - z_correction * inverse_z_fade_height); // Unapply the faded Z offset
#else
raw.z = z_no_fade;
#endif
@@ -1570,11 +1570,14 @@ void Planner::check_axes_activity() {
void Planner::quick_stop() {
- // Remove all the queued blocks. Note that this function is NOT
- // called from the Stepper ISR, so we must consider tail as readonly!
- // that is why we set head to tail - But there is a race condition that
- // must be handled: The tail could change between the read and the assignment
- // so this must be enclosed in a critical section
+ /**
+ * Remove all the queued blocks.
+ * NOTE: This function is NOT called from the Stepper ISR,
+ * so we must consider tail as readonly!
+ * That is why we set head to tail - But there is a race condition that
+ * must be handled: The tail could change between the read and the assignment
+ * so this must be enclosed in a critical section
+ */
const bool was_enabled = stepper.suspend();
@@ -1703,9 +1706,9 @@ void Planner::synchronize() { while (busy()) idle(); }
* @param target Target position in steps units
* @param target_float Target position in direct (mm, degrees) units.
* @param cart_dist_mm The pre-calculated move lengths for all axes, in mm
- * @param fr_mm_s (target) speed of the move
- * @param extruder target extruder
- * @param hints parameters to aid planner calculations
+ * @param fr_mm_s (Target) speed of the move
+ * @param extruder Target extruder
+ * @param hints Parameters to aid planner calculations
*
* @return true if movement was properly queued, false otherwise (if cleaning)
*/
@@ -1765,7 +1768,7 @@ bool Planner::_buffer_steps(const xyze_long_t &target
}
/**
- * @brief Populate a block in preparation for insertion
+ * @brief Populate a block in preparation for insertion.
* @details Populate the fields of a new linear movement block
* that will be added to the queue and processed soon
* by the Stepper ISR.
@@ -1774,9 +1777,9 @@ bool Planner::_buffer_steps(const xyze_long_t &target
* @param target Target position in steps units
* @param target_float Target position in native mm
* @param cart_dist_mm The pre-calculated move lengths for all axes, in mm
- * @param fr_mm_s (target) speed of the move
- * @param extruder target extruder
- * @param hints parameters to aid planner calculations
+ * @param fr_mm_s (Target) speed of the move
+ * @param extruder Target extruder
+ * @param hints Parameters to aid planner calculations
*
* @return true if movement is acceptable, false otherwise
*/
@@ -2195,9 +2198,11 @@ bool Planner::_populate_block(
const float inverse_millimeters = 1.0f / block->millimeters; // Inverse millimeters to remove multiple divides
- // Calculate inverse time for this move. No divide by zero due to previous checks.
- // Example: At 120mm/s a 60mm move involving XYZ axes takes 0.5s. So this will give 2.0.
- // Example 2: At 120°/s a 60° move involving only rotational axes takes 0.5s. So this will give 2.0.
+ /**
+ * Calculate inverse time for this move. No divide by zero due to previous checks.
+ * EXAMPLE: At 120mm/s a 60mm move involving XYZ axes takes 0.5s. So this will give 2.0.
+ * EXAMPLE: At 120°/s a 60° move involving only rotational axes takes 0.5s. So this will give 2.0.
+ */
float inverse_secs = inverse_millimeters * (
#if ALL(HAS_ROTATIONAL_AXES, INCH_MODE_SUPPORT)
/**
@@ -2766,8 +2771,8 @@ bool Planner::_populate_block(
} // _populate_block()
/**
- * @brief Add a block to the buffer that just updates the position
- * Supports LASER_SYNCHRONOUS_M106_M107 and LASER_POWER_SYNC power sync block buffer queueing.
+ * @brief Add a block to the buffer that just updates the position.
+ * @details Supports LASER_SYNCHRONOUS_M106_M107 and LASER_POWER_SYNC power sync block buffer queueing.
*
* @param sync_flag The sync flag to set, determining the type of sync the block will do
*/
@@ -2813,16 +2818,15 @@ void Planner::buffer_sync_block(const BlockFlagBit sync_flag/*=BLOCK_BIT_SYNC_PO
} // buffer_sync_block()
/**
- * @brief Add a single linear movement
- *
- * @description Add a new linear movement to the buffer in axis units.
- * Leveling and kinematics should be applied before calling this.
+ * @brief Add a single linear movement.
+ * @details Add a new linear movement to the buffer in axis units.
+ * Leveling and kinematics should be applied before calling this.
*
* @param abce Target position in mm and/or degrees
* @param cart_dist_mm The pre-calculated move lengths for all axes, in mm
- * @param fr_mm_s (target) speed of the move
- * @param extruder optional target extruder (otherwise active_extruder)
- * @param hints optional parameters to aid planner calculations
+ * @param fr_mm_s (Target) speed of the move
+ * @param extruder Optional target extruder (otherwise active_extruder)
+ * @param hints Optional parameters to aid planner calculations
*
* @return false if no segment was queued due to cleaning, cold extrusion, full queue, etc.
*/
@@ -2867,7 +2871,7 @@ bool Planner::buffer_segment(const abce_pos_t &abce
#if HAS_EXTRUDERS
// DRYRUN prevents E moves from taking place
- if (DEBUGGING(DRYRUN) || TERN0(CANCEL_OBJECTS, cancelable.skipping)) {
+ if (DEBUGGING(DRYRUN) || TERN0(CANCEL_OBJECTS, cancelable.state.skipping)) {
position.e = target.e;
TERN_(HAS_POSITION_FLOAT, position_float.e = abce.e);
}
@@ -2944,14 +2948,14 @@ bool Planner::buffer_segment(const abce_pos_t &abce
} // buffer_segment()
/**
- * Add a new linear movement to the buffer.
- * The target is cartesian. It's translated to
- * delta/scara if needed.
+ * @brief Add a new linear movement to the buffer.
+ * @details The target is cartesian. It's translated to
+ * delta/scara if needed.
*
- * cart - target position in mm or degrees
- * fr_mm_s - (target) speed of the move (mm/s)
- * extruder - optional target extruder (otherwise active_extruder)
- * hints - optional parameters to aid planner calculations
+ * @param cart Target position in mm or degrees
+ * @param fr_mm_s (Target) speed of the move (mm/s)
+ * @param extruder Optional target extruder (otherwise active_extruder)
+ * @param hints Optional parameters to aid planner calculations
*/
bool Planner::buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s
, const uint8_t extruder/*=active_extruder*/
@@ -3233,7 +3237,7 @@ inline void limit_and_warn(float &val, const AxisEnum axis, FSTR_P const setting
}
/**
- * For the specified 'axis' set the Maximum Acceleration to the given value (mm/s^2)
+ * For the specified 'axis' set the Maximum Acceleration to the given value (mm/s^2).
* The value may be limited with warning feedback, if configured.
* Calls refresh_acceleration_rates to precalculate planner terms in steps.
*
@@ -3257,7 +3261,7 @@ void Planner::set_max_acceleration(const AxisEnum axis, float inMaxAccelMMS2) {
}
/**
- * For the specified 'axis' set the Maximum Feedrate to the given value (mm/s)
+ * For the specified 'axis' set the Maximum Feedrate to the given value (mm/s).
* The value may be limited with warning feedback, if configured.
*
* This hard limit is applied as a block is being added to the planner queue.
@@ -3279,7 +3283,7 @@ void Planner::set_max_feedrate(const AxisEnum axis, float inMaxFeedrateMMS) {
#if ENABLED(CLASSIC_JERK)
/**
- * For the specified 'axis' set the Maximum Jerk (instant change) to the given value (mm/s)
+ * For the specified 'axis' set the Maximum Jerk (instant change) to the given value (mm/s).
* The value may be limited with warning feedback, if configured.
*
* This hard limit is applied (to the block start speed) as the block is being added to the planner queue.
@@ -3310,7 +3314,7 @@ void Planner::set_max_feedrate(const AxisEnum axis, float inMaxFeedrateMMS) {
uint16_t Planner::block_buffer_runtime() {
#ifdef __AVR__
// Protect the access to the variable. Only required for AVR, as
- // any 32bit CPU offers atomic access to 32bit variables
+ // any 32bit CPU offers atomic access to 32bit variables
const bool was_enabled = stepper.suspend();
#endif
@@ -3332,7 +3336,7 @@ void Planner::set_max_feedrate(const AxisEnum axis, float inMaxFeedrateMMS) {
void Planner::clear_block_buffer_runtime() {
#ifdef __AVR__
// Protect the access to the variable. Only required for AVR, as
- // any 32bit CPU offers atomic access to 32bit variables
+ // any 32bit CPU offers atomic access to 32bit variables
const bool was_enabled = stepper.suspend();
#endif
diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h
index 5b37d7fdda5b..64381350cc1c 100644
--- a/Marlin/src/module/planner.h
+++ b/Marlin/src/module/planner.h
@@ -337,8 +337,8 @@ constexpr uint8_t block_inc_mod(const uint8_t v1, const uint8_t v2) {
#endif
typedef struct PlannerSettings {
- uint32_t max_acceleration_mm_per_s2[DISTINCT_AXES], // (mm/s^2) M201 XYZE
- min_segment_time_us; // (µs) M205 B
+ uint32_t max_acceleration_mm_per_s2[DISTINCT_AXES]; // (mm/s^2) M201 XYZE
+ uint32_t min_segment_time_us; // (µs) M205 B
// (steps) M92 XYZE - Steps per millimeter
#if ENABLED(EDITABLE_STEPS_PER_UNIT)
@@ -356,12 +356,12 @@ typedef struct PlannerSettings {
#undef _DLIM
#endif
- feedRate_t max_feedrate_mm_s[DISTINCT_AXES]; // (mm/s) M203 XYZE - Max speeds
- float acceleration, // (mm/s^2) M204 S - Normal acceleration. DEFAULT ACCELERATION for all printing moves.
- retract_acceleration, // (mm/s^2) M204 R - Retract acceleration. Filament pull-back and push-forward while standing still in the other axes
- travel_acceleration; // (mm/s^2) M204 T - Travel acceleration. DEFAULT ACCELERATION for all NON printing moves.
- feedRate_t min_feedrate_mm_s, // (mm/s) M205 S - Minimum linear feedrate
- min_travel_feedrate_mm_s; // (mm/s) M205 T - Minimum travel feedrate
+ feedRate_t max_feedrate_mm_s[DISTINCT_AXES]; // (mm/s) M203 XYZE - Max speeds
+ float acceleration, // (mm/s^2) M204 S - Normal acceleration. DEFAULT ACCELERATION for all printing moves.
+ retract_acceleration, // (mm/s^2) M204 R - Retract acceleration. Filament pull-back and push-forward while standing still in the other axes
+ travel_acceleration; // (mm/s^2) M204 T - Travel acceleration. DEFAULT ACCELERATION for all NON printing moves.
+ feedRate_t min_feedrate_mm_s, // (mm/s) M205 S - Minimum linear feedrate
+ min_travel_feedrate_mm_s; // (mm/s) M205 T - Minimum travel feedrate
} planner_settings_t;
#if ENABLED(IMPROVE_HOMING_RELIABILITY)
@@ -460,8 +460,8 @@ class Planner {
#endif
#if DISABLED(NO_VOLUMETRICS)
+ static float volumetric_area_nominal; // (mm^3) Nominal cross-sectional area
static float filament_size[EXTRUDERS], // (mm) Diameter of filament, typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder
- volumetric_area_nominal, // (mm^3) Nominal cross-sectional area
volumetric_multiplier[EXTRUDERS]; // (1/mm^2) Reciprocal of cross-sectional area of filament. Pre-calculated to reduce computation in the planner
// May be auto-adjusted by a filament width sensor
#endif
@@ -811,11 +811,12 @@ class Planner {
FORCE_INLINE static uint8_t moves_free() { return (BLOCK_BUFFER_SIZE) - 1 - movesplanned(); }
/**
- * Planner::get_next_free_block
+ * @fn Planner::get_next_free_block
*
- * - Get the next head indices (passed by reference)
- * - Wait for the number of spaces to open up in the planner
- * - Return the first head block
+ * @details Get the next head indices (passed by reference)
+ * Wait for the number of spaces to open up in the planner
+ *
+ * @return The first head block
*/
FORCE_INLINE static block_t* get_next_free_block(uint8_t &next_buffer_head, const uint8_t count=1) {
@@ -828,16 +829,18 @@ class Planner {
}
/**
- * Planner::_buffer_steps
+ * @fn Planner::_buffer_steps
*
- * Add a new linear movement to the buffer (in terms of steps).
+ * @brief Add a new linear movement to the planner queue (in terms of steps).
*
- * target - target position in steps units
- * fr_mm_s - (target) speed of the move
- * extruder - target extruder
- * hints - parameters to aid planner calculations
+ * @param target Target position in steps units
+ * @param target_float Target position in direct (mm, degrees) units.
+ * @param cart_dist_mm The pre-calculated move lengths for all axes, in mm
+ * @param fr_mm_s (Target) speed of the move
+ * @param extruder Target extruder
+ * @param hints Parameters to aid planner calculations
*
- * Returns true if movement was buffered, false otherwise
+ * @return true if movement was properly queued, false otherwise (if cleaning)
*/
static bool _buffer_steps(const xyze_long_t &target
OPTARG(HAS_POSITION_FLOAT, const xyze_pos_t &target_float)
@@ -846,7 +849,9 @@ class Planner {
);
/**
- * @brief Populate a block in preparation for insertion
+ * @fn Planner::_populate_block
+ *
+ * @brief Populate a block in preparation for insertion.
* @details Populate the fields of a new linear movement block
* that will be added to the queue and processed soon
* by the Stepper ISR.
@@ -855,9 +860,9 @@ class Planner {
* @param target Target position in steps units
* @param target_float Target position in native mm
* @param cart_dist_mm The pre-calculated move lengths for all axes, in mm
- * @param fr_mm_s (target) speed of the move
- * @param extruder target extruder
- * @param hints parameters to aid planner calculations
+ * @param fr_mm_s (Target) speed of the move
+ * @param extruder Target extruder
+ * @param hints Parameters to aid planner calculations
*
* @return true if movement is acceptable, false otherwise
*/
@@ -869,31 +874,31 @@ class Planner {
);
/**
- * Planner::buffer_sync_block
- * Add a block to the buffer that just updates the position
- * @param sync_flag sets a condition bit to process additional items
- * such as sync fan pwm or sync M3/M4 laser power into a queued block
+ * @fn Planner::buffer_sync_block
+ *
+ * @brief Add a block to the buffer that just updates the position.
+ * @details Supports LASER_SYNCHRONOUS_M106_M107 and LASER_POWER_SYNC power sync block buffer queueing.
+ *
+ * @param sync_flag The sync flag to set, determining the type of sync the block will do
+ * Sets a condition bit to process additional items such as sync fan pwm
+ * or sync M3/M4 laser power into a queued block
*/
- static void buffer_sync_block(const BlockFlagBit flag=BLOCK_BIT_SYNC_POSITION);
-
- #if IS_KINEMATIC
- private:
-
- // Allow do_homing_move to access internal functions, such as buffer_segment.
- friend void do_homing_move(const AxisEnum, const float, const feedRate_t, const bool);
- #endif
+ static void buffer_sync_block(const BlockFlagBit flag=BLOCK_BIT_SYNC_POSITION);
/**
- * Planner::buffer_segment
+ * @fn Planner::buffer_segment
*
- * Add a new linear movement to the buffer in axis units.
+ * @brief Add a single linear movement.
+ * @details Add a new linear movement to the buffer in axis units.
+ * Leveling and kinematics should be applied before calling this.
*
- * Leveling and kinematics should be applied ahead of calling this.
+ * @param abce Target position in mm and/or degrees
+ * @param cart_dist_mm The pre-calculated move lengths for all axes, in mm
+ * @param fr_mm_s (Target) speed of the move
+ * @param extruder Optional target extruder (otherwise active_extruder)
+ * @param hints Optional parameters to aid planner calculations
*
- * a,b,c,e - target positions in mm and/or degrees
- * fr_mm_s - (target) speed of the move
- * extruder - optional target extruder (otherwise active_extruder)
- * hints - optional parameters to aid planner calculations
+ * @return false if no segment was queued due to cleaning, cold extrusion, full queue, etc...
*/
static bool buffer_segment(const abce_pos_t &abce
OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm)
@@ -902,17 +907,19 @@ class Planner {
, const PlannerHints &hints=PlannerHints()
);
- public:
-
/**
- * Add a new linear movement to the buffer.
- * The target is cartesian. It's translated to
- * delta/scara if needed.
+ * @fn Planner::buffer_line
+ *
+ * @brief Add a new linear movement to the buffer.
+ * @details The target is cartesian. It's translated to
+ * delta/scara if needed.
+ *
+ * @param cart Target position in mm or degrees
+ * @param fr_mm_s (Target) speed of the move (mm/s)
+ * @param extruder Optional target extruder (otherwise active_extruder)
+ * @param hints Optional parameters to aid planner calculations
*
- * cart - target position in mm or degrees
- * fr_mm_s - (target) speed of the move (mm/s)
- * extruder - optional target extruder (otherwise active_extruder)
- * hints - optional parameters to aid planner calculations
+ * @return false if no segment was queued due to cleaning, cold extrusion, full queue, etc...
*/
static bool buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s
, const uint8_t extruder=active_extruder
@@ -1090,6 +1097,11 @@ class Planner {
static void recalculate(const_float_t safe_exit_speed_sqr);
+ #if IS_KINEMATIC
+ // Allow do_homing_move to access internal functions, such as buffer_segment.
+ friend void do_homing_move(const AxisEnum, const float, const feedRate_t, const bool);
+ #endif
+
#if HAS_JUNCTION_DEVIATION
FORCE_INLINE static void normalize_junction_vector(xyze_float_t &vector) {
diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp
index c6df105aa8b1..96295d7db586 100644
--- a/Marlin/src/module/temperature.cpp
+++ b/Marlin/src/module/temperature.cpp
@@ -3466,13 +3466,14 @@ void Temperature::disable_all_heaters() {
#endif // SINGLENOZZLE_STANDBY_TEMP || SINGLENOZZLE_STANDBY_FAN
#if HAS_MAX_TC
-
typedef TERN(HAS_MAX31855, uint32_t, uint16_t) max_tc_temp_t;
#ifndef THERMOCOUPLE_MAX_ERRORS
#define THERMOCOUPLE_MAX_ERRORS 15
#endif
+#endif
+#if TEMP_SENSOR_IS_MAX_TC(0) || TEMP_SENSOR_IS_MAX_TC(1) || TEMP_SENSOR_IS_MAX_TC(2)
/**
* @brief Read MAX Thermocouple temperature.
*
@@ -3729,7 +3730,7 @@ void Temperature::disable_all_heaters() {
#endif
// Set thermocouple above max temperature (TMAX)
- max_tc_temp = TEMP_SENSOR_BED_MAX_TC_TMAX << (BED_MAX_TC_DISCARD_BITS + 1);
+ max_tc_temp = max_tc_temp_t(TEMP_SENSOR_BED_MAX_TC_TMAX) << (BED_MAX_TC_DISCARD_BITS + 1);
}
}
else {
diff --git a/Marlin/src/pins/esp32/pins_FYSETC_E4.h b/Marlin/src/pins/esp32/pins_FYSETC_E4.h
index 4bcffb545ee0..4c31dfc1cec1 100644
--- a/Marlin/src/pins/esp32/pins_FYSETC_E4.h
+++ b/Marlin/src/pins/esp32/pins_FYSETC_E4.h
@@ -42,16 +42,13 @@
//
// TMC2209 stepper drivers
//
-
- //
- // Hardware serial 1
- //
#define X_HARDWARE_SERIAL Serial1
#define Y_HARDWARE_SERIAL Serial1
#define Z_HARDWARE_SERIAL Serial1
#define E0_HARDWARE_SERIAL Serial1
-
- #define TMC_BAUD_RATE 115200
+ #ifndef TMC_BAUD_RATE
+ #define TMC_BAUD_RATE 115200
+ #endif
#endif
/**
diff --git a/Marlin/src/pins/gd32f1/pins_SOVOL_V131.h b/Marlin/src/pins/gd32f1/pins_SOVOL_V131.h
index 2f6dd12c493b..f8a279c11eb4 100644
--- a/Marlin/src/pins/gd32f1/pins_SOVOL_V131.h
+++ b/Marlin/src/pins/gd32f1/pins_SOVOL_V131.h
@@ -51,16 +51,9 @@
*/
#define X_SERIAL_TX_PIN PC1
- #define X_SERIAL_RX_PIN PC1
-
#define Y_SERIAL_TX_PIN PC0
- #define Y_SERIAL_RX_PIN PC0
-
#define Z_SERIAL_TX_PIN PA15
- #define Z_SERIAL_RX_PIN PA15
-
#define E0_SERIAL_TX_PIN PC14
- #define E0_SERIAL_RX_PIN PC14
// Default TMC slave addresses
#ifndef X_SLAVE_ADDRESS
diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h
index 6345001b118b..2de1e459e1e6 100644
--- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h
+++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h
@@ -234,19 +234,10 @@
//#define E4_HARDWARE_SERIAL Serial1
#define X_SERIAL_TX_PIN P1_10
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN P1_09
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN P1_08
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN P1_04
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN P1_01
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h
index e6a2abc0f0f0..f38cab692ec2 100644
--- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h
+++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h
@@ -173,7 +173,6 @@
#define E2_CS_PIN EXP1_06_PIN
#if HAS_TMC_UART
#define E2_SERIAL_TX_PIN EXP1_06_PIN
- #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN
#endif
#endif
@@ -186,7 +185,6 @@
#define E3_CS_PIN EXP1_04_PIN
#if HAS_TMC_UART
#define E3_SERIAL_TX_PIN EXP1_04_PIN
- #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN
#endif
#else
#define E3_ENABLE_PIN EXP2_07_PIN
@@ -201,7 +199,6 @@
#define E4_CS_PIN EXP1_02_PIN
#if HAS_TMC_UART
#define E4_SERIAL_TX_PIN EXP1_02_PIN
- #define E4_SERIAL_RX_PIN E4_SERIAL_TX_PIN
#endif
#else
#define E4_ENABLE_PIN EXP2_07_PIN
diff --git a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h
index f785d3b7378c..4cb8a01a20f0 100644
--- a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h
+++ b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h
@@ -87,22 +87,11 @@
//
#if HAS_TMC_UART
#define X_SERIAL_TX_PIN P1_00
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN P1_09
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN P1_16
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN P0_04
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN P2_02
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
-
#define E2_SERIAL_TX_PIN P2_06
- #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h
index 6ee1f116599e..9ca1fb9555e0 100644
--- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h
+++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h
@@ -124,30 +124,18 @@
#ifndef X_SERIAL_TX_PIN
#define X_SERIAL_TX_PIN P0_01
#endif
- #ifndef X_SERIAL_RX_PIN
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
- #endif
#ifndef Y_SERIAL_TX_PIN
#define Y_SERIAL_TX_PIN P0_00
#endif
- #ifndef Y_SERIAL_RX_PIN
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
- #endif
#ifndef Z_SERIAL_TX_PIN
#define Z_SERIAL_TX_PIN P2_13
#endif
- #ifndef Z_SERIAL_RX_PIN
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
- #endif
#ifndef E0_SERIAL_TX_PIN
#define E0_SERIAL_TX_PIN P2_08
#endif
- #ifndef E0_SERIAL_RX_PIN
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
- #endif
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h
index 074ee067a69b..4156fd57079e 100644
--- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h
+++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h
@@ -144,19 +144,10 @@
*/
#define X_SERIAL_TX_PIN P1_01
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN P1_10
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN P1_17
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN P0_05
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN P0_22
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/lpc1769/pins_FLY_CDY.h b/Marlin/src/pins/lpc1769/pins_FLY_CDY.h
index 9b22214a7a1c..5a6fd050ed3f 100644
--- a/Marlin/src/pins/lpc1769/pins_FLY_CDY.h
+++ b/Marlin/src/pins/lpc1769/pins_FLY_CDY.h
@@ -107,22 +107,11 @@
#if HAS_TMC_UART
#define X_SERIAL_TX_PIN P1_04
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN P1_10
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN P1_16
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN P4_28
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN P2_12
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
-
#define E2_SERIAL_TX_PIN P0_10
- #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h
index 64abf5212f66..ecddbd2c6e43 100644
--- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h
+++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h
@@ -36,23 +36,14 @@
#include "../lpc1768/pins_MKS_SBASE.h"
#if HAS_TMC_UART
- /**
- * TMC2208/TMC2209 stepper drivers
- */
+ //
+ // TMC2208/TMC2209 stepper drivers
+ //
#define X_SERIAL_TX_PIN P1_22 // J8-2
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN P1_23 // J8-3
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN P2_12 // J8-4
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN P2_11 // J8-5
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN P4_28 // J8-6
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h
index aec4240276e7..5d7a703015d9 100644
--- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h
+++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h
@@ -186,19 +186,10 @@
//#define E4_HARDWARE_SERIAL Serial1
#define X_SERIAL_TX_PIN P1_01
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN P1_08
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN P1_10
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN P1_15
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN P1_17
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/lpc1769/pins_XTLW_CLIMBER_8TH_LPC.h b/Marlin/src/pins/lpc1769/pins_XTLW_CLIMBER_8TH_LPC.h
index 17089b8fea34..f5a23ec5fb78 100644
--- a/Marlin/src/pins/lpc1769/pins_XTLW_CLIMBER_8TH_LPC.h
+++ b/Marlin/src/pins/lpc1769/pins_XTLW_CLIMBER_8TH_LPC.h
@@ -99,25 +99,12 @@
#endif
#if HAS_TMC_UART
-
#define X_SERIAL_TX_PIN P1_04
- #define X_SERIAL_RX_PIN P1_04
-
#define X2_SERIAL_TX_PIN P0_10
- #define X2_SERIAL_RX_PIN P0_10
-
#define Y_SERIAL_TX_PIN P1_10
- #define Y_SERIAL_RX_PIN P1_10
-
#define Z_SERIAL_TX_PIN P1_16
- #define Z_SERIAL_RX_PIN P1_16
-
#define E0_SERIAL_TX_PIN P4_28
- #define E0_SERIAL_RX_PIN P4_28
-
#define E1_SERIAL_TX_PIN P2_12
- #define E1_SERIAL_RX_PIN P2_12
-
#endif
//
diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h
index a8d97ecd233f..e70a70b51835 100644
--- a/Marlin/src/pins/pins.h
+++ b/Marlin/src/pins/pins.h
@@ -336,6 +336,8 @@
#include "mega/pins_GT2560_V4.h" // ATmega2560 env:mega2560
#elif MB(GT2560_V4_A20)
#include "mega/pins_GT2560_V4_A20.h" // ATmega2560 env:mega2560
+#elif MB(GT2560_V41B)
+ #include "mega/pins_GT2560_V41b.h" // ATmega2560 env:mega2560ext
#elif MB(EINSTART_S)
#include "mega/pins_EINSTART-S.h" // ATmega2560, ATmega1280 env:mega2560ext env:mega1280
#elif MB(WANHAO_ONEPLUS)
@@ -360,8 +362,6 @@
#include "mega/pins_PROTONEER_CNC_SHIELD_V3.h" // ATmega2560 env:mega2560
#elif MB(WEEDO_62A)
#include "mega/pins_WEEDO_62A.h" // ATmega2560 env:mega2560
-#elif MB(GT2560_V41B)
- #include "mega/pins_GT2560_V41b.h" // ATmega2560 env:mega2560ext
//
// ATmega1281, ATmega2561
@@ -938,6 +938,15 @@
#elif MB(CREALITY_ENDER2P_V24S4)
#include "hc32f4/pins_CREALITY_ENDER2P_V24S4.h" // HC32F460 env:HC32F460C_e2p24s4
+//
+// Raspberry Pi RP2040
+//
+
+#elif MB(RP2040)
+ #include "rp2040/pins_RP2040.h" // RP2040 env:RP2040
+#elif MB(BTT_SKR_PICO)
+ #include "rp2040/pins_BTT_SKR_Pico.h" // RP2040 env:SKR_Pico env:SKR_Pico_UART
+
//
// Custom board (with custom PIO env)
//
diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h
index 6d3ccbd8c651..2372382a3407 100644
--- a/Marlin/src/pins/pinsDebug_list.h
+++ b/Marlin/src/pins/pinsDebug_list.h
@@ -161,6 +161,11 @@
REPORT_NAME_ANALOG(__LINE__, TEMP_BOARD_PIN)
#endif
#endif
+#if PIN_EXISTS(TEMP_SOC)
+ #if ANALOG_OK(TEMP_SOC_PIN)
+ REPORT_NAME_ANALOG(__LINE__, TEMP_SOC_PIN)
+ #endif
+#endif
#if PIN_EXISTS(ADC_KEYPAD)
#if ANALOG_OK(ADC_KEYPAD_PIN)
REPORT_NAME_ANALOG(__LINE__, ADC_KEYPAD_PIN)
diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h
index f9814b45d14b..1d3b0ebcce2a 100644
--- a/Marlin/src/pins/pins_postprocess.h
+++ b/Marlin/src/pins/pins_postprocess.h
@@ -307,74 +307,167 @@
#define E7_CS_PIN -1
#endif
+// If only TX is defined, use the same pin for RX
+#if HAS_TMC_UART
+ #if !defined(X_SERIAL_RX_PIN) && PIN_EXISTS(X_SERIAL_TX)
+ #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
+ #endif
+ #if !defined(X2_SERIAL_RX_PIN) && PIN_EXISTS(X2_SERIAL_TX)
+ #define X2_SERIAL_RX_PIN X2_SERIAL_TX_PIN
+ #endif
+ #if !defined(Y_SERIAL_RX_PIN) && PIN_EXISTS(Y_SERIAL_TX)
+ #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
+ #endif
+ #if !defined(Y2_SERIAL_RX_PIN) && PIN_EXISTS(Y2_SERIAL_TX)
+ #define Y2_SERIAL_RX_PIN Y2_SERIAL_TX_PIN
+ #endif
+ #if !defined(Z_SERIAL_RX_PIN) && PIN_EXISTS(Z_SERIAL_TX)
+ #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
+ #endif
+ #if !defined(Z2_SERIAL_RX_PIN) && PIN_EXISTS(Z2_SERIAL_TX)
+ #define Z2_SERIAL_RX_PIN Z2_SERIAL_TX_PIN
+ #endif
+ #if !defined(Z3_SERIAL_RX_PIN) && PIN_EXISTS(Z3_SERIAL_TX)
+ #define Z3_SERIAL_RX_PIN Z3_SERIAL_TX_PIN
+ #endif
+ #if !defined(Z4_SERIAL_RX_PIN) && PIN_EXISTS(Z4_SERIAL_TX)
+ #define Z4_SERIAL_RX_PIN Z4_SERIAL_TX_PIN
+ #endif
+ #if !defined(I_SERIAL_RX_PIN) && PIN_EXISTS(I_SERIAL_TX)
+ #define I_SERIAL_RX_PIN I_SERIAL_TX_PIN
+ #endif
+ #if !defined(J_SERIAL_RX_PIN) && PIN_EXISTS(J_SERIAL_TX)
+ #define J_SERIAL_RX_PIN J_SERIAL_TX_PIN
+ #endif
+ #if !defined(K_SERIAL_RX_PIN) && PIN_EXISTS(K_SERIAL_TX)
+ #define K_SERIAL_RX_PIN K_SERIAL_TX_PIN
+ #endif
+ #if !defined(U_SERIAL_RX_PIN) && PIN_EXISTS(U_SERIAL_TX)
+ #define U_SERIAL_RX_PIN U_SERIAL_TX_PIN
+ #endif
+ #if !defined(V_SERIAL_RX_PIN) && PIN_EXISTS(V_SERIAL_TX)
+ #define V_SERIAL_RX_PIN V_SERIAL_TX_PIN
+ #endif
+ #if !defined(W_SERIAL_RX_PIN) && PIN_EXISTS(W_SERIAL_TX)
+ #define W_SERIAL_RX_PIN W_SERIAL_TX_PIN
+ #endif
+ #if !defined(EX_SERIAL_RX_PIN) && PIN_EXISTS(EX_SERIAL_TX)
+ #define EX_SERIAL_RX_PIN EX_SERIAL_TX_PIN
+ #endif
+ #if !defined(E0_SERIAL_RX_PIN) && PIN_EXISTS(E0_SERIAL_TX)
+ #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
+ #endif
+ #if !defined(E1_SERIAL_RX_PIN) && PIN_EXISTS(E1_SERIAL_TX)
+ #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
+ #endif
+ #if !defined(E2_SERIAL_RX_PIN) && PIN_EXISTS(E2_SERIAL_TX)
+ #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN
+ #endif
+ #if !defined(E3_SERIAL_RX_PIN) && PIN_EXISTS(E3_SERIAL_TX)
+ #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN
+ #endif
+ #if !defined(E4_SERIAL_RX_PIN) && PIN_EXISTS(E4_SERIAL_TX)
+ #define E4_SERIAL_RX_PIN E4_SERIAL_TX_PIN
+ #endif
+ #if !defined(E5_SERIAL_RX_PIN) && PIN_EXISTS(E5_SERIAL_TX)
+ #define E5_SERIAL_RX_PIN E5_SERIAL_TX_PIN
+ #endif
+ #if !defined(E6_SERIAL_RX_PIN) && PIN_EXISTS(E6_SERIAL_TX)
+ #define E6_SERIAL_RX_PIN E6_SERIAL_TX_PIN
+ #endif
+ #if !defined(E7_SERIAL_RX_PIN) && PIN_EXISTS(E7_SERIAL_TX)
+ #define E7_SERIAL_RX_PIN E7_SERIAL_TX_PIN
+ #endif
+#endif
+
//
// Destroy stepper driver RX and TX pins when set to -1
+// Some RX depend on TX, so RX needs to be un-defined before TX
+// or it breaks "PIN_EXISTS(NAME_OF_UNDEF)".
//
-#if !PIN_EXISTS(Z2_SERIAL_TX)
- #undef Z2_SERIAL_TX_PIN
+#if !PIN_EXISTS(W_SERIAL_RX)
+ #undef W_SERIAL_RX_PIN
#endif
-#if !PIN_EXISTS(Z2_SERIAL_RX)
- #undef Z2_SERIAL_RX_PIN
+#if !PIN_EXISTS(W_SERIAL_TX)
+ #undef W_SERIAL_TX_PIN
#endif
-#if !PIN_EXISTS(Z3_SERIAL_TX)
- #undef Z3_SERIAL_TX_PIN
+#if !PIN_EXISTS(V_SERIAL_RX)
+ #undef V_SERIAL_RX_PIN
#endif
-#if !PIN_EXISTS(Z3_SERIAL_RX)
- #undef Z3_SERIAL_RX_PIN
+#if !PIN_EXISTS(V_SERIAL_TX)
+ #undef V_SERIAL_TX_PIN
#endif
-#if !PIN_EXISTS(Z4_SERIAL_TX)
- #undef Z4_SERIAL_TX_PIN
+#if !PIN_EXISTS(U_SERIAL_RX)
+ #undef U_SERIAL_RX_PIN
#endif
-#if !PIN_EXISTS(Z4_SERIAL_RX)
- #undef Z4_SERIAL_RX_PIN
+#if !PIN_EXISTS(U_SERIAL_TX)
+ #undef U_SERIAL_TX_PIN
#endif
-#if !PIN_EXISTS(X2_SERIAL_TX)
- #undef X2_SERIAL_TX_PIN
+#if !PIN_EXISTS(K_SERIAL_RX)
+ #undef K_SERIAL_RX_PIN
#endif
-#if !PIN_EXISTS(X2_SERIAL_RX)
- #undef X2_SERIAL_RX_PIN
+#if !PIN_EXISTS(K_SERIAL_TX)
+ #undef K_SERIAL_TX_PIN
#endif
-#if !PIN_EXISTS(Y2_SERIAL_TX)
- #undef Y2_SERIAL_TX_PIN
+#if !PIN_EXISTS(J_SERIAL_RX)
+ #undef J_SERIAL_RX_PIN
#endif
-#if !PIN_EXISTS(Y2_SERIAL_RX)
- #undef Y2_SERIAL_RX_PIN
+#if !PIN_EXISTS(J_SERIAL_TX)
+ #undef J_SERIAL_TX_PIN
+#endif
+#if !PIN_EXISTS(I_SERIAL_RX)
+ #undef I_SERIAL_RX_PIN
#endif
#if !PIN_EXISTS(I_SERIAL_TX)
#undef I_SERIAL_TX_PIN
#endif
-#if !PIN_EXISTS(I_SERIAL_RX)
- #undef I_SERIAL_RX_PIN
+#if !PIN_EXISTS(Z4_SERIAL_RX)
+ #undef Z4_SERIAL_RX_PIN
#endif
-#if !PIN_EXISTS(J_SERIAL_TX)
- #undef J_SERIAL_TX_PIN
+#if !PIN_EXISTS(Z4_SERIAL_TX)
+ #undef Z4_SERIAL_TX_PIN
#endif
-#if !PIN_EXISTS(J_SERIAL_RX)
- #undef J_SERIAL_RX_PIN
+#if !PIN_EXISTS(Z3_SERIAL_RX)
+ #undef Z3_SERIAL_RX_PIN
#endif
-#if !PIN_EXISTS(K_SERIAL_TX)
- #undef K_SERIAL_TX_PIN
+#if !PIN_EXISTS(Z3_SERIAL_TX)
+ #undef Z3_SERIAL_TX_PIN
#endif
-#if !PIN_EXISTS(K_SERIAL_RX)
- #undef K_SERIAL_RX_PIN
+#if !PIN_EXISTS(Z2_SERIAL_RX)
+ #undef Z2_SERIAL_RX_PIN
#endif
-#if !PIN_EXISTS(U_SERIAL_TX)
- #undef U_SERIAL_TX_PIN
+#if !PIN_EXISTS(Z2_SERIAL_TX)
+ #undef Z2_SERIAL_TX_PIN
#endif
-#if !PIN_EXISTS(U_SERIAL_RX)
- #undef U_SERIAL_RX_PIN
+#if !PIN_EXISTS(Y2_SERIAL_RX)
+ #undef Y2_SERIAL_RX_PIN
#endif
-#if !PIN_EXISTS(V_SERIAL_TX)
- #undef V_SERIAL_TX_PIN
+#if !PIN_EXISTS(Y2_SERIAL_TX)
+ #undef Y2_SERIAL_TX_PIN
#endif
-#if !PIN_EXISTS(V_SERIAL_RX)
- #undef V_SERIAL_RX_PIN
+#if !PIN_EXISTS(X2_SERIAL_RX)
+ #undef X2_SERIAL_RX_PIN
#endif
-#if !PIN_EXISTS(W_SERIAL_TX)
- #undef W_SERIAL_TX_PIN
+#if !PIN_EXISTS(X2_SERIAL_TX)
+ #undef X2_SERIAL_TX_PIN
#endif
-#if !PIN_EXISTS(W_SERIAL_RX)
- #undef W_SERIAL_RX_PIN
+#if !PIN_EXISTS(Z_SERIAL_RX)
+ #undef Z_SERIAL_RX_PIN
+#endif
+#if !PIN_EXISTS(Z_SERIAL_TX)
+ #undef Z_SERIAL_TX_PIN
+#endif
+#if !PIN_EXISTS(Y_SERIAL_RX)
+ #undef Y_SERIAL_RX_PIN
+#endif
+#if !PIN_EXISTS(Y_SERIAL_TX)
+ #undef Y_SERIAL_TX_PIN
+#endif
+#if !PIN_EXISTS(X_SERIAL_RX)
+ #undef X_SERIAL_RX_PIN
+#endif
+#if !PIN_EXISTS(X_SERIAL_TX)
+ #undef X_SERIAL_TX_PIN
#endif
#ifndef FAN0_PIN
@@ -456,9 +549,13 @@
#define TEMP_BED_PIN -1
#endif
-// Use ATEMP if TEMP_SOC_PIN is not defined
-#if !defined(TEMP_SOC_PIN) && defined(ATEMP)
- #define TEMP_SOC_PIN ATEMP
+// Get TEMP_SOC_PIN from the platform, if not defined
+#ifndef TEMP_SOC_PIN
+ #ifdef ATEMP
+ #define TEMP_SOC_PIN ATEMP
+ #elif defined(HAL_ADC_MCU_TEMP_DUMMY_PIN)
+ #define TEMP_SOC_PIN HAL_ADC_MCU_TEMP_DUMMY_PIN
+ #endif
#endif
#ifndef SD_DETECT_PIN
diff --git a/Marlin/src/pins/ramps/pins_DAGOMA_D6.h b/Marlin/src/pins/ramps/pins_DAGOMA_D6.h
index 2a89647376e1..f44657d2b55b 100644
--- a/Marlin/src/pins/ramps/pins_DAGOMA_D6.h
+++ b/Marlin/src/pins/ramps/pins_DAGOMA_D6.h
@@ -75,18 +75,13 @@
// the jumper next to the limit switch socket when using sensorless homing.
//
#if HAS_TMC_UART
- /**
- * TMC2208/TMC2209 stepper drivers
- */
- #define X_SERIAL_RX_PIN 73
+ //
+ // TMC2208/TMC2209 stepper drivers
+ //
#define X_SERIAL_TX_PIN 73
- #define Y_SERIAL_RX_PIN 73
#define Y_SERIAL_TX_PIN 73
- #define Z_SERIAL_RX_PIN 73
#define Z_SERIAL_TX_PIN 73
- #define E0_SERIAL_RX_PIN 73
#define E0_SERIAL_TX_PIN 73
- #define E1_SERIAL_RX_PIN 12
#define E1_SERIAL_TX_PIN 12
// Default TMC slave addresses
diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h
index 5fdaa1941959..a21009b35378 100644
--- a/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h
+++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h
@@ -32,9 +32,9 @@
#define Z_MAX_PIN 2
#if HAS_TMC_UART
- /**
- * TMC2208/TMC2209 stepper drivers
- */
+ //
+ // TMC2208/TMC2209 stepper drivers
+ //
#define X_SERIAL_TX_PIN 71
#define X_SERIAL_RX_PIN 72
diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h
index 0c573f25fc39..a4968eff3fb7 100644
--- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h
+++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h
@@ -124,33 +124,26 @@
//#define E3_HARDWARE_SERIAL Serial1
#define X_SERIAL_TX_PIN -1 // 59
- #define X_SERIAL_RX_PIN -1 // 63
+ //#define X_SERIAL_RX_PIN -1 // 63
#define X2_SERIAL_TX_PIN -1
- #define X2_SERIAL_RX_PIN -1
#define Y_SERIAL_TX_PIN -1 // 64
- #define Y_SERIAL_RX_PIN -1 // 40
+ //#define Y_SERIAL_RX_PIN -1 // 40
#define Y2_SERIAL_TX_PIN -1
- #define Y2_SERIAL_RX_PIN -1
#define Z_SERIAL_TX_PIN -1 // 44
- #define Z_SERIAL_RX_PIN -1 // 42
+ //#define Z_SERIAL_RX_PIN -1 // 42
#define Z2_SERIAL_TX_PIN -1
- #define Z2_SERIAL_RX_PIN -1
#define E0_SERIAL_TX_PIN -1 // 66
- #define E0_SERIAL_RX_PIN -1 // 65
+ //#define E0_SERIAL_RX_PIN -1 // 65
#define E1_SERIAL_TX_PIN -1
- #define E1_SERIAL_RX_PIN -1
#define E2_SERIAL_TX_PIN -1
- #define E2_SERIAL_RX_PIN -1
#define E3_SERIAL_TX_PIN -1
- #define E3_SERIAL_RX_PIN -1
#define E4_SERIAL_TX_PIN -1
- #define E4_SERIAL_RX_PIN -1
- #define E5_SERIAL_RX_PIN -1
- #define E6_SERIAL_RX_PIN -1
- #define E7_SERIAL_RX_PIN -1
+ #define E5_SERIAL_TX_PIN -1
+ #define E6_SERIAL_TX_PIN -1
+ #define E7_SERIAL_TX_PIN -1
#endif
//
diff --git a/Marlin/src/pins/rp2040/env_validate.h b/Marlin/src/pins/rp2040/env_validate.h
new file mode 100644
index 000000000000..f409b52b831a
--- /dev/null
+++ b/Marlin/src/pins/rp2040/env_validate.h
@@ -0,0 +1,26 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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
+
+#if NOT_TARGET(__PLAT_RP2040__)
+ #error "Oops! Make sure to build with target platform 'RP2040'."
+#endif
diff --git a/Marlin/src/pins/rp2040/pins_BTT_SKR_Pico.h b/Marlin/src/pins/rp2040/pins_BTT_SKR_Pico.h
new file mode 100644
index 000000000000..0d0807ee9123
--- /dev/null
+++ b/Marlin/src/pins/rp2040/pins_BTT_SKR_Pico.h
@@ -0,0 +1,157 @@
+/**
+ * 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
+
+/**
+ * BigTreeTech SKR Pico
+ * https://github.com/bigtreetech/SKR-Pico
+ */
+
+#include "env_validate.h"
+
+#define BOARD_INFO_NAME "BTT SKR Pico"
+#define DEFAULT_MACHINE_NAME "BIQU 3D Printer"
+
+#define USBCON
+
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE 0x2000 // 8KB
+#endif
+
+//
+// Servos
+//
+#define SERVO0_PIN 29
+
+//
+// Limit Switches
+//
+#define X_DIAG_PIN 4
+#define Y_DIAG_PIN 3
+#define Z_DIAG_PIN 25 // probe:z_virtual_endstop
+
+#define X_STOP_PIN X_DIAG_PIN
+#define Y_STOP_PIN Y_DIAG_PIN
+#define Z_STOP_PIN Z_DIAG_PIN
+
+#ifndef FIL_RUNOUT_PIN
+ #define FIL_RUNOUT_PIN 16 // E0-STOP
+#endif
+
+#ifndef Z_MIN_PROBE_PIN
+ #define Z_MIN_PROBE_PIN 22
+#endif
+
+//
+// Steppers
+//
+#define X_STEP_PIN 11
+#define X_DIR_PIN 10
+#define X_ENABLE_PIN 12
+
+#define Y_STEP_PIN 6
+#define Y_DIR_PIN 5
+#define Y_ENABLE_PIN 7
+
+#define Z_STEP_PIN 19
+#define Z_DIR_PIN 28
+#define Z_ENABLE_PIN 2
+
+#define E0_STEP_PIN 14
+#define E0_DIR_PIN 13
+#define E0_ENABLE_PIN 15
+
+//
+// Temperature Sensors
+//
+#define TEMP_0_PIN 27 // Analog Input
+#define TEMP_BED_PIN 26 // Analog Input
+
+//
+// Heaters / Fans
+//
+#define HEATER_0_PIN 23
+#define HEATER_BED_PIN 21
+
+#define FAN0_PIN 17
+#define FAN1_PIN 18
+
+#if HAS_CUTTER
+ #define SPINDLE_LASER_ENA_PIN 0
+ #define SPINDLE_LASER_PWM_PIN 1
+#else
+ #define FAN2_PIN 20
+#endif
+
+//
+// Misc. Functions
+//
+#define NEOPIXEL_PIN 24
+
+/**
+ * TMC2208/TMC2209 stepper drivers
+ */
+#if HAS_TMC_UART
+ /**
+ * Hardware serial communication ports.
+ * If undefined software serial is used according to the pins below
+ */
+ //#define X_HARDWARE_SERIAL Serial1
+ //#define X2_HARDWARE_SERIAL Serial1
+ //#define Y_HARDWARE_SERIAL Serial1
+ //#define Y2_HARDWARE_SERIAL Serial1
+ //#define Z_HARDWARE_SERIAL MSerial1
+ //#define Z2_HARDWARE_SERIAL Serial1
+ //#define E0_HARDWARE_SERIAL Serial1
+ //#define E1_HARDWARE_SERIAL Serial1
+ //#define E2_HARDWARE_SERIAL Serial1
+ //#define E3_HARDWARE_SERIAL Serial1
+ //#define E4_HARDWARE_SERIAL Serial1
+
+ /**
+ * Software serial
+ */
+ #ifndef X_SERIAL_TX_PIN
+ #define X_SERIAL_TX_PIN 8
+ #endif
+ #ifndef X_SERIAL_RX_PIN
+ #define X_SERIAL_RX_PIN 9
+ #endif
+ #ifndef Y_SERIAL_TX_PIN
+ #define Y_SERIAL_TX_PIN 8
+ #endif
+ #ifndef Y_SERIAL_RX_PIN
+ #define Y_SERIAL_RX_PIN 9
+ #endif
+ #ifndef Z_SERIAL_TX_PIN
+ #define Z_SERIAL_TX_PIN 8
+ #endif
+ #ifndef Z_SERIAL_RX_PIN
+ #define Z_SERIAL_RX_PIN 9
+ #endif
+ #ifndef E0_SERIAL_TX_PIN
+ #define E0_SERIAL_TX_PIN 8
+ #endif
+ #ifndef E0_SERIAL_RX_PIN
+ #define E0_SERIAL_RX_PIN 9
+ #endif
+#endif
diff --git a/Marlin/src/pins/rp2040/pins_RP2040.h b/Marlin/src/pins/rp2040/pins_RP2040.h
new file mode 100644
index 000000000000..2f4e3796a68c
--- /dev/null
+++ b/Marlin/src/pins/rp2040/pins_RP2040.h
@@ -0,0 +1,562 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 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"
+
+#define BOARD_INFO_NAME "RP2040 Test"
+#define DEFAULT_MACHINE_NAME "RP2040 Test"
+
+#ifndef MARLIN_EEPROM_SIZE
+ #define MARLIN_EEPROM_SIZE 0x1000 // 4KB
+#endif
+
+//
+// Servos
+//
+
+#define SERVO0_PIN 14
+
+//
+// Limit Switches
+//
+#define X_STOP_PIN 13
+#define Y_STOP_PIN 3
+#define Z_STOP_PIN 2
+
+//
+// Steppers
+//
+#define X_STEP_PIN 29
+#define X_DIR_PIN 29
+#define X_ENABLE_PIN 29
+#ifndef X_CS_PIN
+ #define X_CS_PIN 29
+#endif
+
+#define Y_STEP_PIN 29
+#define Y_DIR_PIN 29
+#define Y_ENABLE_PIN 29
+#ifndef Y_CS_PIN
+ #define Y_CS_PIN 29
+#endif
+
+#define Z_STEP_PIN 5
+#define Z_DIR_PIN 4
+#define Z_ENABLE_PIN 7
+#ifndef Z_CS_PIN
+ #define Z_CS_PIN 4
+#endif
+
+#define E0_STEP_PIN 29
+#define E0_DIR_PIN 29
+#define E0_ENABLE_PIN 29
+#ifndef E0_CS_PIN
+ #define E0_CS_PIN 29
+#endif
+
+//#define E1_STEP_PIN 36
+//#define E1_DIR_PIN 34
+//#define E1_ENABLE_PIN 30
+//#ifndef E1_CS_PIN
+// #define E1_CS_PIN 44
+//#endif
+
+//
+// Temperature Sensors
+//
+#define TEMP_0_PIN A0 // Analog Input
+#define TEMP_1_PIN A1 // Analog Input
+#define TEMP_2_PIN A2 // Analog Input
+#define TEMP_BED_PIN A1 // Analog Input
+
+#define TEMP_MCU HAL_ADC_MCU_TEMP_DUMMY_PIN // this is a flag value, don´t change
+
+#define TEMP_CHAMBER_PIN TEMP_1_PIN
+#define TEMP_BOARD_PIN TEMP_MCU
+
+// SPI for MAX Thermocouple
+#if DISABLED(SDSUPPORT)
+ #define TEMP_0_CS_PIN 17 // Don't use 53 if using Display/SD card
+#else
+ #define TEMP_0_CS_PIN 17 // Don't use 49 (SD_DETECT_PIN)
+#endif
+
+//
+// Heaters / Fans
+//
+#define HEATER_0_PIN 24
+
+ // Non-specific are "EFB" (i.e., "EFBF" or "EFBE")
+#define FAN0_PIN 23
+#define HEATER_BED_PIN 25
+
+#if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL)
+ #define FAN1_PIN 21
+#else
+ #define HEATER_1_PIN MOSFET_D_PIN
+#endif
+
+#ifndef FAN0_PIN
+ #define FAN0_PIN 4 // IO pin. Buffer needed
+#endif
+
+//
+// Misc. Functions
+//
+#define SDSS 20
+//#define LED_PIN 13
+#define NEOPIXEL_PIN 15
+
+#ifndef FILWIDTH_PIN
+ #define FILWIDTH_PIN 5 // Analog Input on AUX2
+#endif
+
+// define digital pin 4 for the filament runout sensor. Use the RAMPS 1.4 digital input 4 on the servos connector
+#ifndef FIL_RUNOUT_PIN
+ #define FIL_RUNOUT_PIN 21
+#endif
+
+#ifndef PS_ON_PIN
+ #define PS_ON_PIN 12
+#endif
+
+#if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) && !defined(SPINDLE_LASER_ENA_PIN)
+ #if NUM_SERVOS <= 1 // Prefer the servo connector
+ #define CASE_LIGHT_PIN 6 // Hardware PWM
+ #elif HAS_FREE_AUX2_PINS // try to use AUX 2
+ #define CASE_LIGHT_PIN 21 // Hardware PWM
+ #endif
+#endif
+
+//
+// M3/M4/M5 - Spindle/Laser Control
+//
+#if HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA)
+ #if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // Prefer the servo connector
+ #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown!
+ #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM
+ #define SPINDLE_DIR_PIN 5
+ #elif HAS_FREE_AUX2_PINS // try to use AUX 2
+ #define SPINDLE_LASER_ENA_PIN 22 // Pullup or pulldown!
+ #define SPINDLE_LASER_PWM_PIN 23 // Hardware PWM
+ #define SPINDLE_DIR_PIN 24
+ #endif
+#endif
+
+//
+// Průša i3 MK2 Multiplexer Support
+//
+#ifndef E_MUX0_PIN
+ #define E_MUX0_PIN 40 // Z_CS_PIN
+#endif
+#ifndef E_MUX1_PIN
+ #define E_MUX1_PIN 42 // E0_CS_PIN
+#endif
+#ifndef E_MUX2_PIN
+ #define E_MUX2_PIN 44 // E1_CS_PIN
+#endif
+
+/**
+ * Default pins for TMC software SPI
+ */
+#if ENABLED(TMC_USE_SW_SPI)
+ #ifndef TMC_SW_MOSI
+ #define TMC_SW_MOSI 66
+ #endif
+ #ifndef TMC_SW_MISO
+ #define TMC_SW_MISO 44
+ #endif
+ #ifndef TMC_SW_SCK
+ #define TMC_SW_SCK 64
+ #endif
+#endif
+
+#if HAS_TMC_UART
+ /**
+ * TMC2208/TMC2209 stepper drivers
+ *
+ * Hardware serial communication ports.
+ * If undefined software serial is used according to the pins below
+ */
+ //#define X_HARDWARE_SERIAL Serial1
+ //#define X2_HARDWARE_SERIAL Serial1
+ //#define Y_HARDWARE_SERIAL Serial1
+ //#define Y2_HARDWARE_SERIAL Serial1
+ #define Z_HARDWARE_SERIAL MSerial1
+ //#define Z2_HARDWARE_SERIAL Serial1
+ //#define E0_HARDWARE_SERIAL Serial1
+ //#define E1_HARDWARE_SERIAL Serial1
+ //#define E2_HARDWARE_SERIAL Serial1
+ //#define E3_HARDWARE_SERIAL Serial1
+ //#define E4_HARDWARE_SERIAL Serial1
+
+ /**
+ * Software serial
+ */
+
+ #ifndef X_SERIAL_TX_PIN
+ #define X_SERIAL_TX_PIN -1
+ #endif
+ #ifndef X2_SERIAL_TX_PIN
+ #define X2_SERIAL_TX_PIN -1
+ #endif
+
+ #ifndef Y_SERIAL_TX_PIN
+ #define Y_SERIAL_TX_PIN -1
+ #endif
+ #ifndef Y2_SERIAL_TX_PIN
+ #define Y2_SERIAL_TX_PIN -1
+ #endif
+
+ #ifndef Z_SERIAL_TX_PIN
+ #define Z_SERIAL_TX_PIN 0
+ #endif
+ #ifndef Z2_SERIAL_TX_PIN
+ #define Z2_SERIAL_TX_PIN -1
+ #endif
+
+ #ifndef E0_SERIAL_TX_PIN
+ #define E0_SERIAL_TX_PIN -1
+ #endif
+ #ifndef E1_SERIAL_TX_PIN
+ #define E1_SERIAL_TX_PIN -1
+ #endif
+ #ifndef E2_SERIAL_TX_PIN
+ #define E2_SERIAL_TX_PIN -1
+ #endif
+ #ifndef E3_SERIAL_TX_PIN
+ #define E3_SERIAL_TX_PIN -1
+ #endif
+ #ifndef E4_SERIAL_TX_PIN
+ #define E4_SERIAL_TX_PIN -1
+ #endif
+ #ifndef E5_SERIAL_TX_PIN
+ #define E5_SERIAL_TX_PIN -1
+ #endif
+ #ifndef E6_SERIAL_TX_PIN
+ #define E6_SERIAL_TX_PIN -1
+ #endif
+ #ifndef E7_SERIAL_TX_PIN
+ #define E7_SERIAL_TX_PIN -1
+ #endif
+#endif
+
+//////////////////////////
+// LCDs and Controllers //
+//////////////////////////
+
+#if ANY(TFT_COLOR_UI, TFT_CLASSIC_UI, TFT_LVGL_UI)
+
+ #define TFT_A0_PIN 43
+ #define TFT_CS_PIN 49
+ #define TFT_DC_PIN 43
+ #define TFT_SCK_PIN SD_SCK_PIN
+ #define TFT_MOSI_PIN SD_MOSI_PIN
+ #define TFT_MISO_PIN SD_MISO_PIN
+ #define LCD_USE_DMA_SPI
+
+ #define BTN_EN1 40
+ #define BTN_EN2 63
+ #define BTN_ENC 59
+ #define BEEPER_PIN 22
+
+ #define TOUCH_CS_PIN 33
+ #define SD_DETECT_PIN 41
+
+ #define HAS_SPI_FLASH 1
+ #if HAS_SPI_FLASH
+ #define SPI_DEVICE 1
+ #define SPI_FLASH_SIZE 0x1000000 // 16MB
+ #define SPI_FLASH_CS_PIN 31
+ #define SPI_FLASH_MOSI_PIN SD_MOSI_PIN
+ #define SPI_FLASH_MISO_PIN SD_MISO_PIN
+ #define SPI_FLASH_SCK_PIN SD_SCK_PIN
+ #endif
+
+ #define TFT_BUFFER_SIZE 0xFFFF
+ #ifndef TFT_DRIVER
+ #define TFT_DRIVER ST7796
+ #endif
+ #ifndef XPT2046_X_CALIBRATION
+ #define XPT2046_X_CALIBRATION 63934
+ #endif
+ #ifndef XPT2046_Y_CALIBRATION0
+ #define XPT2046_Y_CALIBRATION 63598
+ #endif
+ #ifndef XPT2046_X_OFFSET
+ #define XPT2046_X_OFFSET -1
+ #endif
+ #ifndef XPT2046_Y_OFFSET
+ #define XPT2046_Y_OFFSET -20
+ #endif
+
+ #define BTN_BACK 70
+
+#elif HAS_WIRED_LCD
+
+ //
+ // LCD Display output pins
+ //
+ #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD)
+
+ #define LCD_PINS_RS 49 // CS chip select /SS chip slave select
+ #define LCD_PINS_ENABLE 51 // SID (MOSI)
+ #define LCD_PINS_D4 52 // SCK (CLK) clock
+
+ #elif ALL(IS_NEWPANEL, PANEL_ONE)
+
+ #define LCD_PINS_RS 40
+ #define LCD_PINS_ENABLE 42
+ #define LCD_PINS_D4 65
+ #define LCD_PINS_D5 66
+ #define LCD_PINS_D6 44
+ #define LCD_PINS_D7 64
+
+ #else
+
+ #if ENABLED(CR10_STOCKDISPLAY)
+
+ #define LCD_PINS_RS 27
+ #define LCD_PINS_ENABLE 29
+ #define LCD_PINS_D4 25
+
+ #if !IS_NEWPANEL
+ #define BEEPER_PIN 37
+ #endif
+
+ #elif ENABLED(ZONESTAR_LCD)
+
+ #define LCD_PINS_RS 64
+ #define LCD_PINS_ENABLE 44
+ #define LCD_PINS_D4 63
+ #define LCD_PINS_D5 40
+ #define LCD_PINS_D6 42
+ #define LCD_PINS_D7 65
+
+ #else
+
+ #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306)
+ #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
+ #define LCD_PINS_RS 16
+ #define LCD_PINS_ENABLE 17
+ #define LCD_PINS_D4 23
+ #define LCD_PINS_D5 25
+ #define LCD_PINS_D6 27
+ #endif
+
+ #define LCD_PINS_D7 29
+
+ #if !IS_NEWPANEL
+ #define BEEPER_PIN 33
+ #endif
+
+ #endif
+
+ #if !IS_NEWPANEL
+ // Buttons attached to a shift register
+ // Not wired yet
+ //#define SHIFT_CLK_PIN 38
+ //#define SHIFT_LD_PIN 42
+ //#define SHIFT_OUT_PIN 40
+ //#define SHIFT_EN_PIN 17
+ #endif
+
+ #endif
+
+ //
+ // LCD Display input pins
+ //
+ #if IS_NEWPANEL
+
+ #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER)
+
+ #define BEEPER_PIN 37
+
+ #if ENABLED(CR10_STOCKDISPLAY)
+ #define BTN_EN1 17
+ #define BTN_EN2 23
+ #else
+ #define BTN_EN1 31
+ #define BTN_EN2 33
+ #endif
+
+ #define BTN_ENC 35
+ #define SD_DETECT_PIN 49
+ #define KILL_PIN 41
+
+ #if ENABLED(BQ_LCD_SMART_CONTROLLER)
+ #define LCD_BACKLIGHT_PIN 39
+ #endif
+
+ #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD)
+
+ #define BTN_EN1 64
+ #define BTN_EN2 59
+ #define BTN_ENC 63
+ #define SD_DETECT_PIN 42
+
+ #elif ENABLED(LCD_I2C_PANELOLU2)
+
+ #define BTN_EN1 47
+ #define BTN_EN2 43
+ #define BTN_ENC 32
+ #define LCD_SDSS SDSS
+ #define KILL_PIN 41
+
+ #elif ENABLED(LCD_I2C_VIKI)
+
+ #define BTN_EN1 22 // https://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42.
+ #define BTN_EN2 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13.
+ #define BTN_ENC -1
+
+ #define LCD_SDSS SDSS
+ #define SD_DETECT_PIN 49
+
+ #elif ANY(VIKI2, miniVIKI)
+
+ #define DOGLCD_CS 45
+ #define DOGLCD_A0 44
+ #define LCD_SCREEN_ROT_180
+
+ #define BEEPER_PIN 33
+ #define STAT_LED_RED_PIN 32
+ #define STAT_LED_BLUE_PIN 35
+
+ #define BTN_EN1 22
+ #define BTN_EN2 7
+ #define BTN_ENC 39
+
+ #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)
+
+ #define DOGLCD_CS 29
+ #define DOGLCD_A0 27
+
+ #define BEEPER_PIN 23
+ #define LCD_BACKLIGHT_PIN 33
+
+ #define BTN_EN1 35
+ #define BTN_EN2 37
+ #define BTN_ENC 31
+
+ #define LCD_SDSS SDSS
+ #define SD_DETECT_PIN 49
+ #define KILL_PIN 41
+
+ #elif ENABLED(MKS_MINI_12864)
+
+ #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
+
+ #define BEEPER_PIN 37
+ // not connected to a pin
+ #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65
+
+ #define BTN_EN1 31
+ #define BTN_EN2 33
+ #define BTN_ENC 35
+
+ #define SD_DETECT_PIN 49
+ #define KILL_PIN 64
+
+ #elif ENABLED(MINIPANEL)
+
+ #define BEEPER_PIN 42
+ // not connected to a pin
+ #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65
+
+ #define DOGLCD_A0 44
+ #define DOGLCD_CS 66
+
+ // GLCD features
+ // Uncomment screen orientation
+ //#define LCD_SCREEN_ROT_90
+ //#define LCD_SCREEN_ROT_180
+ //#define LCD_SCREEN_ROT_270
+
+ #define BTN_EN1 40
+ #define BTN_EN2 63
+ #define BTN_ENC 59
+
+ #define SD_DETECT_PIN 49
+ #define KILL_PIN 64
+
+ #elif ENABLED(ZONESTAR_LCD)
+
+ #define ADC_KEYPAD_PIN 12
+
+ #elif ENABLED(AZSMZ_12864)
+
+ // Pins only defined for RAMPS_SMART currently
+
+ #else
+
+ // Beeper on AUX-4
+ #define BEEPER_PIN 33
+
+ // Buttons are directly attached to AUX-2
+ #if IS_RRW_KEYPAD
+ #define SHIFT_OUT_PIN 40
+ #define SHIFT_CLK_PIN 44
+ #define SHIFT_LD_PIN 42
+ #define BTN_EN1 64
+ #define BTN_EN2 59
+ #define BTN_ENC 63
+ #elif ENABLED(PANEL_ONE)
+ #define BTN_EN1 59 // AUX2 PIN 3
+ #define BTN_EN2 63 // AUX2 PIN 4
+ #define BTN_ENC 49 // AUX3 PIN 7
+ #else
+ #define BTN_EN1 37
+ #define BTN_EN2 35
+ #define BTN_ENC 31
+ #define SD_DETECT_PIN 41
+ #endif
+
+ #if ENABLED(G3D_PANEL)
+ #define SD_DETECT_PIN 49
+ #define KILL_PIN 41
+ #endif
+ #endif
+
+ // CUSTOM SIMULATOR INPUTS
+ #define BTN_BACK 70
+
+ #endif // IS_NEWPANEL
+
+#endif // HAS_WIRED_LCD
diff --git a/Marlin/src/pins/samd/pins_RAMPS_144.h b/Marlin/src/pins/samd/pins_RAMPS_144.h
index 6897540f05e8..33a45fc9f4e8 100644
--- a/Marlin/src/pins/samd/pins_RAMPS_144.h
+++ b/Marlin/src/pins/samd/pins_RAMPS_144.h
@@ -210,54 +210,30 @@
#ifndef X_SERIAL_TX_PIN
#define X_SERIAL_TX_PIN 47
#endif
- #ifndef X_SERIAL_RX_PIN
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
- #endif
#ifndef X2_SERIAL_TX_PIN
#define X2_SERIAL_TX_PIN -1
#endif
- #ifndef X2_SERIAL_RX_PIN
- #define X2_SERIAL_RX_PIN X2_SERIAL_TX_PIN
- #endif
#ifndef Y_SERIAL_TX_PIN
#define Y_SERIAL_TX_PIN 45
#endif
- #ifndef Y_SERIAL_RX_PIN
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
- #endif
#ifndef Y2_SERIAL_TX_PIN
#define Y2_SERIAL_TX_PIN -1
#endif
- #ifndef Y2_SERIAL_RX_PIN
- #define Y2_SERIAL_RX_PIN Y2_SERIAL_TX_PIN
- #endif
#ifndef Z_SERIAL_TX_PIN
#define Z_SERIAL_TX_PIN 32
#endif
- #ifndef Z_SERIAL_RX_PIN
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
- #endif
#ifndef Z2_SERIAL_TX_PIN
#define Z2_SERIAL_TX_PIN 22
#endif
- #ifndef Z2_SERIAL_RX_PIN
- #define Z2_SERIAL_RX_PIN Z2_SERIAL_TX_PIN
- #endif
#ifndef E0_SERIAL_TX_PIN
#define E0_SERIAL_TX_PIN 43
#endif
- #ifndef E0_SERIAL_RX_PIN
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
- #endif
#ifndef E1_SERIAL_TX_PIN
#define E1_SERIAL_TX_PIN -1
#endif
- #ifndef E1_SERIAL_RX_PIN
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
- #endif
#endif
//
diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h
index 3b42a0985283..de7ded7d52ac 100644
--- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h
+++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h
@@ -126,16 +126,9 @@
//#define E0_HARDWARE_SERIAL MSerial1
#define X_SERIAL_TX_PIN PC10
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PC11
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PC12
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PD2
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h
index 9209515b1a24..37e7ac8fc2a6 100644
--- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h
+++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h
@@ -34,16 +34,9 @@
*/
#if HAS_TMC_UART
#define X_SERIAL_TX_PIN PB15
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PC6
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PC10
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PC11
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h
index d0bd2944bc03..70f3f85747d4 100644
--- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h
+++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h
@@ -81,16 +81,9 @@
#if HAS_TMC_UART // Shared with EXP1
#define X_SERIAL_TX_PIN PC10
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PC11
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PC12
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PC14
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_CR4NS.h b/Marlin/src/pins/stm32f1/pins_CREALITY_CR4NS.h
index 5ff033e6841d..95bd5e98ff97 100644
--- a/Marlin/src/pins/stm32f1/pins_CREALITY_CR4NS.h
+++ b/Marlin/src/pins/stm32f1/pins_CREALITY_CR4NS.h
@@ -33,11 +33,6 @@
#error "CR4NS200320C13 only supports one hotend / E-stepper."
#endif
-// Validate stepper driver selections.
-//#if !AXIS_DRIVER_TYPE_X(TMC2208) || !AXIS_DRIVER_TYPE_Y(TMC2208) || !AXIS_DRIVER_TYPE_Z(TMC2208) || !AXIS_DRIVER_TYPE_E0(TMC2208)
-// #error "This board has onboard TMC2208 drivers for X, Y, Z, and E0."
-//#endif
-
#ifndef BOARD_INFO_NAME
#define BOARD_INFO_NAME "CR4NS200320C13"
#endif
@@ -46,23 +41,28 @@
#endif
#define BOARD_WEBSITE_URL "www.creality.com"
+//
+// EEPROM
+//
+#define IIC_EEPROM_SDA PA7
+#define IIC_EEPROM_SCL PA8
+
//
// Servos
//
#ifndef SERVO0_PIN
- #define SERVO0_PIN PC14
+ #define SERVO0_PIN PC13
#endif
-
#ifndef Z_MIN_PROBE_PIN
- #define Z_MIN_PROBE_PIN PC13 // BLTouch IN
+ #define Z_MIN_PROBE_PIN PC14
#endif
//
// Limit Switches
//
-//#ifndef Z_STOP_PIN
-// #define Z_STOP_PIN PA15 // else PA7
-//#endif
+#ifndef Z_STOP_PIN
+ #define Z_STOP_PIN PC14
+#endif
//
// Filament Runout Sensor
@@ -76,31 +76,31 @@
//
#define HEATER_BED_PIN PB2 // HOT BED
#define FAN1_PIN PC1 // extruder fan
-//#define FAN2_PIN PB1 // Controller fan FET
//
-// Auto fans
+// Steppers
//
-//#ifndef CONTROLLER_FAN_PIN
-// #define CONTROLLER_FAN_PIN FAN2_PIN
-//#endif
-
#if HAS_TMC_UART
+
// Reduce baud rate to improve software serial reliability
#define TMC_BAUD_RATE 19200
// Software serial
#define X_SERIAL_TX_PIN PB12
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
+ #define X_DIAG_PIN PB10
#define Y_SERIAL_TX_PIN PB13
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
+ #define Y_DIAG_PIN PB11
#define Z_SERIAL_TX_PIN PB14
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#endif // HAS_TMC_UART
+//
+// SD Card
+//
+#define ONBOARD_SPI_DEVICE 1 // SPI1
+#define ONBOARD_SD_CS_PIN PA4 // SDSS
+
#if ANY(RET6_12864_LCD, HAS_DWIN_E3V2, IS_DWIN_MARLINUI)
/**
@@ -118,18 +118,10 @@
#define EXP3_03_PIN PA2
#define EXP3_04_PIN PA3
#define EXP3_05_PIN PB1
- #define EXP3_06_PIN -1
+ #define EXP3_06_PIN PB0
#define EXP3_07_PIN PA12
#define EXP3_08_PIN PA11
- #ifndef BEEPER_PIN
- #define BEEPER_PIN EXP1_06_PIN // BEEP
- #endif
-
- #define BTN_ENC EXP1_05_PIN // EN
- #define BTN_EN1 EXP1_08_PIN // A
- #define BTN_EN2 EXP1_07_PIN // B
-
#endif
#include "pins_CREALITY_V4.h"
diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h
index 9ae858f2d08d..38959a4c6cfe 100644
--- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h
+++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h
@@ -57,8 +57,12 @@
#endif
#if ENABLED(IIC_BL24CXX_EEPROM)
- #define IIC_EEPROM_SDA PA11
- #define IIC_EEPROM_SCL PA12
+ #ifndef IIC_EEPROM_SDA
+ #define IIC_EEPROM_SDA PA11
+ #endif
+ #ifndef IIC_EEPROM_SCL
+ #define IIC_EEPROM_SCL PA12
+ #endif
#define MARLIN_EEPROM_SIZE 0x800 // 2K (24C16)
#elif ENABLED(SDCARD_EEPROM_EMULATION)
#define MARLIN_EEPROM_SIZE 0x800 // 2K
@@ -193,14 +197,30 @@
* GND | 9 10 | 5V
* ------
*/
- #define EXP3_01_PIN PC6
- #define EXP3_02_PIN PB2
- #define EXP3_03_PIN PB10
- #define EXP3_04_PIN PB11
- #define EXP3_05_PIN PB14
- #define EXP3_06_PIN PB13
- #define EXP3_07_PIN PB12
- #define EXP3_08_PIN PB15
+ #ifndef EXP3_01_PIN
+ #define EXP3_01_PIN PC6
+ #endif
+ #ifndef EXP3_02_PIN
+ #define EXP3_02_PIN PB2
+ #endif
+ #ifndef EXP3_03_PIN
+ #define EXP3_03_PIN PB10
+ #endif
+ #ifndef EXP3_04_PIN
+ #define EXP3_04_PIN PB11
+ #endif
+ #ifndef EXP3_05_PIN
+ #define EXP3_05_PIN PB14
+ #endif
+ #ifndef EXP3_06_PIN
+ #define EXP3_06_PIN PB13
+ #endif
+ #ifndef EXP3_07_PIN
+ #define EXP3_07_PIN PB12
+ #endif
+ #ifndef EXP3_08_PIN
+ #define EXP3_08_PIN PB15
+ #endif
#elif ANY(VET6_12864_LCD, DWIN_VET6_CREALITY_LCD)
diff --git a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h
index 55100b1efbd2..3372ae3aba59 100644
--- a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h
+++ b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h
@@ -127,11 +127,8 @@
// SoftwareSerial with one pin per driver
// Compatible with TMC2208 and TMC2209 drivers
#define X_SERIAL_TX_PIN PA10 // RXD1
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
#define Y_SERIAL_TX_PIN PA9 // TXD1
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
#define Z_SERIAL_TX_PIN PC7 // IO1
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
#ifndef TMC_BAUD_RATE
#define TMC_BAUD_RATE 19200
#endif
@@ -174,7 +171,6 @@
//
#if AXIS_DRIVER_TYPE_E0(TMC2208) || AXIS_DRIVER_TYPE_E0(TMC2209)
#define E0_SERIAL_TX_PIN PA8 // IO0
- #define E0_SERIAL_RX_PIN PA8 // IO0
#else
// Motor current PWM pins
#define MOTOR_CURRENT_PWM_E_PIN PB0 // VREF1 CONTROL E
diff --git a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h
index e31d11f40827..22c977d8b92b 100644
--- a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h
+++ b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h
@@ -95,13 +95,9 @@
#if HAS_TMC_UART
#define X_SERIAL_TX_PIN PB0
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
#define Y_SERIAL_TX_PIN PA7
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
#define Z_SERIAL_TX_PIN PA4
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
#define E0_SERIAL_TX_PIN PC2
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
#endif
//
diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h
index fc9e24b79016..d32479267de9 100644
--- a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h
+++ b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h
@@ -85,9 +85,9 @@
#define E0_ENABLE_PIN PC13
#if HAS_TMC_UART
- /**
- * TMC2208/TMC2209 stepper drivers
- */
+ //
+ // TMC2208/TMC2209 stepper drivers
+ //
// Hardware serial with switch
#define X_HARDWARE_SERIAL MSerial2
diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h
index 96e90b701ca7..43bd8501d2f8 100644
--- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h
+++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h
@@ -38,9 +38,9 @@
#if HAS_TMC_UART
- /**
- * TMC2208/TMC2209 stepper drivers
- */
+ //
+ // TMC2208/TMC2209 stepper drivers
+ //
#define X_SERIAL_TX_PIN PA11
#define X_SERIAL_RX_PIN PA12
diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h
index 222698fa111c..37ac753fc8a0 100644
--- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h
+++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h
@@ -154,6 +154,13 @@
#define LCD_BRIGHTNESS_DEFAULT TFT_BACKLIGHT_PWM
#endif
+//
+// SD Support
+//
+#ifndef SDCARD_CONNECTION
+ #define SDCARD_CONNECTION ONBOARD
+#endif
+
#if SD_CONNECTION_IS(ONBOARD)
#define ONBOARD_SDIO
#define SD_SS_PIN -1 // else SDSS set to PA4 in M43 (spi_pins.h)
diff --git a/Marlin/src/pins/stm32f1/pins_MD_D301.h b/Marlin/src/pins/stm32f1/pins_MD_D301.h
index 19445998b2f5..5d7a2dbf886d 100644
--- a/Marlin/src/pins/stm32f1/pins_MD_D301.h
+++ b/Marlin/src/pins/stm32f1/pins_MD_D301.h
@@ -120,19 +120,10 @@
// Software serial
//
#define X_SERIAL_TX_PIN PD6
- #define X_SERIAL_RX_PIN PD6
-
#define Y_SERIAL_TX_PIN PC11
- #define Y_SERIAL_RX_PIN PC11
-
#define Z_SERIAL_TX_PIN PA8
- #define Z_SERIAL_RX_PIN PA8
-
#define E0_SERIAL_TX_PIN PG2
- #define E0_SERIAL_RX_PIN PG2
-
#define Z2_SERIAL_TX_PIN PG6
- #define Z2_SERIAL_RX_PIN PG6
// Reduce baud rate to improve software serial reliability
#define TMC_BAUD_RATE 19200
diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h
index b9ab65e36d28..b3fc52c89418 100644
--- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h
+++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h
@@ -261,13 +261,9 @@
//#define TMC_SOFTWARE_SERIAL
#if ENABLED(TMC_SOFTWARE_SERIAL)
#define X_SERIAL_TX_PIN PF8 // SERVO3_PIN -- XS2 - 6
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
#define Y_SERIAL_TX_PIN PF9 // SERVO2_PIN -- XS2 - 5
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
#define Z_SERIAL_TX_PIN PA1 // SERVO1_PIN -- XS1 - 6
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
#define E0_SERIAL_TX_PIN PC3 // SERVO0_PIN -- XS1 - 5
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
#define TMC_BAUD_RATE 19200
#endif
#endif
diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h
index b7aaac12b9b7..01be779b1366 100644
--- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h
+++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h
@@ -151,16 +151,9 @@
//#define E4_HARDWARE_SERIAL Serial1
#define X_SERIAL_TX_PIN PD5
- #define X_SERIAL_RX_PIN PD5
-
#define Y_SERIAL_TX_PIN PD7
- #define Y_SERIAL_RX_PIN PD7
-
#define Z_SERIAL_TX_PIN PD4
- #define Z_SERIAL_RX_PIN PD4
-
#define E0_SERIAL_TX_PIN PD9
- #define E0_SERIAL_RX_PIN PD9
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h
index 49f14866c04d..31ef7f5c24e9 100644
--- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h
+++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h
@@ -107,16 +107,9 @@
//#define E0_HARDWARE_SERIAL MSerial1
#define X_SERIAL_TX_PIN PC7
- #define X_SERIAL_RX_PIN PC7
-
#define Y_SERIAL_TX_PIN PD2
- #define Y_SERIAL_RX_PIN PD2
-
#define Z_SERIAL_TX_PIN PC12
- #define Z_SERIAL_RX_PIN PC12
-
#define E0_SERIAL_TX_PIN PC11
- #define E0_SERIAL_RX_PIN PC11
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h
index 357960d8a74c..67d60a97ede6 100644
--- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h
+++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h
@@ -155,19 +155,10 @@
//#define E1_HARDWARE_SERIAL MSerial1
#define X_SERIAL_TX_PIN PD5
- #define X_SERIAL_RX_PIN PD5
-
#define Y_SERIAL_TX_PIN PD7
- #define Y_SERIAL_RX_PIN PD7
-
#define Z_SERIAL_TX_PIN PD4
- #define Z_SERIAL_RX_PIN PD4
-
#define E0_SERIAL_TX_PIN PD9
- #define E0_SERIAL_RX_PIN PD9
-
#define E1_SERIAL_TX_PIN PD8
- #define E1_SERIAL_RX_PIN PD8
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32f1/pins_ORCA_3D_SPRINGER.h b/Marlin/src/pins/stm32f1/pins_ORCA_3D_SPRINGER.h
index a376feb93a74..5c0c9aedd16b 100644
--- a/Marlin/src/pins/stm32f1/pins_ORCA_3D_SPRINGER.h
+++ b/Marlin/src/pins/stm32f1/pins_ORCA_3D_SPRINGER.h
@@ -137,25 +137,12 @@
//#define E1_HARDWARE_SERIAL MSerial1
#define X_SERIAL_TX_PIN PE3
- #define X_SERIAL_RX_PIN PE3
-
#define Y_SERIAL_TX_PIN PE4
- #define Y_SERIAL_RX_PIN PE4
-
#define Z_SERIAL_TX_PIN PB3
- #define Z_SERIAL_RX_PIN PB3
-
#define E0_SERIAL_TX_PIN PB7
- #define E0_SERIAL_RX_PIN PB7
-
#define E1_SERIAL_TX_PIN PD15
- #define E1_SERIAL_RX_PIN PD15
-
#define E2_SERIAL_TX_PIN PD11
- #define E2_SERIAL_RX_PIN PD11
-
#define E3_SERIAL_TX_PIN PD8
- #define E3_SERIAL_RX_PIN PD8
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h b/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h
index 8be9f5db8362..f2b903e96dc2 100644
--- a/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h
+++ b/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h
@@ -113,16 +113,9 @@
//#define E0_HARDWARE_SERIAL MSerial1
#define X_SERIAL_TX_PIN PC10
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PC11
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PC12
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PD2
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32f4/pins_ARMED.h b/Marlin/src/pins/stm32f4/pins_ARMED.h
index b4661226380f..027faf82995e 100644
--- a/Marlin/src/pins/stm32f4/pins_ARMED.h
+++ b/Marlin/src/pins/stm32f4/pins_ARMED.h
@@ -206,21 +206,10 @@
#if HAS_TMC_UART
// TMC2208/TMC2209 stepper drivers
#define X_SERIAL_TX_PIN EXT0_PIN
- #define X_SERIAL_RX_PIN EXT0_PIN
-
#define Y_SERIAL_TX_PIN EXT1_PIN
- #define Y_SERIAL_RX_PIN EXT1_PIN
-
#define Z_SERIAL_TX_PIN EXT2_PIN
- #define Z_SERIAL_RX_PIN EXT2_PIN
-
#define E0_SERIAL_TX_PIN EXT3_PIN
- #define E0_SERIAL_RX_PIN EXT3_PIN
-
- #define E1_SERIAL_RX_PIN EXT4_PIN
#define E1_SERIAL_TX_PIN EXT4_PIN
-
- #define Z2_SERIAL_RX_PIN EXT4_PIN
#define Z2_SERIAL_TX_PIN EXT4_PIN
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h
index 2abbf3452bed..42cc30407e3b 100644
--- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h
+++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h
@@ -140,16 +140,9 @@
//#define E4_HARDWARE_SERIAL Serial1
#define X_SERIAL_TX_PIN PE2
- #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 PE4
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PD7
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h
index 1ec7e7516335..e7fa7f8a5557 100644
--- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h
+++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h
@@ -118,23 +118,12 @@
*/
#if HAS_TMC_UART
#define X_SERIAL_TX_PIN PD6
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PD1
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PD15
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PD11
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#if ENABLED(BTT_E3_RRF_IDEX_BOARD)
#define X2_SERIAL_TX_PIN FPC12_PIN // X2UART
- #define X2_SERIAL_RX_PIN X2_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN FPC6_PIN // E1UART
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
#endif
// Reduce baud rate to improve software serial reliability
diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h
index cd5755539bfc..de3e026b05cd 100644
--- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h
+++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h
@@ -255,38 +255,17 @@
//#define E7_HARDWARE_SERIAL Serial1 // M5 MOTOR 5
#define X_SERIAL_TX_PIN PC14
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PE1
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PB5
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PG10
- #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 PC12
- #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN
-
#if ENABLED(M5_EXTENDER)
#define E3_SERIAL_TX_PIN PG4
- #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN
-
#define E4_SERIAL_TX_PIN PE15
- #define E4_SERIAL_RX_PIN E4_SERIAL_TX_PIN
-
#define E5_SERIAL_TX_PIN PE7
- #define E5_SERIAL_RX_PIN E5_SERIAL_TX_PIN
-
#define E6_SERIAL_TX_PIN PF15
- #define E6_SERIAL_RX_PIN E6_SERIAL_TX_PIN
-
#define E7_SERIAL_TX_PIN PH14
- #define E7_SERIAL_RX_PIN E7_SERIAL_TX_PIN
#endif
// Reduce baud rate to improve software serial reliability
diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h
index 1bfc6c5492bb..980f3fa02a35 100644
--- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h
+++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h
@@ -288,28 +288,13 @@
//#define E4_HARDWARE_SERIAL Serial1
#define X_SERIAL_TX_PIN PC4
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PD11
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PC6
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define Z2_SERIAL_TX_PIN PC7
- #define Z2_SERIAL_RX_PIN Z2_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PF2
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN PE4
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
-
#define E2_SERIAL_TX_PIN PE1
- #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN
-
#define E3_SERIAL_TX_PIN PD3
- #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
@@ -390,7 +375,6 @@
#define E4_CS_PIN EXP1_06_PIN
#if HAS_TMC_UART
#define E4_SERIAL_TX_PIN EXP1_06_PIN
- #define E4_SERIAL_RX_PIN E4_SERIAL_TX_PIN
#endif
// M2 on Driver Expansion Module
@@ -401,7 +385,6 @@
#define E5_CS_PIN EXP1_04_PIN
#if HAS_TMC_UART
#define E5_SERIAL_TX_PIN EXP1_04_PIN
- #define E5_SERIAL_RX_PIN E5_SERIAL_TX_PIN
#endif
// M3 on Driver Expansion Module
@@ -412,7 +395,6 @@
#define E6_CS_PIN EXP1_02_PIN
#if HAS_TMC_UART
#define E6_SERIAL_TX_PIN EXP1_02_PIN
- #define E6_SERIAL_RX_PIN E6_SERIAL_TX_PIN
#endif
#endif // BTT_MOTOR_EXPANSION
diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h
index c751f9b04119..0b8dd71f740b 100644
--- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h
+++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h
@@ -211,22 +211,11 @@
//#define E4_HARDWARE_SERIAL Serial1
#define X_SERIAL_TX_PIN PC13
- #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 PE1
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PD4
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN PD1
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
-
#define E2_SERIAL_TX_PIN PD6
- #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
@@ -395,7 +384,6 @@
#define E3_CS_PIN EXP1_06_PIN
#if HAS_TMC_UART
#define E3_SERIAL_TX_PIN EXP1_06_PIN
- #define E3_SERIAL_RX_PIN EXP1_06_PIN
#endif
#endif
@@ -408,7 +396,6 @@
#define E4_CS_PIN EXP1_04_PIN
#if HAS_TMC_UART
#define E4_SERIAL_TX_PIN EXP1_04_PIN
- #define E4_SERIAL_RX_PIN EXP1_04_PIN
#endif
#else
#define E4_ENABLE_PIN EXP2_07_PIN
@@ -423,7 +410,6 @@
#define E5_CS_PIN EXP1_02_PIN
#if HAS_TMC_UART
#define E5_SERIAL_TX_PIN EXP1_02_PIN
- #define E5_SERIAL_RX_PIN EXP1_02_PIN
#endif
#else
#define E5_ENABLE_PIN EXP2_07_PIN
diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h
index 41514181f5a9..d0d78ed7f56c 100644
--- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h
+++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h
@@ -305,19 +305,10 @@
// Software serial
//
#define X_SERIAL_TX_PIN PE0
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PD3
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PD0
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PC6
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN PD12
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
@@ -400,7 +391,6 @@
#define E2_CS_PIN EXP1_06_PIN
#if HAS_TMC_UART
#define E2_SERIAL_TX_PIN EXP1_06_PIN
- #define E2_SERIAL_RX_PIN EXP1_06_PIN
#endif
#endif
@@ -413,7 +403,6 @@
#define E3_CS_PIN EXP1_04_PIN
#if HAS_TMC_UART
#define E3_SERIAL_TX_PIN EXP1_04_PIN
- #define E3_SERIAL_RX_PIN EXP1_04_PIN
#endif
#else
#define E3_ENABLE_PIN EXP2_07_PIN
@@ -428,7 +417,6 @@
#define E4_CS_PIN EXP1_02_PIN
#if HAS_TMC_UART
#define E4_SERIAL_TX_PIN EXP1_02_PIN
- #define E4_SERIAL_RX_PIN EXP1_02_PIN
#endif
#else
#define E4_ENABLE_PIN EXP2_07_PIN
diff --git a/Marlin/src/pins/stm32f4/pins_CREALITY_CR4NTXXC10.h b/Marlin/src/pins/stm32f4/pins_CREALITY_CR4NTXXC10.h
index d1077cd5d0e0..683f68089a63 100644
--- a/Marlin/src/pins/stm32f4/pins_CREALITY_CR4NTXXC10.h
+++ b/Marlin/src/pins/stm32f4/pins_CREALITY_CR4NTXXC10.h
@@ -139,6 +139,7 @@
#endif
#if HAS_TMC_UART
+
// Reduce baud rate to improve software serial reliability
#define TMC_BAUD_RATE 19200
diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h
index d41a6eac754a..d63c6ea724cc 100644
--- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h
+++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h
@@ -253,31 +253,14 @@
#if HAS_TMC_UART
#define X_SERIAL_TX_PIN PG13
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PG10
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PD5
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PD1
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN PA14
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
-
#define E2_SERIAL_TX_PIN PG6
- #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN
-
#define E3_SERIAL_TX_PIN PG3
- #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN
-
#define E4_SERIAL_TX_PIN PD10
- #define E4_SERIAL_RX_PIN E4_SERIAL_TX_PIN
-
#define E5_SERIAL_TX_PIN PB12
- #define E5_SERIAL_RX_PIN E5_SERIAL_TX_PIN
#endif
//
diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V30.h b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V30.h
index 5eb398c3cf69..3da978c06f00 100644
--- a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V30.h
+++ b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V30.h
@@ -94,29 +94,17 @@
#ifndef X_SERIAL_TX_PIN
#define X_SERIAL_TX_PIN PB3
#endif
- #ifndef X_SERIAL_RX_PIN
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
- #endif
#ifndef Y_SERIAL_TX_PIN
#define Y_SERIAL_TX_PIN PB3
#endif
- #ifndef Y_SERIAL_RX_PIN
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
- #endif
#ifndef Z_SERIAL_TX_PIN
#define Z_SERIAL_TX_PIN PB3
#endif
- #ifndef Z_SERIAL_RX_PIN
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
- #endif
#ifndef E0_SERIAL_TX_PIN
#define E0_SERIAL_TX_PIN PB3
#endif
- #ifndef E0_SERIAL_RX_PIN
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
- #endif
// Default TMC slave addresses
#ifndef X_SLAVE_ADDRESS
diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h
index a6035c2c6f01..9d9eb1d37cf9 100644
--- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h
+++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h
@@ -39,17 +39,11 @@
#if HAS_TMC_UART
#define X_SERIAL_TX_PIN PE8
- #define X_SERIAL_RX_PIN PE8
#define Y_SERIAL_TX_PIN PC4
- #define Y_SERIAL_RX_PIN PC4
#define Z_SERIAL_TX_PIN PD12
- #define Z_SERIAL_RX_PIN PD12
#define E0_SERIAL_TX_PIN PA15
- #define E0_SERIAL_RX_PIN PA15
#define E1_SERIAL_TX_PIN PC5
- #define E1_SERIAL_RX_PIN PC5
#define E2_SERIAL_TX_PIN PE0
- #define E2_SERIAL_RX_PIN PE0
#endif
//
diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h
index 368f464f86ca..24055cb3cc3d 100644
--- a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h
+++ b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h
@@ -76,28 +76,13 @@
#if HAS_TMC_UART
#define X_SERIAL_TX_PIN PE7
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define X2_SERIAL_TX_PIN PA15
- #define X2_SERIAL_RX_PIN X2_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PE15
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PD10
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define Z2_SERIAL_TX_PIN PD11
- #define Z2_SERIAL_RX_PIN Z2_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PD7
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN PC14
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
-
#define E2_SERIAL_TX_PIN PC15
- #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN
#endif
//
diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING407.h b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING407.h
index 4a1960367cff..2164223d4433 100644
--- a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING407.h
+++ b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING407.h
@@ -144,37 +144,20 @@
// TMC2208/TMC2209 stepper drivers
//
#define X_SERIAL_TX_PIN PD2
- #define X_SERIAL_RX_PIN PD2
-
#define X2_SERIAL_TX_PIN PE15
- #define X2_SERIAL_RX_PIN PE15
-
#define Y_SERIAL_TX_PIN PD8
- #define Y_SERIAL_RX_PIN PD8
-
#define Z_SERIAL_TX_PIN PD7
- #define Z_SERIAL_RX_PIN PD7
-
#define Z2_SERIAL_TX_PIN PC14
- #define Z2_SERIAL_RX_PIN PC14
-
#define E0_SERIAL_TX_PIN PC15
- #define E0_SERIAL_RX_PIN PC15
-
#define E1_SERIAL_TX_PIN PG3
- #define E1_SERIAL_RX_PIN PG3
-
#define E2_SERIAL_TX_PIN PD9
- #define E2_SERIAL_RX_PIN PD9
-
#define E3_SERIAL_TX_PIN PF5
- #define E3_SERIAL_RX_PIN PF5
-
#define E4_SERIAL_TX_PIN PG11
- #define E4_SERIAL_RX_PIN PG11
// Reduce baud rate to improve software serial reliability
- #define TMC_BAUD_RATE 19200
+ #ifndef TMC_BAUD_RATE
+ #define TMC_BAUD_RATE 19200
+ #endif
#endif
//
diff --git a/Marlin/src/pins/stm32f4/pins_I3DBEEZ9.h b/Marlin/src/pins/stm32f4/pins_I3DBEEZ9.h
index 6cd09d3ac884..79599d59287b 100644
--- a/Marlin/src/pins/stm32f4/pins_I3DBEEZ9.h
+++ b/Marlin/src/pins/stm32f4/pins_I3DBEEZ9.h
@@ -253,31 +253,14 @@
//#define E4_HARDWARE_SERIAL Serial1
#define X_SERIAL_TX_PIN PA15
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PB8
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PB9
- #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 PG15
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
-
#define E2_SERIAL_TX_PIN PG12
- #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN
-
#define E3_SERIAL_TX_PIN PE2
- #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN
-
#define E4_SERIAL_TX_PIN PG11
- #define E4_SERIAL_RX_PIN E4_SERIAL_TX_PIN
-
#define E5_SERIAL_TX_PIN PD2
- #define E5_SERIAL_RX_PIN E5_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#define TMC_BAUD_RATE 19200
@@ -443,7 +426,6 @@
#define E6_CS_PIN EXP1_06_PIN
#if HAS_TMC_UART
#define E6_SERIAL_TX_PIN EXP1_06_PIN
- #define E6_SERIAL_RX_PIN EXP1_06_PIN
#endif
#endif
@@ -456,7 +438,6 @@
#define E7_CS_PIN EXP1_04_PIN
#if HAS_TMC_UART
#define E7_SERIAL_TX_PIN EXP1_04_PIN
- #define E7_SERIAL_RX_PIN EXP1_04_PIN
#endif
#else
#define E7_ENABLE_PIN EXP2_07_PIN
@@ -471,7 +452,6 @@
#define E8_CS_PIN EXP1_02_PIN
#if HAS_TMC_UART
#define E8_SERIAL_TX_PIN EXP1_02_PIN
- #define E8_SERIAL_RX_PIN EXP1_02_PIN
#endif
#else
#define E8_ENABLE_PIN EXP2_07_PIN
diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h
index 879c318f8575..4b6dc89f0675 100644
--- a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h
+++ b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h
@@ -114,50 +114,31 @@
//#endif
#if HAS_TMC_UART
- /**
- * TMC2208/TMC2209 stepper drivers
- */
+ //
+ // TMC2208/TMC2209 stepper drivers
+ //
#ifndef X_SERIAL_TX_PIN
#define X_SERIAL_TX_PIN PB2
#endif
- #ifndef X_SERIAL_RX_PIN
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
- #endif
#ifndef Y_SERIAL_TX_PIN
#define Y_SERIAL_TX_PIN PE2
#endif
- #ifndef Y_SERIAL_RX_PIN
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
- #endif
#ifndef Z_SERIAL_TX_PIN
#define Z_SERIAL_TX_PIN PE3
#endif
- #ifndef Z_SERIAL_RX_PIN
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
- #endif
#ifndef E0_SERIAL_TX_PIN
#define E0_SERIAL_TX_PIN PE4
#endif
- #ifndef E0_SERIAL_RX_PIN
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
- #endif
#ifndef E1_SERIAL_TX_PIN
#define E1_SERIAL_TX_PIN PE1
#endif
- #ifndef E1_SERIAL_RX_PIN
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
- #endif
// Ex-motor can be any... X2/Y2/Z2 or E2
#ifndef EX_SERIAL_TX_PIN
#define EX_SERIAL_TX_PIN PE0
#endif
- #ifndef EX_SERIAL_RX_PIN
- #define EX_SERIAL_RX_PIN EX_SERIAL_TX_PIN
- #endif
- //#define Z2_SERIAL_RX_PIN EX_SERIAL_RX_PIN
//#define Z2_SERIAL_TX_PIN EX_SERIAL_TX_PIN
- //#define E2_SERIAL_RX_PIN EX_SERIAL_RX_PIN
//#define E2_SERIAL_TX_PIN EX_SERIAL_TX_PIN
+
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
#define TMC_BAUD_RATE 19200
diff --git a/Marlin/src/pins/stm32f4/pins_MELLOW_FLY_E3_V2.h b/Marlin/src/pins/stm32f4/pins_MELLOW_FLY_E3_V2.h
index 248fc514ac40..2d48a3c709e8 100644
--- a/Marlin/src/pins/stm32f4/pins_MELLOW_FLY_E3_V2.h
+++ b/Marlin/src/pins/stm32f4/pins_MELLOW_FLY_E3_V2.h
@@ -204,19 +204,10 @@
// Software serial
//
#define X_SERIAL_TX_PIN PC15
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PB6
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PD7
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PD4
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN PD0
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
@@ -297,7 +288,6 @@
#define E2_CS_PIN EXP1_06_PIN
#if HAS_TMC_UART
#define E2_SERIAL_TX_PIN EXP1_06_PIN
- #define E2_SERIAL_RX_PIN EXP1_06_PIN
#endif
#endif
@@ -310,7 +300,6 @@
#define E3_CS_PIN EXP1_04_PIN
#if HAS_TMC_UART
#define E3_SERIAL_TX_PIN EXP1_04_PIN
- #define E3_SERIAL_RX_PIN EXP1_04_PIN
#endif
#else
#define E3_ENABLE_PIN EXP2_07_PIN
@@ -325,7 +314,6 @@
#define E4_CS_PIN EXP1_02_PIN
#if HAS_TMC_UART
#define E4_SERIAL_TX_PIN EXP1_02_PIN
- #define E4_SERIAL_RX_PIN EXP1_02_PIN
#endif
#else
#define E4_ENABLE_PIN EXP2_07_PIN
diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h
index b832a14b2ac9..b15c7d7288c6 100644
--- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h
+++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h
@@ -158,28 +158,13 @@
// No Hardware serial for steppers
//
#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
-
#define E4_SERIAL_TX_PIN PD11
- #define E4_SERIAL_RX_PIN E4_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h
index 050c8f242462..a3f65712712c 100644
--- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h
+++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h
@@ -100,19 +100,10 @@
// No Hardware serial for steppers
//
#define X_SERIAL_TX_PIN PD5
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PD7
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PD4
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PD9
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN PD8
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h
index 5af3cf53dd49..e8b9938c954f 100644
--- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h
+++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h
@@ -152,19 +152,10 @@
//#define E4_HARDWARE_SERIAL Serial1
#define X_SERIAL_TX_PIN PD5
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PD7
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PD4
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PD9
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN PD8
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h b/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h
index b20477a15db5..a0b088db4b3f 100644
--- a/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h
+++ b/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h
@@ -197,25 +197,12 @@
//
#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
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h
index cf400335f531..010ae0ec0573 100644
--- a/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h
+++ b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h
@@ -123,22 +123,11 @@
#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
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h
index 9c374eae4444..0f275788f927 100644
--- a/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h
+++ b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h
@@ -123,22 +123,11 @@
#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
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h
index 2f3e121fe17a..1712b24f2bda 100644
--- a/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h
+++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h
@@ -48,20 +48,9 @@
// TMC2208/TMC2209 Software Serial
//
#define X_SERIAL_TX_PIN PC14 // BTT Rumba32 only uses 1 pin for UART
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PE4
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PE0
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PC13
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN PD5
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
-
#define E2_SERIAL_TX_PIN PD1
- #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN
#endif
diff --git a/Marlin/src/pins/stm32f4/pins_XTLW_CLIMBER_8TH.h b/Marlin/src/pins/stm32f4/pins_XTLW_CLIMBER_8TH.h
index 2ce754847c26..9ab3331d4c15 100644
--- a/Marlin/src/pins/stm32f4/pins_XTLW_CLIMBER_8TH.h
+++ b/Marlin/src/pins/stm32f4/pins_XTLW_CLIMBER_8TH.h
@@ -146,22 +146,11 @@
#if HAS_TMC_UART
#define X_SERIAL_TX_PIN PC15
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define X2_SERIAL_TX_PIN PA8
- #define X2_SERIAL_RX_PIN X2_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PB6
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PD5
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PD1
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN PE9
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#define TMC_BAUD_RATE 19200
diff --git a/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h b/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h
index d9c542c6a281..46840868abdd 100644
--- a/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h
+++ b/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h
@@ -130,16 +130,9 @@
#if HAS_TMC_UART
#define X_SERIAL_TX_PIN PB9
- #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 PE12
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PG9
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
#endif
//
diff --git a/Marlin/src/pins/stm32g0/pins_BTT_EBB42_V1_1.h b/Marlin/src/pins/stm32g0/pins_BTT_EBB42_V1_1.h
index ffa644c88c47..2d6cdb73f43c 100644
--- a/Marlin/src/pins/stm32g0/pins_BTT_EBB42_V1_1.h
+++ b/Marlin/src/pins/stm32g0/pins_BTT_EBB42_V1_1.h
@@ -97,7 +97,6 @@
//#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
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_E3_EZ_V1_0.h b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_E3_EZ_V1_0.h
index 3489fe5c8fc1..ee7ea42bde50 100644
--- a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_E3_EZ_V1_0.h
+++ b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_E3_EZ_V1_0.h
@@ -155,19 +155,10 @@
#if HAS_TMC_UART
#define X_SERIAL_TX_PIN PB8 // X_CS_PIN
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PC9 // Y_CS_PIN
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PD0 // Z_CS_PIN
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PD1 // E0_CS_PIN
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN PB5 // E1_CS_PIN
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M4P_V2_1.h b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M4P_V2_1.h
index b7c5a8c470f8..4c4a6ca928ee 100644
--- a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M4P_V2_1.h
+++ b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M4P_V2_1.h
@@ -124,16 +124,9 @@
#if HAS_TMC_UART
#define X_SERIAL_TX_PIN PB12
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PC10
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PC9
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PA13
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M5P_V1_0.h b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M5P_V1_0.h
index 8d75638ee578..90379e06e62f 100644
--- a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M5P_V1_0.h
+++ b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M5P_V1_0.h
@@ -141,19 +141,10 @@
#if HAS_TMC_UART
#define X_SERIAL_TX_PIN PD9 // X_CS_PIN
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PD8 // Y_CS_PIN
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PB10 // Z_CS_PIN
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PB2 // E0_CS_PIN
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN PA6 // E1_CS_PIN
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_V1_0.h b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_V1_0.h
index b81dbe0dac26..0b105118e13d 100644
--- a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_V1_0.h
+++ b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_V1_0.h
@@ -55,13 +55,8 @@
#if HAS_TMC_UART
#define E1_SERIAL_TX_PIN PF8
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
-
#define E2_SERIAL_TX_PIN PD13
- #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN
-
#define E3_SERIAL_TX_PIN PC7
- #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_V1_1.h b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_V1_1.h
index 36aa3895c372..65071820d4e9 100644
--- a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_V1_1.h
+++ b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_V1_1.h
@@ -54,13 +54,8 @@
#if HAS_TMC_UART
#define E1_SERIAL_TX_PIN PF8
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
-
#define E2_SERIAL_TX_PIN PD14
- #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN
-
#define E3_SERIAL_TX_PIN PD10
- #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_common.h b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_common.h
index 327c5f1970ca..e00729208906 100644
--- a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_common.h
+++ b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_common.h
@@ -177,19 +177,10 @@
#if HAS_TMC_UART
#define X_SERIAL_TX_PIN PC10
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PF13
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PF9
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define Z2_SERIAL_TX_PIN PD4
- #define Z2_SERIAL_RX_PIN Z2_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PD0
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32g0/pins_BTT_SKRAT_V1_0.h b/Marlin/src/pins/stm32g0/pins_BTT_SKRAT_V1_0.h
index c010e0232552..cbdb8ed896ae 100644
--- a/Marlin/src/pins/stm32g0/pins_BTT_SKRAT_V1_0.h
+++ b/Marlin/src/pins/stm32g0/pins_BTT_SKRAT_V1_0.h
@@ -310,19 +310,10 @@
// Software serial
//
#define X_SERIAL_TX_PIN PF10
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PD4
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PC8
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PD8
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN PB11
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
@@ -415,7 +406,6 @@
#define E2_CS_PIN EXP1_06_PIN
#if HAS_TMC_UART
#define E2_SERIAL_TX_PIN EXP1_06_PIN
- #define E2_SERIAL_RX_PIN EXP1_06_PIN
#endif
#endif
@@ -428,7 +418,6 @@
#define E3_CS_PIN EXP1_04_PIN
#if HAS_TMC_UART
#define E3_SERIAL_TX_PIN EXP1_04_PIN
- #define E3_SERIAL_RX_PIN EXP1_04_PIN
#endif
#else
#define E3_ENABLE_PIN EXP2_07_PIN
@@ -443,7 +432,6 @@
#define E4_CS_PIN EXP1_02_PIN
#if HAS_TMC_UART
#define E4_SERIAL_TX_PIN EXP1_02_PIN
- #define E4_SERIAL_RX_PIN EXP1_02_PIN
#endif
#else
#define E4_ENABLE_PIN EXP2_07_PIN
diff --git a/Marlin/src/pins/stm32h7/pins_BTT_KRAKEN_V1_0.h b/Marlin/src/pins/stm32h7/pins_BTT_KRAKEN_V1_0.h
index 13bb1b7d8b03..9f67c7a14cea 100644
--- a/Marlin/src/pins/stm32h7/pins_BTT_KRAKEN_V1_0.h
+++ b/Marlin/src/pins/stm32h7/pins_BTT_KRAKEN_V1_0.h
@@ -426,7 +426,6 @@
#define E4_CS_PIN EXP1_06_PIN
#if HAS_TMC_UART
#define E4_SERIAL_TX_PIN EXP1_06_PIN
- #define E4_SERIAL_RX_PIN E4_SERIAL_TX_PIN
#endif
// M2 on Driver Expansion Module
@@ -437,7 +436,6 @@
#define E5_CS_PIN EXP1_04_PIN
#if HAS_TMC_UART
#define E5_SERIAL_TX_PIN EXP1_04_PIN
- #define E5_SERIAL_RX_PIN E5_SERIAL_TX_PIN
#endif
// M3 on Driver Expansion Module
@@ -448,7 +446,6 @@
#define E6_CS_PIN EXP1_02_PIN
#if HAS_TMC_UART
#define E6_SERIAL_TX_PIN EXP1_02_PIN
- #define E6_SERIAL_RX_PIN E6_SERIAL_TX_PIN
#endif
#endif // BTT_MOTOR_EXPANSION
diff --git a/Marlin/src/pins/stm32h7/pins_BTT_MANTA_M8P_V2_0.h b/Marlin/src/pins/stm32h7/pins_BTT_MANTA_M8P_V2_0.h
index 2c5c4bc05e8b..496668513d41 100644
--- a/Marlin/src/pins/stm32h7/pins_BTT_MANTA_M8P_V2_0.h
+++ b/Marlin/src/pins/stm32h7/pins_BTT_MANTA_M8P_V2_0.h
@@ -315,28 +315,13 @@
//#define E4_HARDWARE_SERIAL Serial1
#define X_SERIAL_TX_PIN PC13
- #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 PB9
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define Z2_SERIAL_TX_PIN PB5
- #define Z2_SERIAL_RX_PIN Z2_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PG14
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN PG10
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
-
#define E2_SERIAL_TX_PIN PD5
- #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN
-
#define E3_SERIAL_TX_PIN PC6
- #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h b/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h
index 3ceb9561ab4d..a6948cd08c34 100644
--- a/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h
+++ b/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h
@@ -301,34 +301,17 @@
//#define E4_HARDWARE_SERIAL Serial1
#define X_SERIAL_TX_PIN PG14
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PG13
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PG12
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define Z2_SERIAL_TX_PIN PG11
- #define Z2_SERIAL_RX_PIN Z2_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PG10
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN PG9
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
-
#define E2_SERIAL_TX_PIN PD7
- #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN
-
#define E3_SERIAL_TX_PIN PD6
- #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN
-
#define E4_SERIAL_TX_PIN PG8
- #define E4_SERIAL_RX_PIN E3_SERIAL_TX_PIN
-
+ #define E4_SERIAL_RX_PIN E3_SERIAL_RX_PIN
#define E5_SERIAL_TX_PIN PG7
- #define E5_SERIAL_RX_PIN E3_SERIAL_TX_PIN
+ #define E5_SERIAL_RX_PIN E3_SERIAL_RX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
diff --git a/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_PRO_V1_common.h b/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_PRO_V1_common.h
index 113b7eac290c..45ca3c5588eb 100644
--- a/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_PRO_V1_common.h
+++ b/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_PRO_V1_common.h
@@ -293,28 +293,13 @@
//#define E4_HARDWARE_SERIAL Serial1
#define X_SERIAL_TX_PIN PC4
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PD11
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PC6
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define Z2_SERIAL_TX_PIN PC7
- #define Z2_SERIAL_RX_PIN Z2_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PF2
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN PE4
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
-
#define E2_SERIAL_TX_PIN PE1
- #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN
-
#define E3_SERIAL_TX_PIN PD3
- #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
@@ -395,7 +380,6 @@
#define E4_CS_PIN EXP1_06_PIN
#if HAS_TMC_UART
#define E4_SERIAL_TX_PIN EXP1_06_PIN
- #define E4_SERIAL_RX_PIN E4_SERIAL_TX_PIN
#endif
// M2 on Driver Expansion Module
@@ -406,7 +390,6 @@
#define E5_CS_PIN EXP1_04_PIN
#if HAS_TMC_UART
#define E5_SERIAL_TX_PIN EXP1_04_PIN
- #define E5_SERIAL_RX_PIN E5_SERIAL_TX_PIN
#endif
// M3 on Driver Expansion Module
@@ -417,7 +400,6 @@
#define E6_CS_PIN EXP1_02_PIN
#if HAS_TMC_UART
#define E6_SERIAL_TX_PIN EXP1_02_PIN
- #define E6_SERIAL_RX_PIN E6_SERIAL_TX_PIN
#endif
#endif // BTT_MOTOR_EXPANSION
diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h
index 7314ccc825d4..f6f8442cdfe9 100644
--- a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h
+++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h
@@ -159,28 +159,18 @@
//#define E7_HARDWARE_SERIAL Serial1
#define X_SERIAL_TX_PIN PG10
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PD4
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#ifdef BX_SWAP_ZM_E1M
#define Z_SERIAL_TX_PIN PC8
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
#else
#define Z_SERIAL_TX_PIN PD5
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
#endif
#define E0_SERIAL_TX_PIN PI8
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#ifdef BX_SWAP_ZM_E1M
#define E1_SERIAL_TX_PIN PD5
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
#else
#define E1_SERIAL_TX_PIN PC8
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
#endif
// Reduce baud rate to improve software serial reliability
diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h
index b67992186315..fce16aebf112 100644
--- a/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h
+++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h
@@ -298,19 +298,10 @@
// Software serial
//
#define X_SERIAL_TX_PIN PD5
- #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN
-
#define Y_SERIAL_TX_PIN PD0
- #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN
-
#define Z_SERIAL_TX_PIN PE1
- #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN
-
#define E0_SERIAL_TX_PIN PC6
- #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN
-
#define E1_SERIAL_TX_PIN PD12
- #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN
// Reduce baud rate to improve software serial reliability
#ifndef TMC_BAUD_RATE
@@ -394,7 +385,6 @@
#define E2_CS_PIN EXP1_06_PIN
#if HAS_TMC_UART
#define E2_SERIAL_TX_PIN EXP1_06_PIN
- #define E2_SERIAL_RX_PIN EXP1_06_PIN
#endif
#endif
@@ -407,7 +397,6 @@
#define E3_CS_PIN EXP1_04_PIN
#if HAS_TMC_UART
#define E3_SERIAL_TX_PIN EXP1_04_PIN
- #define E3_SERIAL_RX_PIN EXP1_04_PIN
#endif
#else
#define E3_ENABLE_PIN EXP2_07_PIN
@@ -422,7 +411,6 @@
#define E4_CS_PIN EXP1_02_PIN
#if HAS_TMC_UART
#define E4_SERIAL_TX_PIN EXP1_02_PIN
- #define E4_SERIAL_RX_PIN EXP1_02_PIN
#endif
#else
#define E4_ENABLE_PIN EXP2_07_PIN
diff --git a/buildroot/share/PlatformIO/boards/marlin_CREALITY_STM32F401RE.json b/buildroot/share/PlatformIO/boards/marlin_STM32F401RE_creality.json
similarity index 96%
rename from buildroot/share/PlatformIO/boards/marlin_CREALITY_STM32F401RE.json
rename to buildroot/share/PlatformIO/boards/marlin_STM32F401RE_creality.json
index 31739c3a386a..031d804691a7 100644
--- a/buildroot/share/PlatformIO/boards/marlin_CREALITY_STM32F401RE.json
+++ b/buildroot/share/PlatformIO/boards/marlin_STM32F401RE_creality.json
@@ -16,7 +16,7 @@
],
"ldscript": "ldscript.ld",
"mcu": "stm32f401ret6",
- "variant": "MARLIN_CREALITY_STM32F401RE"
+ "variant": "MARLIN_F401RE_CREALITY"
},
"debug": {
"jlink_device": "STM32F401RE",
diff --git a/buildroot/share/PlatformIO/boards/marlin_STM32F401RE_freeruns.json b/buildroot/share/PlatformIO/boards/marlin_STM32F401RE_freeruns.json
index 3a8848e93418..96f06b3c029b 100644
--- a/buildroot/share/PlatformIO/boards/marlin_STM32F401RE_freeruns.json
+++ b/buildroot/share/PlatformIO/boards/marlin_STM32F401RE_freeruns.json
@@ -16,7 +16,7 @@
],
"ldscript": "ldscript.ld",
"mcu": "stm32f401ret6",
- "variant": "MARLIN_STM32F401RE_FREERUNS"
+ "variant": "MARLIN_F401RE_FREERUNS"
},
"debug": {
"jlink_device": "STM32F401RE",
diff --git a/buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py b/buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py
index 1ded5b4b8a24..6fa53ef57f15 100644
--- a/buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py
+++ b/buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py
@@ -3,28 +3,41 @@
#
import pioutil
if pioutil.is_pio_build():
- import shutil, marlin
from pathlib import Path
- env = pioutil.env
- platform = env.PioPlatform()
- board = env.BoardConfig()
-
- FRAMEWORK_DIR = Path(platform.get_package_dir("framework-arduinoststm32-maple"))
- assert FRAMEWORK_DIR.is_dir()
- source_root = Path("buildroot/share/PlatformIO/variants")
+ source_root_str = "buildroot/share/PlatformIO/variants"
+ source_root = Path(source_root_str)
assert source_root.is_dir()
+ env = pioutil.env
+ board = env.BoardConfig()
variant = board.get("build.variant")
- variant_dir = FRAMEWORK_DIR / "STM32F1/variants" / variant
source_dir = source_root / variant
assert source_dir.is_dir()
- if variant_dir.is_dir():
- shutil.rmtree(variant_dir)
+ if True:
+ # Copying to the platform folder is still needed by STM32F1 (Maple).
+ # The alternative code below comes close. See if you can solve it!
+ platform = env.PioPlatform()
+ FRAMEWORK_DIR = Path(platform.get_package_dir("framework-arduinoststm32-maple"))
+ assert FRAMEWORK_DIR.is_dir()
+
+ variant_dir = FRAMEWORK_DIR / "STM32F1/variants" / variant
+
+ if variant_dir.is_dir():
+ import shutil
+ shutil.rmtree(variant_dir)
+
+ if not variant_dir.is_dir():
+ variant_dir.mkdir()
+
+ import marlin
+ marlin.copytree(source_dir, variant_dir)
- if not variant_dir.is_dir():
- variant_dir.mkdir()
+ else:
- marlin.copytree(source_dir, variant_dir)
+ # The following almost works, but __start__ (from wirish/start.S) is not seen by common.inc
+ board.update("build.variants_dir", source_root_str);
+ src = str(source_dir)
+ env.Append(BUILD_FLAGS=[f"-I{src}", f"-L{src}/ld"]) # Add include path for variant
diff --git a/buildroot/share/PlatformIO/scripts/common-dependencies.py b/buildroot/share/PlatformIO/scripts/common-dependencies.py
index 6c76cb8c5e1b..6be716ae4647 100644
--- a/buildroot/share/PlatformIO/scripts/common-dependencies.py
+++ b/buildroot/share/PlatformIO/scripts/common-dependencies.py
@@ -188,77 +188,75 @@ def apply_features_config():
set_env_field('lib_ignore', lib_ignore)
build_src_filter = ""
- if True:
- # Build the actual equivalent build_src_filter list based on the inclusions by the features.
- # PlatformIO doesn't do it this way, but maybe in the future....
- cur_srcs = set()
- # Remove the references to the same folder
- my_srcs = re.findall(r'([+-]<.*?>)', build_filters)
- for d in my_srcs:
- # Assume normalized relative paths
- plain = d[2:-1]
- if d[0] == '+':
- def addentry(fullpath, info=None):
- relp = os.path.relpath(fullpath, marlinbasedir)
- if srcfilepattern.match(relp):
- if info:
- blab("Added src file %s (%s)" % (relp, str(info)), 3)
- else:
- blab("Added src file %s " % relp, 3)
- cur_srcs.add(relp)
- # Special rule: If a direct folder is specified add all files within.
- fullplain = os.path.join(marlinbasedir, plain)
- if os.path.isdir(fullplain):
- blab("Directory content addition for %s " % plain, 3)
- gpattern = os.path.join(fullplain, "**")
- for fname in glob.glob(gpattern, recursive=True):
- addentry(fname, "dca")
- else:
- # Add all the things from the pattern by GLOB.
- def srepl(matchi):
- g0 = matchi.group(0)
- return r"**" + g0[1:]
- gpattern = re.sub(r'[*]($|[^*])', srepl, plain)
- gpattern = os.path.join(marlinbasedir, gpattern)
-
- for fname in glob.glob(gpattern, recursive=True):
- addentry(fname)
- else:
- # Special rule: If a direct folder is specified then remove all files within.
- def onremove(relp, info=None):
+
+ # Build the actual equivalent build_src_filter list based on the inclusions by the features.
+ # PlatformIO doesn't do it this way, but maybe in the future....
+ cur_srcs = set()
+ # Remove the references to the same folder
+ my_srcs = re.findall(r'([+-]<.*?>)', build_filters)
+ for d in my_srcs:
+ # Assume normalized relative paths
+ plain = d[2:-1]
+ if d[0] == '+':
+ def addentry(fullpath, info=None):
+ relp = os.path.relpath(fullpath, marlinbasedir)
+ if srcfilepattern.match(relp):
if info:
- blab("Removed src file %s (%s)" % (relp, str(info)), 3)
+ blab("Added src file %s (%s)" % (relp, str(info)), 3)
else:
- blab("Removed src file %s " % relp, 3)
- fullplain = os.path.join(marlinbasedir, plain)
- if os.path.isdir(fullplain):
- blab("Directory content removal for %s " % plain, 2)
- def filt(x):
- common = os.path.commonpath([plain, x])
- if not common == os.path.normpath(plain): return True
- onremove(x, "dcr")
- return False
- cur_srcs = set(filter(filt, cur_srcs))
+ blab("Added src file %s " % relp, 3)
+ cur_srcs.add(relp)
+ # Special rule: If a direct folder is specified add all files within.
+ fullplain = os.path.join(marlinbasedir, plain)
+ if os.path.isdir(fullplain):
+ blab("Directory content addition for %s " % plain, 3)
+ gpattern = os.path.join(fullplain, "**")
+ for fname in glob.glob(gpattern, recursive=True):
+ addentry(fname, "dca")
+ else:
+ # Add all the things from the pattern by GLOB.
+ def srepl(matchi):
+ g0 = matchi.group(0)
+ return r"**" + g0[1:]
+ gpattern = re.sub(r'[*]($|[^*])', srepl, plain)
+ gpattern = os.path.join(marlinbasedir, gpattern)
+
+ for fname in glob.glob(gpattern, recursive=True):
+ addentry(fname)
+ else:
+ # Special rule: If a direct folder is specified then remove all files within.
+ def onremove(relp, info=None):
+ if info:
+ blab("Removed src file %s (%s)" % (relp, str(info)), 3)
else:
- # Remove matching source entries.
- def filt(x):
- if not fnmatch.fnmatch(x, plain): return True
- onremove(x)
- return False
- cur_srcs = set(filter(filt, cur_srcs))
- # Transform the resulting set into a string.
- for x in cur_srcs:
- if build_src_filter != "": build_src_filter += ' '
- build_src_filter += "+<" + x + ">"
-
- #blab("Final build_src_filter: " + build_src_filter, 3)
- else:
- build_src_filter = build_filters
+ blab("Removed src file %s " % relp, 3)
+ fullplain = os.path.join(marlinbasedir, plain)
+ if os.path.isdir(fullplain):
+ blab("Directory content removal for %s " % plain, 2)
+ def filt(x):
+ common = os.path.commonpath([plain, x])
+ if not common == os.path.normpath(plain): return True
+ onremove(x, "dcr")
+ return False
+ cur_srcs = set(filter(filt, cur_srcs))
+ else:
+ # Remove matching source entries.
+ def filt(x):
+ if not fnmatch.fnmatch(x, plain): return True
+ onremove(x)
+ return False
+ cur_srcs = set(filter(filt, cur_srcs))
+ # Transform the resulting set into a string.
+ for x in cur_srcs:
+ if build_src_filter != "": build_src_filter += ' '
+ build_src_filter += "+<" + x + ">"
# Update in PlatformIO
set_env_field('build_src_filter', [build_src_filter])
env.Replace(SRC_FILTER=build_src_filter)
+ #blab("Final build_src_filter: " + build_src_filter, 3)
+
#
# Use the compiler to get a list of all enabled features
#
diff --git a/buildroot/share/PlatformIO/scripts/generic_create_variant.py b/buildroot/share/PlatformIO/scripts/generic_create_variant.py
index db7f2e89e71a..cfab812e1503 100644
--- a/buildroot/share/PlatformIO/scripts/generic_create_variant.py
+++ b/buildroot/share/PlatformIO/scripts/generic_create_variant.py
@@ -40,26 +40,19 @@
FRAMEWORK_DIR = Path(platform.get_package_dir(platform_name))
assert FRAMEWORK_DIR.is_dir()
+ #
+ # Point variants_dir to our variant folder when board_build.variant
+ # is provided and the variant name begins with "marlin_".
+ #
board = env.BoardConfig()
-
- #mcu_type = board.get("build.mcu")[:-2]
variant = board.get("build.variant")
+ #mcu_type = board.get("build.mcu")[:-2]
#series = mcu_type[:7].upper() + "xx"
- # Only prepare a new variant if the PlatformIO configuration provides it (board_build.variant).
- # This check is important to avoid deleting official board config variants.
+ # Make sure the local variant sub-folder exists
if marlin_variant_pattern.match(str(variant).lower()):
- # Prepare a new empty folder at the destination
- variant_dir = FRAMEWORK_DIR / "variants" / variant
- if variant_dir.is_dir():
- shutil.rmtree(variant_dir)
- if not variant_dir.is_dir():
- variant_dir.mkdir()
-
- # Source dir is a local variant sub-folder
- source_dir = Path("buildroot/share/PlatformIO/variants", variant)
+ here = Path.cwd()
+ variants_dir = here / 'buildroot' / 'share' / 'PlatformIO' / 'variants'
+ source_dir = variants_dir / variant
assert source_dir.is_dir()
-
- print("Copying variant " + str(variant) + " to framework directory...")
-
- marlin.copytree(source_dir, variant_dir)
+ board.update("build.variants_dir", str(variants_dir));
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/PeripheralPins.c
similarity index 100%
rename from buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/PeripheralPins.c
rename to buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/PeripheralPins.c
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/PinNamesVar.h
similarity index 100%
rename from buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/PinNamesVar.h
rename to buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/PinNamesVar.h
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/hal_conf_custom.h
similarity index 100%
rename from buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/hal_conf_custom.h
rename to buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/hal_conf_custom.h
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/ldscript.ld
similarity index 100%
rename from buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/ldscript.ld
rename to buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/ldscript.ld
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/variant.cpp
similarity index 100%
rename from buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/variant.cpp
rename to buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/variant.cpp
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/variant.h
similarity index 100%
rename from buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/variant.h
rename to buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/variant.h
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_F401RE_CREALITY/PeripheralPins.c
similarity index 100%
rename from buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/PeripheralPins.c
rename to buildroot/share/PlatformIO/variants/MARLIN_F401RE_CREALITY/PeripheralPins.c
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_F401RE_CREALITY/PinNamesVar.h
similarity index 100%
rename from buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/PinNamesVar.h
rename to buildroot/share/PlatformIO/variants/MARLIN_F401RE_CREALITY/PinNamesVar.h
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_F401RE_CREALITY/hal_conf_custom.h
similarity index 100%
rename from buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/hal_conf_custom.h
rename to buildroot/share/PlatformIO/variants/MARLIN_F401RE_CREALITY/hal_conf_custom.h
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F401RE_CREALITY/ldscript.ld
similarity index 100%
rename from buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/ldscript.ld
rename to buildroot/share/PlatformIO/variants/MARLIN_F401RE_CREALITY/ldscript.ld
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_F401RE_CREALITY/variant.cpp
similarity index 100%
rename from buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/variant.cpp
rename to buildroot/share/PlatformIO/variants/MARLIN_F401RE_CREALITY/variant.cpp
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F401RE_CREALITY/variant.h
similarity index 100%
rename from buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/variant.h
rename to buildroot/share/PlatformIO/variants/MARLIN_F401RE_CREALITY/variant.h
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_STM32F401RE_FREERUNS/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_F401RE_FREERUNS/PeripheralPins.c
similarity index 100%
rename from buildroot/share/PlatformIO/variants/MARLIN_STM32F401RE_FREERUNS/PeripheralPins.c
rename to buildroot/share/PlatformIO/variants/MARLIN_F401RE_FREERUNS/PeripheralPins.c
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_STM32F401RE_FREERUNS/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_F401RE_FREERUNS/PinNamesVar.h
similarity index 100%
rename from buildroot/share/PlatformIO/variants/MARLIN_STM32F401RE_FREERUNS/PinNamesVar.h
rename to buildroot/share/PlatformIO/variants/MARLIN_F401RE_FREERUNS/PinNamesVar.h
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_STM32F401RE_FREERUNS/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_F401RE_FREERUNS/hal_conf_custom.h
similarity index 100%
rename from buildroot/share/PlatformIO/variants/MARLIN_STM32F401RE_FREERUNS/hal_conf_custom.h
rename to buildroot/share/PlatformIO/variants/MARLIN_F401RE_FREERUNS/hal_conf_custom.h
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_STM32F401RE_FREERUNS/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F401RE_FREERUNS/ldscript.ld
similarity index 100%
rename from buildroot/share/PlatformIO/variants/MARLIN_STM32F401RE_FREERUNS/ldscript.ld
rename to buildroot/share/PlatformIO/variants/MARLIN_F401RE_FREERUNS/ldscript.ld
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_STM32F401RE_FREERUNS/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_F401RE_FREERUNS/variant.cpp
similarity index 100%
rename from buildroot/share/PlatformIO/variants/MARLIN_STM32F401RE_FREERUNS/variant.cpp
rename to buildroot/share/PlatformIO/variants/MARLIN_F401RE_FREERUNS/variant.cpp
diff --git a/buildroot/share/PlatformIO/variants/MARLIN_STM32F401RE_FREERUNS/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F401RE_FREERUNS/variant.h
similarity index 100%
rename from buildroot/share/PlatformIO/variants/MARLIN_STM32F401RE_FREERUNS/variant.h
rename to buildroot/share/PlatformIO/variants/MARLIN_F401RE_FREERUNS/variant.h
diff --git a/buildroot/share/scripts/pinsformat.py b/buildroot/share/scripts/pinsformat.py
index 7b041c86fcb2..0260d3174e17 100755
--- a/buildroot/share/scripts/pinsformat.py
+++ b/buildroot/share/scripts/pinsformat.py
@@ -43,7 +43,7 @@ def concat_with_space(s1, s2):
ppad = [ 3, 4, 5, 5 ]
# Match a define line
-definePatt = re.compile(rf'^\s*(//)?#define\s+[A-Z_][A-Z0-9_]+\s+({mstr})\s*(//.*)?$')
+definePinPatt = re.compile(rf'^\s*(//)?#define\s+[A-Z_][A-Z0-9_]+?_PIN\s+({mstr})\s*(//.*)?$')
def format_pins(argv):
src_file = 'stdin'
@@ -93,7 +93,7 @@ def get_pin_pattern(txt):
# Find the most common matching pattern
match_threshold = 5
for line in txt.split('\n'):
- r = definePatt.match(line)
+ r = definePinPatt.match(line)
if r == None: continue
ind = -1
for p in mexpr:
diff --git a/buildroot/tests/DUE b/buildroot/tests/DUE
index ca225d87ddc9..33f6bd511a65 100755
--- a/buildroot/tests/DUE
+++ b/buildroot/tests/DUE
@@ -48,5 +48,5 @@ exec_test $1 $2 "RADDS with ABL (Bilinear), Triple Z Axis, Z_STEPPER_AUTO_ALIGN,
#
restore_configs
opt_set MOTHERBOARD BOARD_RAMPS4DUE_EEF LCD_LANGUAGE fi EXTRUDERS 2 TEMP_SENSOR_BED 0 NUM_SERVOS 1
-opt_enable SWITCHING_EXTRUDER ULTIMAKERCONTROLLER BEEP_ON_FEEDRATE_CHANGE POWER_LOSS_RECOVERY
-exec_test $1 $2 "RAMPS4DUE_EEF with SWITCHING_EXTRUDER, POWER_LOSS_RECOVERY" "$3"
+opt_enable SWITCHING_EXTRUDER ULTIMAKERCONTROLLER BEEP_ON_FEEDRATE_CHANGE CANCEL_OBJECTS POWER_LOSS_RECOVERY
+exec_test $1 $2 "RAMPS4DUE_EEF with SWITCHING_EXTRUDER, CANCEL_OBJECTS, POWER_LOSS_RECOVERY" "$3"
diff --git a/buildroot/tests/HC32F460C_aquila_101 b/buildroot/tests/HC32F460C_aquila_101
index 0544720891a7..00b286fa6df1 100755
--- a/buildroot/tests/HC32F460C_aquila_101
+++ b/buildroot/tests/HC32F460C_aquila_101
@@ -8,7 +8,7 @@ set -e
restore_configs
opt_set MOTHERBOARD BOARD_AQUILA_V101 SERIAL_PORT 1
-opt_enable EEPROM_SETTINGS SDSUPPORT EMERGENCY_PARSER
+opt_enable EEPROM_SETTINGS SDSUPPORT EMERGENCY_PARSER PINS_DEBUGGING
exec_test $1 $2 "Default Configuration with Fallback SD EEPROM" "$3"
# cleanup
diff --git a/buildroot/tests/LPC1768 b/buildroot/tests/LPC1768
index 5891ae0d8572..3a08af8ae82e 100755
--- a/buildroot/tests/LPC1768
+++ b/buildroot/tests/LPC1768
@@ -17,7 +17,9 @@ restore_configs
opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB SERIAL_PORT_3 3 \
NEOPIXEL_TYPE NEO_RGB RGB_LED_R_PIN P2_12 RGB_LED_G_PIN P1_23 RGB_LED_B_PIN P1_22 RGB_LED_W_PIN P1_24
opt_enable FYSETC_MINI_12864_2_1 SDSUPPORT SDCARD_READONLY SERIAL_PORT_2 RGBW_LED E_DUAL_STEPPER_DRIVERS \
- NEOPIXEL_LED NEOPIXEL_IS_SEQUENTIAL NEOPIXEL_STARTUP_TEST NEOPIXEL_BKGD_INDEX_FIRST NEOPIXEL_BKGD_INDEX_LAST NEOPIXEL_BKGD_COLOR NEOPIXEL_BKGD_TIMEOUT_COLOR NEOPIXEL_BKGD_ALWAYS_ON
+ NEOPIXEL_LED NEOPIXEL_IS_SEQUENTIAL NEOPIXEL_STARTUP_TEST NEOPIXEL_BKGD_INDEX_FIRST NEOPIXEL_BKGD_INDEX_LAST \
+ NEOPIXEL_BKGD_COLOR NEOPIXEL_BKGD_TIMEOUT_COLOR NEOPIXEL_BKGD_ALWAYS_ON \
+ PINS_DEBUGGING
exec_test $1 $2 "ReARM EFB VIKI2, SDSUPPORT, 2 Serial ports (USB CDC + UART0), NeoPixel" "$3"
#restore_configs
diff --git a/buildroot/tests/SAMD51_grandcentral_m4 b/buildroot/tests/SAMD51_grandcentral_m4
index da2cdd30b0d0..d4c4cea12219 100755
--- a/buildroot/tests/SAMD51_grandcentral_m4
+++ b/buildroot/tests/SAMD51_grandcentral_m4
@@ -27,5 +27,5 @@ opt_enable ENDSTOP_INTERRUPTS_FEATURE S_CURVE_ACCELERATION BLTOUCH Z_MIN_PROBE_R
MOVE_Z_WHEN_IDLE BABYSTEP_ZPROBE_OFFSET BABYSTEP_GFX_OVERLAY \
LIN_ADVANCE ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE MONITOR_DRIVER_STATUS \
SENSORLESS_HOMING X_STALL_SENSITIVITY Y_STALL_SENSITIVITY Z_STALL_SENSITIVITY Z2_STALL_SENSITIVITY \
- EDGE_STEPPING TMC_DEBUG
+ EDGE_STEPPING TMC_DEBUG PINS_DEBUGGING
exec_test $1 $2 "Grand Central M4 with assorted features" "$3"
diff --git a/buildroot/tests/SKR_Pico b/buildroot/tests/SKR_Pico
new file mode 100755
index 000000000000..1564a2c327e5
--- /dev/null
+++ b/buildroot/tests/SKR_Pico
@@ -0,0 +1,18 @@
+#!/usr/bin/env bash
+#
+# Build tests for BTT SKR Pico
+#
+
+# exit on first failure
+set -e
+
+#
+# Build with the default configurations
+#
+restore_configs
+opt_set MOTHERBOARD BOARD_BTT_SKR_PICO NUM_SERVOS 1
+opt_enable Z_PROBE_SERVO_NR Z_SERVO_ANGLES Z_SAFE_HOMING M114_DETAIL
+exec_test $1 $2 "Default Configuration" "$3"
+
+# clean up
+restore_configs
diff --git a/buildroot/tests/teensy41 b/buildroot/tests/teensy41
index e0e573ca43ff..6cf3f4aba3a3 100755
--- a/buildroot/tests/teensy41
+++ b/buildroot/tests/teensy41
@@ -28,7 +28,7 @@ opt_enable MAX31865_SENSOR_OHMS_0 MAX31865_CALIBRATION_OHMS_0 \
PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE SLOW_PWM_HEATERS PIDTEMPBED EEPROM_SETTINGS INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT \
ADVANCED_PAUSE_FEATURE ARC_SUPPORT BEZIER_CURVE_SUPPORT EXPERIMENTAL_I2CBUS EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES PARK_HEAD_ON_PAUSE \
PHOTO_GCODE PHOTO_POSITION PHOTO_SWITCH_POSITION PHOTO_SWITCH_MS PHOTO_DELAY_MS PHOTO_RETRACT_MM \
- HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT HOST_STATUS_NOTIFICATIONS
+ HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT HOST_STATUS_NOTIFICATIONS PINS_DEBUGGING
opt_add EXTUI_EXAMPLE
exec_test $1 $2 "Teensy4.1 with many features" "$3"
diff --git a/ini/native.ini b/ini/native.ini
index 69233cdf0001..5b62c87add5e 100644
--- a/ini/native.ini
+++ b/ini/native.ini
@@ -83,7 +83,7 @@ build_flags = ${simulator_linux.build_flags} ${simulator_linux.release_flags}
#
# MacPorts:
-# sudo port install gcc14 glm libsdl2 libsdl2_net
+# sudo port install gcc14 glm mesa libsdl2 libsdl2_net
#
# cd /opt/local/bin
# sudo rm gcc g++ cc ld
@@ -92,24 +92,18 @@ build_flags = ${simulator_linux.build_flags} ${simulator_linux.release_flags}
# cd -
# rehash
#
-# Use 'sudo port install mesa' to get a if no Xcode is installed.
-# If Xcode is installed be sure to run `xcode-select --install` first.
-#
#==================================================================================
#
# Homebrew:
# /bin/bash -c "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/HEAD/install.sh)"
#
-# brew install gcc@14 glm sdl2 sdl2_net
+# brew install gcc@14 glm mesa sdl2 sdl2_net
#
# cd /opt/homebrew/bin
# sudo rm -f gcc g++ cc
# sudo ln -s gcc-14 gcc ; sudo ln -s g++-14 g++ ; sudo ln -s g++ cc
# cd -
#
-# Use 'brew install mesa' to get a if no Xcode is installed.
-# If Xcode is installed be sure to run `xcode-select --install` first.
-#
[simulator_macos]
build_unflags = -g3 -lGL -fstack-protector-strong
diff --git a/ini/raspberrypi.ini b/ini/raspberrypi.ini
new file mode 100644
index 000000000000..c61b89b461f0
--- /dev/null
+++ b/ini/raspberrypi.ini
@@ -0,0 +1,37 @@
+#
+# Marlin Firmware
+# PlatformIO Configuration File
+#
+# See https://arduino-pico.readthedocs.io/en/latest/platformio.html
+#
+
+[env:RP2040]
+platform = raspberrypi
+board = pico
+framework = arduino
+#board_build.core = earlephilhower
+#lib_ldf_mode = off
+#lib_compat_mode = strict
+build_src_filter = ${common.default_src_filter} +
+lib_deps = ${common.lib_deps}
+ arduino-libraries/Servo
+ https://github.com/pkElectronics/SoftwareSerialM#master
+ #lvgl/lvgl@^8.1.0
+lib_ignore = WiFi
+build_flags = ${common.build_flags} -D__PLAT_RP2040__ -DPLATFORM_M997_SUPPORT -Wno-expansion-to-defined -Wno-vla -Wno-ignored-qualifiers
+#debug_tool = jlink
+#upload_protocol = jlink
+
+[env:RP2040-alt]
+extends = env:RP2040
+platform = https://github.com/maxgerhardt/platform-raspberrypi.git
+board_build.core = earlephilhower
+
+#
+# BigTreeTech SKR Pico 1.x
+#
+[env:SKR_Pico]
+extends = env:RP2040
+
+[env:SKR_Pico_UART]
+extends = env:SKR_Pico
diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini
index 453531d27ba8..b2f14a61644b 100644
--- a/ini/stm32f1-maple.ini
+++ b/ini/stm32f1-maple.ini
@@ -64,6 +64,7 @@ monitor_speed = 115200
[env:STM32F103RC_meeb_maple]
extends = env:STM32F103RC_maple
board = marlin_maple_MEEB_3DP
+platform_packages = platformio/tool-dfuutil@~1.11.0
build_flags = ${env:STM32F103RC_maple.build_flags}
-DDEBUG_LEVEL=0
-DSS_TIMER=4
diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini
index a1950eebf6ed..0978b19476a2 100644
--- a/ini/stm32f1.ini
+++ b/ini/stm32f1.ini
@@ -200,7 +200,7 @@ board = genericSTM32F103RC
extends = STM32F103Rx_creality
board = genericSTM32F103VE
board_build.variant = MARLIN_F103Vx
-build_flags = ${stm32_variant.build_flags}
+build_flags = ${STM32F103Rx_creality.build_flags}
-DSS_TIMER=4 -DTIMER_SERVO=TIM5
-DENABLE_HWSERIAL3 -DTRANSFER_CLOCK_DIV=8
#
@@ -253,7 +253,7 @@ board = malyanm200_f103cb
build_flags = ${common_stm32.build_flags}
-DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB
-DHAL_UART_MODULE_ENABLED
-build_src_filter = ${common.default_src_filter} + -
+build_src_filter = ${common_stm32.build_src_filter} + -
#
# FLYmaker FLY Mini (STM32F103RCT6)
@@ -462,7 +462,7 @@ board_upload.offset_address = 0x08005000
board_build.offset = 0x5000
board_upload.maximum_size = 237568
extra_scripts = ${stm32_variant.extra_scripts}
-build_flags = ${common_stm32.build_flags}
+build_flags = ${stm32_variant.build_flags}
-DSS_TIMER=4 -DTIMER_SERVO=TIM5 -DUSE_USB_FS -DUSBD_IRQ_PRIO=5 -DUSBD_IRQ_SUBPRIO=6 -DUSBD_USE_CDC_MSC
build_unflags = ${stm32_variant.build_unflags} -DUSBD_USE_CDC
diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini
index 6334de6db214..341797200361 100644
--- a/ini/stm32f4.ini
+++ b/ini/stm32f4.ini
@@ -33,6 +33,7 @@ build_flags = ${common_stm32.build_flags}
#
[env:FYSETC_CHEETAH_V20]
extends = stm32_variant
+platform_packages = platformio/tool-dfuutil@~1.11.0
board = marlin_FYSETC_CHEETAH_V20
board_build.offset = 0x8000
build_flags = ${stm32_variant.build_flags} -DSTM32F401xC
@@ -43,6 +44,7 @@ upload_command = dfu-util -a 0 -s 0x08008000:leave -D "$SOURCE"
#
[env:FYSETC_CHEETAH_V30]
extends = stm32_variant
+platform_packages = platformio/tool-dfuutil@~1.11.0
board = marlin_FYSETC_CHEETAH_V30
build_flags = ${stm32_variant.build_flags} -DHAL_PCD_MODULE_ENABLED
debug_tool = stlink
@@ -54,6 +56,7 @@ upload_command = dfu-util -a 0 -s 0x08000000:leave -D "$SOURCE"
#
[env:FLYF407ZG]
extends = stm32_variant
+platform_packages = platformio/tool-dfuutil@~1.11.0
board = marlin_STM32F407ZGT6
board_build.variant = MARLIN_FLY_F407ZG
board_build.offset = 0x8000
@@ -64,6 +67,7 @@ upload_protocol = dfu
#
[env:FYSETC_S6]
extends = stm32_variant
+platform_packages = platformio/tool-dfuutil@~1.11.0
board = marlin_fysetc_s6
board_build.offset = 0x10000
board_upload.offset_address = 0x08010000
@@ -87,6 +91,7 @@ upload_command = dfu-util -a 0 -s 0x08008000:leave -D "$SOURCE"
#
[env:FYSETC_SPIDER_KING407]
extends = stm32_variant
+platform_packages = platformio/tool-dfuutil@~1.11.0
board = marlin_STM32F407ZGT6
board_build.variant = MARLIN_FYSETC_SPIDER_KING407
board_build.offset = 0x8000
@@ -418,6 +423,7 @@ build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags}
#
[env:rumba32]
extends = stm32_variant
+platform_packages = platformio/tool-dfuutil@~1.11.0
board = rumba32_f446ve
board_build.variant = MARLIN_F446VE
board_build.offset = 0x0000
@@ -685,7 +691,7 @@ extra_scripts = ${common_stm32.extra_scripts}
[STM32F401RC_creality_base]
extends = stm32_variant
board = genericSTM32F401RC
-board_build.variant = MARLIN_CREALITY_STM32F401RC
+board_build.variant = MARLIN_F401RC_CREALITY
build_flags = ${stm32_variant.build_flags} -DMCU_STM32F401RC -DSTM32F4
-DSS_TIMER=4 -DTIMER_SERVO=TIM5
-DENABLE_HWSERIAL3 -DTRANSFER_CLOCK_DIV=8
@@ -720,7 +726,7 @@ upload_protocol = stlink
#
[env:STM32F401RE_creality]
extends = stm32_variant
-board = marlin_CREALITY_STM32F401RE
+board = marlin_STM32F401RE_creality
board_build.offset = 0x10000
board_upload.offset_address = 0x08010000
board_build.rename = firmware-{date}-{time}.bin
@@ -806,6 +812,7 @@ board_build.rename = mks_skipr.bin
[env:mks_skipr_v1_nobootloader]
extends = env:mks_skipr_v1
+platform_packages = platformio/tool-dfuutil@~1.11.0
board_build.rename = firmware.bin
board_build.offset = 0x0000
board_upload.offset_address = 0x08000000
@@ -862,6 +869,7 @@ upload_protocol = stlink
#
[env:BLACKBEEZMINI_V1]
platform = ststm32
+platform_packages = platformio/tool-dfuutil@~1.11.0
extends = common_stm32
board = blackpill_f401cc
board_build.offset = 0x0000
@@ -894,7 +902,6 @@ upload_protocol = stlink
# XTLW3D Climber-8th-F4 (STM32F407VGT6 ARM Cortex-M4)
#
[env:XTLW_CLIMBER_8TH]
-platform = ${common_stm32.platform}
extends = stm32_variant
platform_packages = ${stm_flash_drive.platform_packages}
board = marlin_STM32F407VGT6_CCM
diff --git a/platformio.ini b/platformio.ini
index 5c9be792f03d..ed1670dc6daf 100644
--- a/platformio.ini
+++ b/platformio.ini
@@ -36,6 +36,7 @@ extra_configs =
ini/stm32g0.ini
ini/teensy.ini
ini/renamed.ini
+ ini/raspberrypi.ini
#
# The 'common' section applies to most Marlin builds.