diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h
index 7ea040803c..b29e1e4054 100644
--- a/Marlin/Configuration.h
+++ b/Marlin/Configuration.h
@@ -1910,6 +1910,12 @@
 // https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
 //
 //#define FYSETC_MINI_12864
+#ifdef FYSETC_MINI_12864
+  #define FYSETC_MINI_12864_REV_1_2              //  types C, D, E & F  back light is monochrome (always on) - discrete RGB signals
+  //#define FYSETC_MINI_12864_REV_2_0            //  types A & B  back light is RGB - requires LED_USER_PRESET_STARTUP - discrete RGB signals
+  //#define FYSETC_MINI_12864_REV_2_1            //  types A & B  back light is RGB - requires LED_USER_PRESET_STARTUP -  RGB
+  //#define FYSETC_MINI_12864_REV_2_1            //  types A & B  back light is RGB - requires LED_USER_PRESET_STARTUP - Neopixel
+#endif
 
 //
 // Factory display for Creality CR-10
@@ -2013,6 +2019,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/Marlin/src/HAL/HAL_DUE/HAL_spi_Due.cpp b/Marlin/src/HAL/HAL_DUE/HAL_spi_Due.cpp
index a1934886f9..5adc7fcf09 100644
--- a/Marlin/src/HAL/HAL_DUE/HAL_spi_Due.cpp
+++ b/Marlin/src/HAL/HAL_DUE/HAL_spi_Due.cpp
@@ -53,7 +53,7 @@
 // Public functions
 // --------------------------------------------------------------------------
 
-#if ENABLED(DUE_SOFTWARE_SPI)
+#if EITHER(DUE_SOFTWARE_SPI, FORCE_SOFT_SPI)
 
   // --------------------------------------------------------------------------
   // software SPI
@@ -739,7 +739,42 @@
     #define SPI_MODE_2_DUE_HW 0
     #define SPI_MODE_3_DUE_HW 1
 
+    /**
+     *  The DUE SPI controller is set up so the upper word of the longword
+     *  written to the transmit data register selects which SPI Chip Select
+     *  Register is used. This allows different streams to have different SPI
+     *  settings.
+     *
+     *  In practice it's spooky. Some combinations hang the system, while others
+     *  upset the peripheral device.
+     *
+     *  SPI mode should be the same for all streams. The FYSETC_MINI_12864 gets
+     *  upset if the clock phase changes after chip select goes active.
+     *
+     *  SPI_CSR_CSAAT should be set for all streams. If not the WHILE_TX(0)
+     *  macro returns immediately which can result in the SPI chip select going
+     *  inactive before all the data has been sent.
+     *
+     *  The TMC2130 library uses SPI0->SPI_CSR[3].
+     *
+     *  The U8G hardware SPI uses SPI0->SPI_CSR[0]. The system hangs and/or the
+     *  FYSETC_MINI_12864 gets upset if lower baud rates are used and the SD card
+     *  is inserted or removed.
+     *
+     *  The SD card uses SPI0->SPI_CSR[3]. Efforts were made to use [1] and [2]
+     *  but they all resulted in hangs or garbage on the LCD.
+     *
+     *  The SPI controlled chip selects are NOT enabled in the GPIO controller.
+     *  The application must control the chip select.
+     *
+     *  All of the above can be avoided by defining FORCE_SOFT_SPI to force the
+     *  display to use software SPI.
+     *
+     */
+
     void spiInit(uint8_t spiRate=6) {  // Default to slowest rate if not specified)
+                                       // Also sets U8G SPI rate to 4MHz and the SPI mode to 3
+
       // 8.4 MHz, 4 MHz, 2 MHz, 1 MHz, 0.5 MHz, 0.329 MHz, 0.329 MHz
       constexpr int spiDivider[] = { 10, 21, 42, 84, 168, 255, 255 };
       if (spiRate > 6) spiRate = 1;
@@ -760,15 +795,16 @@
       // TMC2103 compatible setup
       // Master mode, no fault detection, PCS bits in data written to TDR select CSR register
       SPI0->SPI_MR = SPI_MR_MSTR | SPI_MR_PS | SPI_MR_MODFDIS;
-      // SPI mode 0, 8 Bit data transfer, baud rate
-      SPI0->SPI_CSR[3] = SPI_CSR_SCBR(spiDivider[spiRate]) | SPI_CSR_CSAAT | SPI_MODE_0_DUE_HW;  // use same CSR as TMC2130
+      // SPI mode 3, 8 Bit data transfer, baud rate
+      SPI0->SPI_CSR[3] = SPI_CSR_SCBR(spiDivider[spiRate]) | SPI_CSR_CSAAT | SPI_MODE_3_DUE_HW;  // use same CSR as TMC2130
+      SPI0->SPI_CSR[0] = SPI_CSR_SCBR(spiDivider[1]) | SPI_CSR_CSAAT | SPI_MODE_3_DUE_HW;  // U8G default to 4MHz
     }
 
     void spiBegin() { spiInit(); }
 
     static uint8_t spiTransfer(uint8_t data) {
       WHILE_TX(0);
-      SPI0->SPI_TDR = (uint32_t)data | 0x00070000UL;  // Add TMC2130 PCS bits to every byte
+      SPI0->SPI_TDR = (uint32_t)data | 0x00070000UL;  // Add TMC2130 PCS bits to every byte (use SPI0->SPI_CSR[3])
       WHILE_TX(0);
       WHILE_RX(0);
       return SPI0->SPI_RDR;
diff --git a/Marlin/src/HAL/HAL_DUE/u8g_com_HAL_DUE_st7920_sw_spi.cpp b/Marlin/src/HAL/HAL_DUE/u8g_com_HAL_DUE_st7920_sw_spi.cpp
index 1546407a1e..3cef880bca 100644
--- a/Marlin/src/HAL/HAL_DUE/u8g_com_HAL_DUE_st7920_sw_spi.cpp
+++ b/Marlin/src/HAL/HAL_DUE/u8g_com_HAL_DUE_st7920_sw_spi.cpp
@@ -99,7 +99,7 @@ static void u8g_com_DUE_st7920_write_byte_sw_spi(uint8_t rs, uint8_t val) {
     spiSend_sw_DUE(rs ? 0x0FA : 0x0F8); // Command or Data
     DELAY_US(40); // give the controller some time to process the data: 20 is bad, 30 is OK, 40 is safe
   }
-  spiSend_sw_DUE(val & 0x0F0);
+  spiSend_sw_DUE(val & 0xF0);
   spiSend_sw_DUE(val << 4);
 }
 
@@ -168,6 +168,42 @@ uint8_t u8g_com_HAL_DUE_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_va
   return 1;
 }
 
-#endif // HAS_GRAPHICAL_LCD
+#if ENABLED(LIGHTWEIGHT_UI)
+  #include "../../lcd/ultralcd.h"
+  #include "../shared/HAL_ST7920.h"
 
+  #define ST7920_CS_PIN LCD_PINS_RS
+
+  #if DOGM_SPI_DELAY_US > 0
+    #define U8G_DELAY() DELAY_US(DOGM_SPI_DELAY_US)
+  #else
+    #define U8G_DELAY() DELAY_US(10)
+  #endif
+
+  void ST7920_cs() {
+    WRITE(ST7920_CS_PIN, HIGH);
+    U8G_DELAY();
+  }
+
+  void ST7920_ncs() {
+    WRITE(ST7920_CS_PIN, LOW);
+  }
+
+  void ST7920_set_cmd() {
+    spiSend_sw_DUE(0xF8);
+    DELAY_US(40);
+  }
+
+  void ST7920_set_dat() {
+    spiSend_sw_DUE(0xFA);
+    DELAY_US(40);
+  }
+
+  void ST7920_write_byte(const uint8_t val) {
+    spiSend_sw_DUE(val & 0xF0);
+    spiSend_sw_DUE(val << 4);
+  }
+#endif // LIGHTWEIGHT_UI
+
+#endif // HAS_GRAPHICAL_LCD
 #endif // ARDUINO_ARCH_SAM
diff --git a/Marlin/src/HAL/HAL_ESP32/HAL.cpp b/Marlin/src/HAL/HAL_ESP32/HAL.cpp
index c755eb6056..53966de55e 100644
--- a/Marlin/src/HAL/HAL_ESP32/HAL.cpp
+++ b/Marlin/src/HAL/HAL_ESP32/HAL.cpp
@@ -133,12 +133,16 @@ int freeMemory() {
 // --------------------------------------------------------------------------
 // ADC
 // --------------------------------------------------------------------------
-#define ADC1_CHANNEL(pin) ADC1_GPIO##pin_CHANNEL
+#define ADC1_CHANNEL(pin) ADC1_GPIO ## pin ## _CHANNEL
 
 adc1_channel_t get_channel(int pin) {
   switch (pin) {
-    case 36: return ADC1_GPIO36_CHANNEL;
-    case 39: return ADC1_GPIO39_CHANNEL;
+    case 39: return ADC1_CHANNEL(39);
+    case 36: return ADC1_CHANNEL(36);
+    case 35: return ADC1_CHANNEL(35);
+    case 34: return ADC1_CHANNEL(34);
+    case 33: return ADC1_CHANNEL(33);
+    case 32: return ADC1_CHANNEL(32);
   }
 
   return ADC1_CHANNEL_MAX;
@@ -147,8 +151,15 @@ adc1_channel_t get_channel(int pin) {
 void HAL_adc_init() {
   // Configure ADC
   adc1_config_width(ADC_WIDTH_12Bit);
-  adc1_config_channel_atten(get_channel(36), ADC_ATTEN_11db);
   adc1_config_channel_atten(get_channel(39), ADC_ATTEN_11db);
+  adc1_config_channel_atten(get_channel(36), ADC_ATTEN_11db);
+  adc1_config_channel_atten(get_channel(35), ADC_ATTEN_11db);
+  adc1_config_channel_atten(get_channel(34), ADC_ATTEN_11db);
+  adc1_config_channel_atten(get_channel(33), ADC_ATTEN_11db);
+  adc1_config_channel_atten(get_channel(32), ADC_ATTEN_11db);
+
+  // Note that adc2 is shared with the WiFi module, which has higher priority, so the conversion may fail.
+  // That's why we're not setting it up here.
 
   // Calculate ADC characteristics i.e. gain and offset factors
   esp_adc_cal_characterize(ADC_UNIT_1, ADC_ATTEN_DB_11, ADC_WIDTH_BIT_12, V_REF, &characteristics);
diff --git a/Marlin/src/HAL/HAL_ESP32/HAL.h b/Marlin/src/HAL/HAL_ESP32/HAL.h
index 3285a8b2b9..16859263b2 100644
--- a/Marlin/src/HAL/HAL_ESP32/HAL.h
+++ b/Marlin/src/HAL/HAL_ESP32/HAL.h
@@ -30,13 +30,18 @@
 
 #include <stdint.h>
 
+// these are going to be re-defined in Arduino.h
 #undef DISABLED
 #undef M_PI
+#undef _BV
 
 #include <Arduino.h>
 
+// revert back to the correct (old) definition
 #undef DISABLED
 #define DISABLED(V...) DO(DIS,&&,V)
+// re-define in case Arduino.h has been skipped due to earlier inclusion (i.e. in Marlin\src\HAL\HAL_ESP32\i2s.cpp)
+#define _BV(b) (1UL << (b))
 
 #include "../shared/math_32bit.h"
 #include "../shared/HAL_SPI.h"
diff --git a/Marlin/src/HAL/HAL_ESP32/fastio_ESP32.h b/Marlin/src/HAL/HAL_ESP32/fastio_ESP32.h
index dc2cd708de..b71ca78418 100644
--- a/Marlin/src/HAL/HAL_ESP32/fastio_ESP32.h
+++ b/Marlin/src/HAL/HAL_ESP32/fastio_ESP32.h
@@ -27,6 +27,10 @@
  * Utility functions
  */
 
+// I2S expander pin mapping.
+#define IS_I2S_EXPANDER_PIN(IO) TEST(IO, 7)
+#define I2S_EXPANDER_PIN_INDEX(IO) (IO & 0x7F)
+
 // Set pin as input
 #define _SET_INPUT(IO)          pinMode(IO, INPUT)
 
@@ -37,10 +41,10 @@
 #define _PULLUP(IO, v)          pinMode(IO, v ? INPUT_PULLUP : INPUT)
 
 // Read a pin wrapper
-#define READ(IO)                digitalRead(IO)
+#define READ(IO)                (IS_I2S_EXPANDER_PIN(IO) ? i2s_state(I2S_EXPANDER_PIN_INDEX(IO)) : digitalRead(IO))
 
 // Write to a pin wrapper
-#define WRITE(IO, v)            (TEST(IO, 7) ? i2s_write(IO & 0x7F, v) : digitalWrite(IO, v))
+#define WRITE(IO, v)            (IS_I2S_EXPANDER_PIN(IO) ? i2s_write(I2S_EXPANDER_PIN_INDEX(IO), v) : digitalWrite(IO, v))
 
 // Set pin as input wrapper
 #define SET_INPUT(IO)           _SET_INPUT(IO)
@@ -61,8 +65,9 @@
 #define extDigitalRead(IO)      digitalRead(IO)
 #define extDigitalWrite(IO,V)   digitalWrite(IO,V)
 
-#define PWM_PIN(P)              true
-#define USEABLE_HARDWARE_PWM(P) PWM_PIN(P)
+// PWM outputs
+#define PWM_PIN(P)              (P < 34) // NOTE Pins >= 34 are input only on ESP32, so they can't be used for output.
+#define USEABLE_HARDWARE_PWM(P) (!IS_I2S_EXPANDER_PIN(P) && PWM_PIN(P))
 
 // Toggle pin value
 #define TOGGLE(IO)              WRITE(IO, !READ(IO))
diff --git a/Marlin/src/HAL/HAL_ESP32/i2s.cpp b/Marlin/src/HAL/HAL_ESP32/i2s.cpp
index 42e65eacd7..0345889e07 100644
--- a/Marlin/src/HAL/HAL_ESP32/i2s.cpp
+++ b/Marlin/src/HAL/HAL_ESP32/i2s.cpp
@@ -21,7 +21,12 @@
  */
 #ifdef ARDUINO_ARCH_ESP32
 
-#include <Arduino.h> // replace that with the proper imports
+// replace that with the proper imports, then cleanup workarounds in Marlin\src\HAL\HAL_ESP32\HAL.h
+#include <Arduino.h>
+// revert back to the correct definition
+#undef DISABLED
+#define DISABLED(V...) DO(DIS,&&,V)
+
 #include "i2s.h"
 #include "../../core/macros.h"
 #include "driver/periph_ctrl.h"
@@ -315,6 +320,10 @@ void i2s_write(uint8_t pin, uint8_t val) {
   SET_BIT_TO(i2s_port_data, pin, val);
 }
 
+uint8_t i2s_state(uint8_t pin) {
+  return TEST(i2s_port_data, pin);
+}
+
 void i2s_push_sample() {
   dma.current[dma.rw_pos++] = i2s_port_data;
 }
diff --git a/Marlin/src/HAL/HAL_ESP32/i2s.h b/Marlin/src/HAL/HAL_ESP32/i2s.h
index 337d91b203..fbe7b2419a 100644
--- a/Marlin/src/HAL/HAL_ESP32/i2s.h
+++ b/Marlin/src/HAL/HAL_ESP32/i2s.h
@@ -26,6 +26,8 @@ extern uint32_t i2s_port_data;
 
 int i2s_init();
 
+uint8_t i2s_state(uint8_t pin);
+
 void i2s_write(uint8_t pin, uint8_t val);
 
 void i2s_push_sample();
diff --git a/Marlin/src/HAL/HAL_ESP32/spi_pins.h b/Marlin/src/HAL/HAL_ESP32/spi_pins.h
index 896d9fa853..4ef6d14ec3 100644
--- a/Marlin/src/HAL/HAL_ESP32/spi_pins.h
+++ b/Marlin/src/HAL/HAL_ESP32/spi_pins.h
@@ -18,7 +18,7 @@
  */
 #pragma once
 
-#define SS_PIN    5
+#define SS_PIN   SDSS
 #define SCK_PIN  18
 #define MISO_PIN 19
 #define MOSI_PIN 23
diff --git a/Marlin/src/HAL/HAL_LPC1768/HAL.h b/Marlin/src/HAL/HAL_LPC1768/HAL.h
index 0ac6db167e..12d73c6713 100644
--- a/Marlin/src/HAL/HAL_LPC1768/HAL.h
+++ b/Marlin/src/HAL/HAL_LPC1768/HAL.h
@@ -147,6 +147,9 @@ using FilteredADC = LPC176x::ADC<ADC_LOWPASS_K_VALUE, ADC_MEDIAN_FILTER_SIZE>;
 #define HAL_READ_ADC()         FilteredADC::get_result()
 #define HAL_ADC_READY()        FilteredADC::finished_conversion()
 
+// A grace period for the ADC readings to stabilize before they start causing thermal protection errors.
+#define THERMAL_PROTECTION_GRACE_PERIOD 500
+
 // Parse a G-code word into a pin index
 int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
 // P0.6 thru P0.9 are for the onboard SD card
diff --git a/Marlin/src/HAL/HAL_LPC1768/SanityCheck.h b/Marlin/src/HAL/HAL_LPC1768/SanityCheck.h
index ecf0eb0c07..2338b34ee3 100644
--- a/Marlin/src/HAL/HAL_LPC1768/SanityCheck.h
+++ b/Marlin/src/HAL/HAL_LPC1768/SanityCheck.h
@@ -66,12 +66,7 @@
   #endif
 #endif // SPINDLE_LASER_ENABLE
 
-#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) && HAS_DRIVER(TMC2130) && DISABLED(TMC_USE_SW_SPI) \
-    && (MB(RAMPS_14_RE_ARM_EFB) \
-    ||  MB(RAMPS_14_RE_ARM_EEB) \
-    ||  MB(RAMPS_14_RE_ARM_EFF) \
-    ||  MB(RAMPS_14_RE_ARM_EEF) \
-    ||  MB(RAMPS_14_RE_ARM_SF))
+#if IS_RE_ARM_BOARD && ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) && HAS_DRIVER(TMC2130) && DISABLED(TMC_USE_SW_SPI)
   #error "Re-ARM with REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER and TMC2130 require TMC_USE_SW_SPI"
 #endif
 
diff --git a/Marlin/src/HAL/shared/HAL_ST7920.h b/Marlin/src/HAL/shared/HAL_ST7920.h
new file mode 100644
index 0000000000..9af1286c7a
--- /dev/null
+++ b/Marlin/src/HAL/shared/HAL_ST7920.h
@@ -0,0 +1,36 @@
+/**
+ * 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 <http://www.gnu.org/licenses/>.
+ *
+ */
+#pragma once
+
+/**
+ * HAL/HAL_ST7920.h
+ * For the HALs that provide direct access to the ST7920 display
+ * (bypassing U8G), it will allow the LIGHTWEIGHT_UI to operate.
+ */
+
+#if HAS_GRAPHICAL_LCD && ENABLED(LIGHTWEIGHT_UI)
+  void ST7920_cs();
+  void ST7920_ncs();
+  void ST7920_set_cmd();
+  void ST7920_set_dat();
+  void ST7920_write_byte(const uint8_t data);
+#endif
\ No newline at end of file
diff --git a/Marlin/src/core/debug_out.h b/Marlin/src/core/debug_out.h
index 81e1e216b4..c43c928a29 100644
--- a/Marlin/src/core/debug_out.h
+++ b/Marlin/src/core/debug_out.h
@@ -26,6 +26,7 @@
 //  (or not) in a given .cpp file
 //
 
+#undef DEBUG_PRINT_P
 #undef DEBUG_ECHO_START
 #undef DEBUG_ERROR_START
 #undef DEBUG_CHAR
diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h
index 0dfd54b3af..14dcf8bd30 100644
--- a/Marlin/src/core/language.h
+++ b/Marlin/src/core/language.h
@@ -344,7 +344,6 @@
 #define MSG_LCD_N3 " 4"
 #define MSG_LCD_N4 " 5"
 #define MSG_LCD_N5 " 6"
-#define MSG_E0 "E0"
 #define MSG_E1 "E1"
 #define MSG_E2 "E2"
 #define MSG_E3 "E3"
diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp
index 9a26400a97..36550a7bd7 100644
--- a/Marlin/src/gcode/calibrate/G34_M422.cpp
+++ b/Marlin/src/gcode/calibrate/G34_M422.cpp
@@ -126,6 +126,12 @@ void GcodeSuite::G34() {
       extruder_duplication_enabled = false;
     #endif
 
+    // Before moving other axes raise Z, if needed. Never lower Z.
+    if (current_position[Z_AXIS] < Z_CLEARANCE_BETWEEN_PROBES) {
+      if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Raise Z (before moving to probe pos) to ", Z_CLEARANCE_BETWEEN_PROBES);
+      do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES);
+    }
+
     // Remember corrections to determine errors on each iteration
     float last_z_align_move[Z_STEPPER_COUNT] = ARRAY_N(Z_STEPPER_COUNT, 10000.0f, 10000.0f, 10000.0f),
           z_measured[Z_STEPPER_COUNT] = { 0 };
diff --git a/Marlin/src/gcode/eeprom/M500-M504.cpp b/Marlin/src/gcode/eeprom/M500-M504.cpp
index 12e323bd7b..e21e125066 100644
--- a/Marlin/src/gcode/eeprom/M500-M504.cpp
+++ b/Marlin/src/gcode/eeprom/M500-M504.cpp
@@ -25,18 +25,11 @@
 #include "../../core/serial.h"
 #include "../../inc/MarlinConfig.h"
 
-#if ENABLED(EXTENSIBLE_UI)
-  #include "../../lcd/extensible_ui/ui_api.h"
-#endif
-
 /**
  * M500: Store settings in EEPROM
  */
 void GcodeSuite::M500() {
   (void)settings.save();
-  #if ENABLED(EXTENSIBLE_UI)
-    ExtUI::onStoreSettings();
-  #endif
 }
 
 /**
@@ -44,9 +37,6 @@ void GcodeSuite::M500() {
  */
 void GcodeSuite::M501() {
   (void)settings.load();
-  #if ENABLED(EXTENSIBLE_UI)
-    ExtUI::onLoadSettings();
-  #endif
 }
 
 /**
@@ -54,9 +44,6 @@ void GcodeSuite::M501() {
  */
 void GcodeSuite::M502() {
   (void)settings.reset();
-  #if ENABLED(EXTENSIBLE_UI)
-    ExtUI::onFactoryReset();
-  #endif
 }
 
 #if DISABLED(DISABLE_M503)
diff --git a/Marlin/src/gcode/feature/trinamic/M906.cpp b/Marlin/src/gcode/feature/trinamic/M906.cpp
index 51a3cefde2..0466bfff4e 100644
--- a/Marlin/src/gcode/feature/trinamic/M906.cpp
+++ b/Marlin/src/gcode/feature/trinamic/M906.cpp
@@ -29,8 +29,18 @@
 #include "../../../module/stepper_indirection.h"
 
 /**
- * M906: Set motor current in milliamps using axis codes X, Y, Z, E
- * Report driver currents when no axis specified
+ * M906: Set motor current in milliamps.
+ *
+ * Parameters:
+ *   X[current]  - Set mA current for X driver(s)
+ *   Y[current]  - Set mA current for Y driver(s)
+ *   Z[current]  - Set mA current for Z driver(s)
+ *   E[current]  - Set mA current for E driver(s)
+ *
+ *   I[index]    - Axis sub-index (Omit or 0 for X, Y, Z; 1 for X2, Y2, Z2; 2 for Z3.)
+ *   T[index]    - Extruder index (Zero-based. Omit for E0 only.)
+ *
+ * With no parameters report driver currents.
  */
 void GcodeSuite::M906() {
   #define TMC_SAY_CURRENT(Q) tmc_get_current(stepper##Q)
diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h
index 320dc00ec3..81c0678e3f 100644
--- a/Marlin/src/inc/Conditionals_LCD.h
+++ b/Marlin/src/inc/Conditionals_LCD.h
@@ -138,6 +138,8 @@
 #elif ENABLED(MKS_MINI_12864)
 
   #define MINIPANEL
+  #define DEFAULT_LCD_CONTRAST 150
+  #define LCD_CONTRAST_MAX 255
 
 #elif ENABLED(FYSETC_MINI_12864)
 
@@ -153,7 +155,9 @@
 #if EITHER(MAKRPANEL, MINIPANEL)
   #define DOGLCD
   #define ULTIPANEL
-  #define DEFAULT_LCD_CONTRAST 17
+  #ifndef DEFAULT_LCD_CONTRAST
+    #define DEFAULT_LCD_CONTRAST 17
+  #endif
 #endif
 
 #if ENABLED(ULTI_CONTROLLER)
@@ -325,7 +329,7 @@
 /**
  * Default LCD contrast for Graphical LCD displays
  */
-#define HAS_LCD_CONTRAST HAS_GRAPHICAL_LCD && defined(DEFAULT_LCD_CONTRAST)
+#define HAS_LCD_CONTRAST (HAS_GRAPHICAL_LCD && defined(DEFAULT_LCD_CONTRAST))
 #if HAS_LCD_CONTRAST
   #ifndef LCD_CONTRAST_MIN
     #define LCD_CONTRAST_MIN 0
@@ -562,3 +566,5 @@
 #if ENABLED(SLIM_LCD_MENUS)
   #define BOOT_MARLIN_LOGO_SMALL
 #endif
+
+#define IS_RE_ARM_BOARD (MB(RAMPS_14_RE_ARM_EFB) || MB(RAMPS_14_RE_ARM_EEB) || MB(RAMPS_14_RE_ARM_EFF) || MB(RAMPS_14_RE_ARM_EEF) || MB(RAMPS_14_RE_ARM_SF))
diff --git a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp
index c8927725c5..57a6e96904 100644
--- a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp
+++ b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp
@@ -1038,9 +1038,7 @@ void MarlinUI::draw_status_screen() {
   }
 
   void draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string, PGM_P const suff) {
-    SETCURSOR(0, 0); lcd_put_u8str_P(pref);
-    if (string) wrap_string(1, string);
-    if (suff) lcd_put_u8str_P(suff);
+    ui.draw_select_screen_prompt(pref, string, suff);
     SETCURSOR(0, LCD_HEIGHT - 1);
     lcd_put_wchar(yesno ? ' ' : '['); lcd_put_u8str_P(no); lcd_put_wchar(yesno ? ' ' : ']');
     SETCURSOR_RJ(utf8_strlen_P(yes) + 2, LCD_HEIGHT - 1);
diff --git a/Marlin/src/lcd/dogm/HAL_LCD_class_defines.h b/Marlin/src/lcd/dogm/HAL_LCD_class_defines.h
index 7141eeb180..d25b58d9a4 100644
--- a/Marlin/src/lcd/dogm/HAL_LCD_class_defines.h
+++ b/Marlin/src/lcd/dogm/HAL_LCD_class_defines.h
@@ -94,3 +94,16 @@ public:
   : U8GLIB(&u8g_dev_tft_320x240_upscale_from_128x64, cs, rs, reset)
   { }
 };
+
+
+extern u8g_dev_t u8g_dev_uc1701_mini12864_HAL_2x_sw_spi, u8g_dev_uc1701_mini12864_HAL_2x_hw_spi;
+
+class U8GLIB_MINI12864_2X_HAL : public U8GLIB {
+public:
+  U8GLIB_MINI12864_2X_HAL(uint8_t sck, uint8_t mosi, uint8_t cs, uint8_t a0, uint8_t reset = U8G_PIN_NONE)
+    : U8GLIB(&u8g_dev_uc1701_mini12864_HAL_2x_sw_spi, sck, mosi, cs, a0, reset)
+    { }
+  U8GLIB_MINI12864_2X_HAL(uint8_t cs, uint8_t a0, uint8_t reset = U8G_PIN_NONE)
+    : U8GLIB(&u8g_dev_uc1701_mini12864_HAL_2x_hw_spi, cs, a0, reset)
+    { }
+};
diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp
index a72b3e4fc8..8b12a83570 100644
--- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp
+++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp
@@ -158,9 +158,7 @@ void ST7920_Lite_Status_Screen::entry_mode_select(const bool ac_increase, const
 // function for scroll_or_addr_select()
 void ST7920_Lite_Status_Screen::_scroll_or_addr_select(const bool sa) {
   extended_function_set(true);
-  cmd(0b00100010 |
-    (sa   ? 0b000001 : 0)
-  );
+  cmd(0b00000010 | (sa ? 0b00000001 : 0));
   current_bits.sa = sa;
 }
 
@@ -907,34 +905,6 @@ void ST7920_Lite_Status_Screen::clear_text_buffer() {
   ncs();
 }
 
-#if ENABLED(U8GLIB_ST7920) && !defined(U8G_HAL_LINKS) && !defined(__SAM3X8E__)
-
-  #include "ultralcd_st7920_u8glib_rrd_AVR.h"
-
-  void ST7920_Lite_Status_Screen::cs() {
-    ST7920_CS();
-    current_bits.synced = false;
-  }
-
-  void ST7920_Lite_Status_Screen::ncs() {
-    ST7920_NCS();
-    current_bits.synced = false;
-  }
-
-  void ST7920_Lite_Status_Screen::sync_cmd() {
-    ST7920_SET_CMD();
-  }
-
-  void ST7920_Lite_Status_Screen::sync_dat() {
-    ST7920_SET_DAT();
-  }
-
-  void ST7920_Lite_Status_Screen::write_byte(const uint8_t data) {
-    ST7920_WRITE_BYTE(data);
-  }
-
-#endif
-
 void MarlinUI::draw_status_screen() {
   ST7920_Lite_Status_Screen::update(false);
 }
diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h
index 8a19030d6b..1fb707ca1d 100644
--- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h
+++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h
@@ -15,6 +15,8 @@
  */
 #pragma once
 
+#include "../../HAL/shared/HAL_ST7920.h"
+
 #include "../../core/macros.h"
 #include "../../libs/duration_t.h"
 
@@ -28,11 +30,11 @@ class ST7920_Lite_Status_Screen {
       uint8_t sa       : 1;
     } current_bits;
 
-    static void cs();
-    static void ncs();
-    static void sync_cmd();
-    static void sync_dat();
-    static void write_byte(const uint8_t w);
+    static void cs()                        { ST7920_cs(); current_bits.synced = false; }
+    static void ncs()                       { ST7920_cs(); current_bits.synced = false; }
+    static void sync_cmd()                  { ST7920_set_cmd(); }
+    static void sync_dat()                  { ST7920_set_dat(); }
+    static void write_byte(const uint8_t w) { ST7920_write_byte(w); }
 
     FORCE_INLINE static void write_word(const uint16_t w) {
       write_byte((w >> 8) & 0xFF);
diff --git a/Marlin/src/lcd/dogm/u8g_dev_uc1701_mini12864_HAL.cpp b/Marlin/src/lcd/dogm/u8g_dev_uc1701_mini12864_HAL.cpp
index 35f7d4161a..4dd8759e7a 100644
--- a/Marlin/src/lcd/dogm/u8g_dev_uc1701_mini12864_HAL.cpp
+++ b/Marlin/src/lcd/dogm/u8g_dev_uc1701_mini12864_HAL.cpp
@@ -66,42 +66,47 @@
 #define PAGE_HEIGHT 8
 
 static const uint8_t u8g_dev_uc1701_mini12864_HAL_init_seq[] PROGMEM = {
-  U8G_ESC_CS(0),             /* disable chip */
-  U8G_ESC_ADR(0),           /* instruction mode */
-  U8G_ESC_RST(1),           /* do reset low pulse with (1*16)+2 milliseconds */
-  U8G_ESC_CS(1),             /* enable chip */
+  U8G_ESC_CS(0),              /* disable chip */
+  U8G_ESC_ADR(0),             /* instruction mode */
+  U8G_ESC_RST(1),             /* do reset low pulse with (1*16)+2 milliseconds */
+  U8G_ESC_CS(1),              /* enable chip */
 
-  0x0E2,            /* soft reset */
-  0x040,    /* set display start line to 0 */
-  0x0A0,    /* ADC set to reverse */
-  0x0C8,    /* common output mode */
-  0x0A6,    /* display normal, bit val 0: LCD pixel off. */
-  0x0A2,    /* LCD bias 1/9 */
-  0x02F,    /* all power  control circuits on */
-  0x0F8,    /* set booster ratio to */
-  0x000,    /* 4x */
-  0x023,    /* set V0 voltage resistor ratio to large */
-  0x081,    /* set contrast */
-  0x027,    /* contrast value */
-  0x0AC,    /* indicator */
-  0x000,    /* disable */
-  0x0AF,    /* display on */
+  0x0E2,                      /* soft reset */
+  0x040,                      /* set display start line to 0 */
+  0x0A0,                      /* ADC set to reverse */
+  0x0C8,                      /* common output mode */
+  0x0A6,                      /* display normal, bit val 0: LCD pixel off. */
+  0x0A2,                      /* LCD bias 1/9 */
+  0x02F,                      /* all power control circuits on */
+  0x0F8,                      /* set booster ratio to */
+  0x000,                      /* 4x */
+  0x023,                      /* set V0 voltage resistor ratio to large */
+  0x081,                      /* set contrast */
+  0x027,                      /* contrast value */
+  0x0AC,                      /* indicator */
+  0x000,                      /* disable */
+  0x0AF,                      /* display on */
 
-  U8G_ESC_DLY(100),       /* delay 100 ms */
-  0x0A5,                    /* display all points, ST7565 */
-  U8G_ESC_DLY(100),       /* delay 100 ms */
-  U8G_ESC_DLY(100),       /* delay 100 ms */
-  0x0A4,                    /* normal display */
-  U8G_ESC_CS(0),             /* disable chip */
-  U8G_ESC_END                /* end of sequence */
+  U8G_ESC_CS(0),              /* disable chip */
+  U8G_ESC_DLY(100),           /* delay 100 ms */
+  U8G_ESC_CS(1),              /* enable chip */
+
+  0x0A5,                      /* display all points, ST7565 */
+  U8G_ESC_CS(0),              /* disable chip */
+  U8G_ESC_DLY(100),           /* delay 100 ms */
+  U8G_ESC_DLY(100),           /* delay 100 ms */
+  U8G_ESC_CS(1),              /* enable chip */
+  0x0A4,                      /* normal display */
+  U8G_ESC_CS(0),              /* disable chip */
+  U8G_ESC_END                 /* end of sequence */
 };
 
 static const uint8_t u8g_dev_uc1701_mini12864_HAL_data_start[] PROGMEM = {
-  U8G_ESC_ADR(0),           /* instruction mode */
-  U8G_ESC_CS(1),             /* enable chip */
-  0x010,    /* set upper 4 bit of the col adr to 0 */
-  0x000,    /* set lower 4 bit of the col adr to 4  */
-  U8G_ESC_END                /* end of sequence */
+  U8G_ESC_ADR(0),             /* instruction mode */
+  U8G_ESC_CS(1),              /* enable chip */
+  0x010,                      /* set upper 4 bit of the col adr to 0 */
+  0x000,                      /* set lower 4 bit of the col adr to 4 */
+  U8G_ESC_END                 /* end of sequence */
 };
 
 uint8_t u8g_dev_uc1701_mini12864_HAL_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) {
diff --git a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp
index 4ef6fc6248..4a33045592 100644
--- a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp
+++ b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp
@@ -175,14 +175,14 @@ void MarlinUI::set_font(const MarlinFont font_nr) {
 
     // Can the text fit to the right of the bitmap?
     if (text_max_width < rspace) {
-      constexpr uint8_t inter = (width - text_max_width - (START_BMPWIDTH)) / 3; // Evenly distribute horizontal space
+      constexpr int8_t inter = (width - text_max_width - (START_BMPWIDTH)) / 3; // Evenly distribute horizontal space
       offx = inter;                             // First the boot logo...
       offy = (height - (START_BMPHEIGHT)) / 2;  // ...V-aligned in the full height
       txt_offx_1 = txt_offx_2 = inter + (START_BMPWIDTH) + inter; // Text right of the bitmap
       txt_base = (height + MENU_FONT_ASCENT + text_total_height - (MENU_FONT_HEIGHT)) / 2; // Text vertical center
     }
     else {
-      constexpr uint8_t inter = (height - text_total_height - (START_BMPHEIGHT)) / 3; // Evenly distribute vertical space
+      constexpr int8_t inter = (height - text_total_height - (START_BMPHEIGHT)) / 3; // Evenly distribute vertical space
       offy = inter;                             // V-align boot logo proportionally
       offx = rspace / 2;                        // Center the boot logo in the whole space
       txt_offx_1 = (width - text_width_1) / 2;  // Text 1 centered
@@ -439,9 +439,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
   }
 
   void draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string, PGM_P const suff) {
-    SETCURSOR(0, 0); lcd_put_u8str_P(pref);
-    if (string) wrap_string(1, string);
-    if (suff) lcd_put_u8str_P(suff);
+    ui.draw_select_screen_prompt(pref, string, suff);
     draw_boxed_string(1, LCD_HEIGHT - 1, no, !yesno);
     draw_boxed_string(LCD_WIDTH - (utf8_strlen_P(yes) + 1), LCD_HEIGHT - 1, yes, yesno);
   }
diff --git a/Marlin/src/lcd/dogm/ultralcd_DOGM.h b/Marlin/src/lcd/dogm/ultralcd_DOGM.h
index 1f2c90b9d9..8ce25d0e77 100644
--- a/Marlin/src/lcd/dogm/ultralcd_DOGM.h
+++ b/Marlin/src/lcd/dogm/ultralcd_DOGM.h
@@ -111,8 +111,8 @@
   // The MINIPanel display
   //#define U8G_CLASS U8GLIB_MINI12864
   //#define U8G_PARAM DOGLCD_CS, DOGLCD_A0                            // 8 stripes
-  #define U8G_CLASS U8GLIB_MINI12864_2X
-  #if EITHER(FYSETC_MINI_12864, TARGET_LPC1768)
+  #define U8G_CLASS U8GLIB_MINI12864_2X_HAL
+  #if BOTH(FYSETC_MINI_12864, FORCE_SOFT_SPI)
     #define U8G_PARAM DOGLCD_SCK, DOGLCD_MOSI, DOGLCD_CS, DOGLCD_A0   // 4 stripes SW-SPI
   #else
     #define U8G_PARAM DOGLCD_CS, DOGLCD_A0                            // 4 stripes HW-SPI
diff --git a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp
index c99a7085a1..969cef10bb 100644
--- a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp
+++ b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp
@@ -134,4 +134,13 @@ u8g_dev_t u8g_dev_st7920_128x64_rrd_sw_spi = {u8g_dev_rrd_st7920_128x64_fn, &u8g
 
 #pragma GCC reset_options
 
+#if ENABLED(LIGHTWEIGHT_UI)
+  #include "../../HAL/shared/HAL_ST7920.h"
+  void ST7920_cs()                          { ST7920_CS(); }
+  void ST7920_ncs()                         { ST7920_NCS(); }
+  void ST7920_set_cmd()                     { ST7920_SET_CMD(); }
+  void ST7920_set_dat()                     { ST7920_SET_DAT(); }
+  void ST7920_write_byte(const uint8_t val) { ST7920_WRITE_BYTE(val); }
+#endif
+
 #endif // U8GLIB_ST7920 && !U8G_HAL_LINKS && !__SAM3X8E__
diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h
index 3fa3be90ef..9275b08643 100644
--- a/Marlin/src/lcd/language/language_de.h
+++ b/Marlin/src/lcd/language/language_de.h
@@ -332,9 +332,11 @@
 #define MSG_ENDSTOP_ABORT                   _UxGT("Endstopp Abbr.")
 #define MSG_HEATING_FAILED_LCD              _UxGT("HEIZEN ERFOLGLOS")
 #define MSG_HEATING_FAILED_LCD_BED          _UxGT("Bett heizen fehlge.")
+#define MSG_HEATING_FAILED_LCD_CHAMBER      _UxGT("Geh. heizen fehlge.")
 #define MSG_ERR_REDUNDANT_TEMP              _UxGT("REDUND. TEMP-ABWEI.")
 #define MSG_THERMAL_RUNAWAY                 LCD_STR_THERMOMETER _UxGT(" NICHT ERREICHT")
 #define MSG_THERMAL_RUNAWAY_BED             _UxGT("BETT") MSG_THERMAL_RUNAWAY
+#define MSG_THERMAL_RUNAWAY_CHAMBER         _UxGT("GEH.") MSG_THERMAL_RUNAWAY
 #define MSG_ERR_MAXTEMP                     LCD_STR_THERMOMETER _UxGT(" ÜBERSCHRITTEN")
 #define MSG_ERR_MINTEMP                     LCD_STR_THERMOMETER _UxGT(" UNTERSCHRITTEN")
 #define MSG_ERR_MAXTEMP_BED                 _UxGT("BETT ") LCD_STR_THERMOMETER _UxGT(" ÜBERSCHRITTEN")
diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h
index c60f8b8051..5677ecbae9 100644
--- a/Marlin/src/lcd/language/language_en.h
+++ b/Marlin/src/lcd/language/language_en.h
@@ -753,12 +753,27 @@
 #ifndef MSG_START_PRINT
   #define MSG_START_PRINT                     _UxGT("Start print")
 #endif
+#ifndef MSG_BUTTON_NEXT
+  #define MSG_BUTTON_NEXT                     _UxGT("Next")
+#endif
+#ifndef MSG_BUTTON_INIT
+  #define MSG_BUTTON_INIT                     _UxGT("Init")
+#endif
+#ifndef MSG_BUTTON_STOP
+  #define MSG_BUTTON_STOP                     _UxGT("Stop")
+#endif
 #ifndef MSG_BUTTON_PRINT
   #define MSG_BUTTON_PRINT                    _UxGT("Print")
 #endif
+#ifndef MSG_BUTTON_RESET
+  #define MSG_BUTTON_RESET                    _UxGT("Reset")
+#endif
 #ifndef MSG_BUTTON_CANCEL
   #define MSG_BUTTON_CANCEL                   _UxGT("Cancel")
 #endif
+#ifndef MSG_BUTTON_DONE
+  #define MSG_BUTTON_DONE                     _UxGT("Done")
+#endif
 #ifndef MSG_PAUSE_PRINT
   #define MSG_PAUSE_PRINT                     _UxGT("Pause print")
 #endif
@@ -930,6 +945,9 @@
 #ifndef MSG_HEATING_FAILED_LCD_BED
   #define MSG_HEATING_FAILED_LCD_BED          _UxGT("Bed heating failed")
 #endif
+#ifndef MSG_HEATING_FAILED_LCD_CHAMBER
+  #define MSG_HEATING_FAILED_LCD_CHAMBER      _UxGT("Chamber heating fail")
+#endif
 #ifndef MSG_ERR_REDUNDANT_TEMP
   #define MSG_ERR_REDUNDANT_TEMP              _UxGT("Err: REDUNDANT TEMP")
 #endif
@@ -939,6 +957,9 @@
 #ifndef MSG_THERMAL_RUNAWAY_BED
   #define MSG_THERMAL_RUNAWAY_BED             _UxGT("BED THERMAL RUNAWAY")
 #endif
+#ifndef MSG_THERMAL_RUNAWAY_CHAMBER
+  #define MSG_THERMAL_RUNAWAY_CHAMBER         _UxGT("CHAMBER T. RUNAWAY")
+#endif
 #ifndef MSG_ERR_MAXTEMP
   #define MSG_ERR_MAXTEMP                     _UxGT("Err: MAXTEMP")
 #endif
diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h
index 058062ee91..e45bb3277d 100644
--- a/Marlin/src/lcd/language/language_fr.h
+++ b/Marlin/src/lcd/language/language_fr.h
@@ -33,19 +33,25 @@
 #define CHARSIZE 2
 
 #define WELCOME_MSG                         MACHINE_NAME _UxGT(" prête.")
+#define MSG_YES                             _UxGT("Oui")
+#define MSG_NO                              _UxGT("Non")
 #define MSG_BACK                            _UxGT("Retour")
 #define MSG_SD_INSERTED                     _UxGT("Carte insérée")
 #define MSG_SD_REMOVED                      _UxGT("Carte retirée")
-#define MSG_LCD_ENDSTOPS                    _UxGT("Butées") // Max length 8 characters
+#define MSG_LCD_ENDSTOPS                    _UxGT("Butées")
+#define MSG_LCD_SOFT_ENDSTOPS               _UxGT("Butées SW")
 #define MSG_MAIN                            _UxGT("Menu principal")
-#define MSG_AUTOSTART                       _UxGT("Demarrage auto")
+#define MSG_ADVANCED_SETTINGS               _UxGT("Config. avancée")
+#define MSG_CONFIGURATION                   _UxGT("Configuration")
+#define MSG_AUTOSTART                       _UxGT("Exéc. auto#.gcode")
 #define MSG_DISABLE_STEPPERS                _UxGT("Arrêter moteurs")
 #define MSG_DEBUG_MENU                      _UxGT("Menu debug")
 #define MSG_PROGRESS_BAR_TEST               _UxGT("Test barre progress.")
 #define MSG_AUTO_HOME                       _UxGT("Origine auto.")
-#define MSG_AUTO_HOME_X                     _UxGT("Origine X Auto.")
-#define MSG_AUTO_HOME_Y                     _UxGT("Origine Y Auto.")
-#define MSG_AUTO_HOME_Z                     _UxGT("Origine Z Auto.")
+#define MSG_AUTO_HOME_X                     _UxGT("Origine X auto.")
+#define MSG_AUTO_HOME_Y                     _UxGT("Origine Y auto.")
+#define MSG_AUTO_HOME_Z                     _UxGT("Origine Z auto.")
+#define MSG_AUTO_Z_ALIGN                    _UxGT("Align. Z auto.")
 #define MSG_LEVEL_BED_HOMING                _UxGT("Origine XYZ")
 #define MSG_LEVEL_BED_WAITING               _UxGT("Clic pour commencer")
 #define MSG_LEVEL_BED_NEXT_POINT            _UxGT("Point suivant")
@@ -59,14 +65,20 @@
 #define MSG_PREHEAT_1_ALL                   _UxGT("Préch. " PREHEAT_1_LABEL " Tout")
 #define MSG_PREHEAT_1_END                   MSG_PREHEAT_1 _UxGT(" buse")
 #define MSG_PREHEAT_1_BEDONLY               _UxGT("Préch. " PREHEAT_1_LABEL " lit")
-#define MSG_PREHEAT_1_SETTINGS              _UxGT("Régl. prech. " PREHEAT_1_LABEL)
+#define MSG_PREHEAT_1_SETTINGS              _UxGT("Régl. préch. " PREHEAT_1_LABEL)
 #define MSG_PREHEAT_2                       _UxGT("Préchauffage " PREHEAT_2_LABEL)
 #define MSG_PREHEAT_2_N                     _UxGT("Préchauff. " PREHEAT_2_LABEL " ")
 #define MSG_PREHEAT_2_ALL                   _UxGT("Préch. " PREHEAT_2_LABEL " Tout")
 #define MSG_PREHEAT_2_END                   MSG_PREHEAT_2 _UxGT(" buse")
 #define MSG_PREHEAT_2_BEDONLY               _UxGT("Préch. " PREHEAT_2_LABEL " lit")
-#define MSG_PREHEAT_2_SETTINGS              _UxGT("Régl. prech. " PREHEAT_2_LABEL)
+#define MSG_PREHEAT_2_SETTINGS              _UxGT("Régl. préch. " PREHEAT_2_LABEL)
+#define MSG_PREHEAT_CUSTOM                  _UxGT("Préchauff. perso.")
 #define MSG_COOLDOWN                        _UxGT("Refroidir")
+#define MSG_LASER_MENU                      _UxGT("Contrôle Laser")
+#define MSG_LASER_OFF                       _UxGT("Laser Off")
+#define MSG_LASER_ON                        _UxGT("Laser On")
+#define MSG_LASER_POWER                     _UxGT("Puissance")
+#define MSG_SPINDLE_REVERSE                 _UxGT("Inverser broches")
 #define MSG_SWITCH_PS_ON                    _UxGT("Allumer alim.")
 #define MSG_SWITCH_PS_OFF                   _UxGT("Eteindre alim.")
 #define MSG_EXTRUDE                         _UxGT("Extrusion")
@@ -77,12 +89,24 @@
 #define MSG_LEVEL_CORNERS                   _UxGT("Niveau coins")
 #define MSG_NEXT_CORNER                     _UxGT("Coin suivant")
 #define MSG_EDITING_STOPPED                 _UxGT("Arrêt édit. maillage")
-#define MSG_USER_MENU                       _UxGT("Commandes perso")
+#define MSG_MESH_X                          _UxGT("Index X")
+#define MSG_MESH_Y                          _UxGT("Index Y")
+#define MSG_MESH_EDIT_Z                     _UxGT("Valeur Z")
+#define MSG_USER_MENU                       _UxGT("Commandes perso.")
 
 #define MSG_UBL_DOING_G29                   _UxGT("G29 en cours")
 #define MSG_UBL_UNHOMED                     _UxGT("Origine XYZ d'abord")
 #define MSG_UBL_TOOLS                       _UxGT("Outils UBL")
 #define MSG_UBL_LEVEL_BED                   _UxGT("Niveau lit unifié")
+#define MSG_IDEX_MENU                       _UxGT("Mode IDEX")
+#define MSG_IDEX_MODE_AUTOPARK              _UxGT("Auto-Park")
+#define MSG_IDEX_MODE_DUPLICATE             _UxGT("Duplication")
+#define MSG_IDEX_MODE_MIRRORED_COPY         _UxGT("Copie miroir")
+#define MSG_IDEX_MODE_FULL_CTRL             _UxGT("Contrôle complet")
+#define MSG_OFFSETS_MENU                    _UxGT("Offsets Outil")
+#define MSG_X_OFFSET                        _UxGT("Buse 2 X")
+#define MSG_Y_OFFSET                        _UxGT("Buse 2 Y")
+#define MSG_Z_OFFSET                        _UxGT("Buse 2 Z")
 #define MSG_UBL_MANUAL_MESH                 _UxGT("Maillage manuel")
 #define MSG_UBL_BC_INSERT                   _UxGT("Poser câle & mesurer")
 #define MSG_UBL_BC_INSERT2                  _UxGT("Mesure")
@@ -167,6 +191,7 @@
 #define MSG_MOVE_Y                          _UxGT("Dépl. Y")
 #define MSG_MOVE_Z                          _UxGT("Dépl. Z")
 #define MSG_MOVE_E                          _UxGT("Extrudeur")
+#define MSG_HOTEND_TOO_COLD                 _UxGT("Buse trop froide")
 #define MSG_MOVE_01MM                       _UxGT("Dépl. 0.1mm")
 #define MSG_MOVE_1MM                        _UxGT("Dépl. 1mm")
 #define MSG_MOVE_10MM                       _UxGT("Dépl. 10mm")
@@ -174,6 +199,7 @@
 #define MSG_BED_Z                           _UxGT("Lit Z")
 #define MSG_NOZZLE                          _UxGT("Buse")
 #define MSG_BED                             _UxGT("Lit")
+#define MSG_CHAMBER                         _UxGT("Caisson")
 #define MSG_FAN_SPEED                       _UxGT("Vitesse ventil.")
 #define MSG_EXTRA_FAN_SPEED                 _UxGT("Extra V ventil.")
 
@@ -203,6 +229,7 @@
 #endif
 #define MSG_VE_JERK                         _UxGT("Ve jerk")
 #define MSG_VELOCITY                        _UxGT("Vélocité")
+#define MSG_JUNCTION_DEVIATION              _UxGT("Déviat. jonct.")
 #define MSG_VMAX                            _UxGT("Vmax ")
 #define MSG_VMIN                            _UxGT("Vmin ")
 #define MSG_VTRAV_MIN                       _UxGT("V dépl. min")
@@ -240,19 +267,26 @@
 #define MSG_LOAD_EEPROM                     _UxGT("Lire config")
 #define MSG_RESTORE_FAILSAFE                _UxGT("Restaurer défauts")
 #define MSG_INIT_EEPROM                     _UxGT("Initialiser EEPROM")
+#define MSG_SD_UPDATE                       _UxGT("MàJ. SD")
+#define MSG_RESET_PRINTER                   _UxGT("RàZ. imprimante")
 #define MSG_REFRESH                         _UxGT("Actualiser")
 #define MSG_WATCH                           _UxGT("Surveiller")
 #define MSG_PREPARE                         _UxGT("Préparer")
 #define MSG_TUNE                            _UxGT("Régler")
+#define MSG_START_PRINT                     _UxGT("Démarrer Impr.")
+#define MSG_BUTTON_PRINT                    _UxGT("Imprimer")
+#define MSG_BUTTON_CANCEL                   _UxGT("Annuler")
 #define MSG_PAUSE_PRINT                     _UxGT("Interrompre impr.")
 #define MSG_RESUME_PRINT                    _UxGT("Reprendre impr.")
 #define MSG_STOP_PRINT                      _UxGT("Arrêter impr.")
+#define MSG_OUTAGE_RECOVERY                 _UxGT("Récupér. coupure")
 #define MSG_CARD_MENU                       _UxGT("Impr. depuis SD")
 #define MSG_NO_CARD                         _UxGT("Pas de carte")
 #define MSG_DWELL                           _UxGT("Repos...")
-#define MSG_USERWAIT                        _UxGT("Atten. de l'util.")
+#define MSG_USERWAIT                        _UxGT("Attente utilis.")
 #define MSG_PRINT_PAUSED                    _UxGT("Impr. en pause")
-#define MSG_PRINT_ABORTED                   _UxGT("Impr. Annulée")
+#define MSG_PRINTING                        _UxGT("Impression")
+#define MSG_PRINT_ABORTED                   _UxGT("Impr. annulée")
 #define MSG_NO_MOVE                         _UxGT("Moteurs bloqués.")
 #define MSG_KILLED                          _UxGT("MORT.")
 #define MSG_STOPPED                         _UxGT("STOPPÉ.")
@@ -264,34 +298,50 @@
 #define MSG_CONTROL_RETRACT_RECOVER_SWAP    _UxGT("Ech. Rappel mm")
 #define MSG_CONTROL_RETRACT_RECOVERF        _UxGT("Rappel V")
 #define MSG_CONTROL_RETRACT_RECOVER_SWAPF   _UxGT("Ech. Rappel V")
-#define MSG_AUTORETRACT                     _UxGT("Retrait. Auto.")
+#define MSG_AUTORETRACT                     _UxGT("Retrait auto.")
+#define MSG_TOOL_CHANGE                     _UxGT("Changement outil")
+#define MSG_TOOL_CHANGE_ZLIFT               _UxGT("Augmenter Z")
+#define MSG_SINGLENOZZLE_PRIME_SPD          _UxGT("Vitesse primaire")
+#define MSG_SINGLENOZZLE_RETRACT_SPD        _UxGT("Vitesse retrait")
+#define MSG_NOZZLE_STANDBY                  _UxGT("Attente buse")
+#define MSG_FILAMENT_SWAP_LENGTH            _UxGT("Distance retrait")
 #define MSG_FILAMENTCHANGE                  _UxGT("Changer filament")
 #define MSG_FILAMENTLOAD                    _UxGT("Charger fil.")
 #define MSG_FILAMENTUNLOAD                  _UxGT("Décharger fil.")
 #define MSG_FILAMENTUNLOAD_ALL              _UxGT("Décharger tout")
 #define MSG_INIT_SDCARD                     _UxGT("Init. la carte SD")
 #define MSG_CHANGE_SDCARD                   _UxGT("Changer de carte")
-#define MSG_ZPROBE_OUT                      _UxGT("Z sonde hors lit")
+#define MSG_ZPROBE_OUT                      _UxGT("Sonde Z hors lit")
 #define MSG_SKEW_FACTOR                     _UxGT("Facteur écart")
 #define MSG_BLTOUCH                         _UxGT("BLTouch")
 #define MSG_BLTOUCH_SELFTEST                _UxGT("Autotest BLTouch")
 #define MSG_BLTOUCH_RESET                   _UxGT("RaZ BLTouch")
 #define MSG_BLTOUCH_DEPLOY                  _UxGT("Déployer BLTouch")
+#define MSG_BLTOUCH_SW_MODE                 _UxGT("Mode BLTouch SW")
+#define MSG_BLTOUCH_5V_MODE                 _UxGT("Mode BLTouch 5V")
+#define MSG_BLTOUCH_OD_MODE                 _UxGT("Mode BLTouch OD")
 #define MSG_BLTOUCH_STOW                    _UxGT("Ranger BLTouch")
+#define MSG_MANUAL_DEPLOY                   _UxGT("Déployer Sonde Z")
+#define MSG_MANUAL_STOW                     _UxGT("Ranger Sonde Z")
 #define MSG_HOME                            _UxGT("Origine")  // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST
 #define MSG_FIRST                           _UxGT("Premier")
 #define MSG_ZPROBE_ZOFFSET                  _UxGT("Décalage Z")
 #define MSG_BABYSTEP_X                      _UxGT("Babystep X")
 #define MSG_BABYSTEP_Y                      _UxGT("Babystep Y")
 #define MSG_BABYSTEP_Z                      _UxGT("Babystep Z")
+#define MSG_BABYSTEP_TOTAL                  _UxGT("Total")
 #define MSG_ENDSTOP_ABORT                   _UxGT("Butée abandon")
 #define MSG_HEATING_FAILED_LCD              _UxGT("Erreur de chauffe")
+#define MSG_HEATING_FAILED_LCD_BED          _UxGT("Erreur de chauffe lit")
 #define MSG_ERR_REDUNDANT_TEMP              _UxGT("Err: TEMP. REDONDANTE")
 #define MSG_THERMAL_RUNAWAY                 _UxGT("EMBALLEMENT THERM.")
+#define MSG_THERMAL_RUNAWAY_BED             _UxGT("ERREUR THERMIQUE LIT")
 #define MSG_ERR_MAXTEMP                     _UxGT("Err: TEMP. MAX")
 #define MSG_ERR_MINTEMP                     _UxGT("Err: TEMP. MIN")
 #define MSG_ERR_MAXTEMP_BED                 _UxGT("Err: TEMP. MAX LIT")
 #define MSG_ERR_MINTEMP_BED                 _UxGT("Err: TEMP. MIN LIT")
+#define MSG_ERR_MAXTEMP_CHAMBER             _UxGT("Err: MAXTEMP CAISSON")
+#define MSG_ERR_MINTEMP_CHAMBER             _UxGT("Err: MINTEMP CAISSON")
 #define MSG_ERR_Z_HOMING                    MSG_HOME _UxGT(" ") MSG_X MSG_Y _UxGT(" ") MSG_FIRST
 
 #define MSG_HALTED                          _UxGT("IMPR. STOPPÉE")
@@ -301,7 +351,9 @@
 #define MSG_SHORT_MINUTE                    _UxGT("m") // One character only
 
 #define MSG_HEATING                         _UxGT("En chauffe...")
+#define MSG_COOLING                         _UxGT("Refroidissement")
 #define MSG_BED_HEATING                     _UxGT("Lit en chauffe...")
+#define MSG_BED_COOLING                     _UxGT("Refroid. du lit...")
 #define MSG_DELTA_CALIBRATE                 _UxGT("Calibration Delta")
 #define MSG_DELTA_CALIBRATE_X               _UxGT("Calibrer X")
 #define MSG_DELTA_CALIBRATE_Y               _UxGT("Calibrer Y")
@@ -310,6 +362,7 @@
 #define MSG_DELTA_SETTINGS                  _UxGT("Réglages Delta")
 #define MSG_DELTA_AUTO_CALIBRATE            _UxGT("Calibration Auto")
 #define MSG_DELTA_HEIGHT_CALIBRATE          _UxGT("Hauteur Delta")
+#define MSG_DELTA_Z_OFFSET_CALIBRATE        _UxGT("Delta Z sonde")
 #define MSG_DELTA_DIAG_ROD                  _UxGT("Diagonale")
 #define MSG_DELTA_HEIGHT                    _UxGT("Hauteur")
 #define MSG_DELTA_RADIUS                    _UxGT("Rayon")
@@ -323,9 +376,9 @@
 #define MSG_MESH_LEVELING                   _UxGT("Niveau maillage")
 #define MSG_INFO_STATS_MENU                 _UxGT("Stats. imprimante")
 #define MSG_INFO_BOARD_MENU                 _UxGT("Infos carte")
-#define MSG_INFO_THERMISTOR_MENU            _UxGT("Thermistors")
+#define MSG_INFO_THERMISTOR_MENU            _UxGT("Thermistances")
 #define MSG_INFO_EXTRUDERS                  _UxGT("Extrudeurs")
-#define MSG_INFO_BAUDRATE                   _UxGT("Baud")
+#define MSG_INFO_BAUDRATE                   _UxGT("Bauds")
 #define MSG_INFO_PROTOCOL                   _UxGT("Protocole")
 #define MSG_CASE_LIGHT                      _UxGT("Lumière caisson")
 #define MSG_CASE_LIGHT_BRIGHTNESS           _UxGT("Luminosité")
@@ -358,35 +411,109 @@
 #define MSG_FILAMENT_CHANGE_OPTION_PURGE    _UxGT("Purger encore")
 #define MSG_FILAMENT_CHANGE_OPTION_RESUME   _UxGT("Reprendre impr.")
 #define MSG_FILAMENT_CHANGE_NOZZLE          _UxGT("  Buse: ")
+#define MSG_RUNOUT_SENSOR                   _UxGT("Capteur Fil.")
 #define MSG_ERR_HOMING_FAILED               _UxGT("Echec origine")
 #define MSG_ERR_PROBING_FAILED              _UxGT("Echec sonde")
 #define MSG_M600_TOO_COLD                   _UxGT("M600: Trop froid")
+#define MSG_MMU2_FILAMENT_CHANGE_HEADER     _UxGT("CHANGER FILAMENT")
+#define MSG_MMU2_CHOOSE_FILAMENT_HEADER     _UxGT("CHOISIR FILAMENT")
+#define MSG_MMU2_MENU                       _UxGT("MMU")
+#define MSG_MMU2_WRONG_FIRMWARE             _UxGT("Update MMU firmware!")
+#define MSG_MMU2_NOT_RESPONDING             _UxGT("MMU ne répond plus")
+#define MSG_MMU2_RESUME                     _UxGT("Continuer impr.")
+#define MSG_MMU2_RESUMING                   _UxGT("Reprise...")
+#define MSG_MMU2_LOAD_FILAMENT              _UxGT("Charger filament")
+#define MSG_MMU2_LOAD_ALL                   _UxGT("Charger tous")
+#define MSG_MMU2_LOAD_TO_NOZZLE             _UxGT("Charger dans buse")
+#define MSG_MMU2_EJECT_FILAMENT             _UxGT("Ejecter filament")
+#define MSG_MMU2_EJECT_FILAMENT0            _UxGT("Ejecter fil. 1")
+#define MSG_MMU2_EJECT_FILAMENT1            _UxGT("Ejecter fil. 2")
+#define MSG_MMU2_EJECT_FILAMENT2            _UxGT("Ejecter fil. 3")
+#define MSG_MMU2_EJECT_FILAMENT3            _UxGT("Ejecter fil. 4")
+#define MSG_MMU2_EJECT_FILAMENT4            _UxGT("Ejecter fil. 5")
+#define MSG_MMU2_UNLOAD_FILAMENT            _UxGT("Retrait filament")
+#define MSG_MMU2_LOADING_FILAMENT           _UxGT("Chargem. fil. %i...")
+#define MSG_MMU2_EJECTING_FILAMENT          _UxGT("Ejection fil...")
+#define MSG_MMU2_UNLOADING_FILAMENT         _UxGT("Retrait fil....")
+#define MSG_MMU2_ALL                        _UxGT("Tous")
+#define MSG_MMU2_FILAMENT0                  _UxGT("Filament 1")
+#define MSG_MMU2_FILAMENT1                  _UxGT("Filament 2")
+#define MSG_MMU2_FILAMENT2                  _UxGT("Filament 3")
+#define MSG_MMU2_FILAMENT3                  _UxGT("Filament 4")
+#define MSG_MMU2_FILAMENT4                  _UxGT("Filament 5")
+#define MSG_MMU2_RESET                      _UxGT("Réinit. MMU")
+#define MSG_MMU2_RESETTING                  _UxGT("Réinit. MMU...")
+#define MSG_MMU2_EJECT_RECOVER              _UxGT("Retrait, click")
+
+#define MSG_MIX                             _UxGT("Mix")
+#define MSG_MIX_COMPONENT                   _UxGT("Composante")
+#define MSG_MIXER                           _UxGT("Mixeur")
+#define MSG_GRADIENT                        _UxGT("Dégradé")
+#define MSG_FULL_GRADIENT                   _UxGT("Dégradé complet")
+#define MSG_TOGGLE_MIX                      _UxGT("Toggle mix")
+#define MSG_CYCLE_MIX                       _UxGT("Cycle mix")
+#define MSG_GRADIENT_MIX                    _UxGT("Mix dégradé")
+#define MSG_REVERSE_GRADIENT                _UxGT("Inverser dégradé")
+#define MSG_ACTIVE_VTOOL                    _UxGT("Active V-tool")
+#define MSG_START_VTOOL                     _UxGT("Début V-tool")
+#define MSG_END_VTOOL                       _UxGT("  Fin V-tool")
+#define MSG_GRADIENT_ALIAS                  _UxGT("Alias V-tool")
+#define MSG_RESET_VTOOLS                    _UxGT("Réinit. V-tools")
+#define MSG_COMMIT_VTOOL                    _UxGT("Valider Mix V-tool")
+#define MSG_VTOOLS_RESET                    _UxGT("V-tools réinit. ok")
+#define MSG_START_Z                         _UxGT("Début Z")
+#define MSG_END_Z                           _UxGT("  Fin Z")
+#define MSG_BRICKOUT                        _UxGT("Casse-briques")
+#define MSG_INVADERS                        _UxGT("Invaders")
+#define MSG_SNAKE                           _UxGT("Sn4k3")
+#define MSG_MAZE                            _UxGT("Labyrinthe")
 
 #if LCD_HEIGHT >= 4
   // Up to 3 lines allowed
-  #define MSG_FILAMENT_CHANGE_INIT_1        _UxGT("Attente Démarrage")
-  #define MSG_FILAMENT_CHANGE_INIT_2        _UxGT("du filament")
-  #define MSG_FILAMENT_CHANGE_INIT_3        _UxGT("changer")
-  #define MSG_FILAMENT_CHANGE_UNLOAD_1      _UxGT("Attente de")
-  #define MSG_FILAMENT_CHANGE_UNLOAD_2      _UxGT("décharger filament")
+  #define MSG_ADVANCED_PAUSE_WAITING_1      _UxGT("Presser bouton")
+  #define MSG_ADVANCED_PAUSE_WAITING_2      _UxGT("pour reprendre")
+  #define MSG_PAUSE_PRINT_INIT_1            _UxGT("Parking...")
+  #define MSG_FILAMENT_CHANGE_INIT_1        _UxGT("Attente filament")
+  #define MSG_FILAMENT_CHANGE_INIT_2        _UxGT("pour démarrer")
   #define MSG_FILAMENT_CHANGE_INSERT_1      _UxGT("Insérer filament")
   #define MSG_FILAMENT_CHANGE_INSERT_2      _UxGT("et app. bouton")
   #define MSG_FILAMENT_CHANGE_INSERT_3      _UxGT("pour continuer...")
   #define MSG_FILAMENT_CHANGE_HEAT_1        _UxGT("Presser le bouton...")
-  #define MSG_FILAMENT_CHANGE_HEAT_2        _UxGT("Pr chauffer la buse")
+  #define MSG_FILAMENT_CHANGE_HEAT_2        _UxGT("pr chauffer la buse")
   #define MSG_FILAMENT_CHANGE_HEATING_1     _UxGT("Buse en chauffe")
-  #define MSG_FILAMENT_CHANGE_HEATING_2     _UxGT("Patientez SVP...")
-  #define MSG_FILAMENT_CHANGE_LOAD_1        _UxGT("Attente de")
-  #define MSG_FILAMENT_CHANGE_LOAD_2        _UxGT("Chargement filament")
+  #define MSG_FILAMENT_CHANGE_HEATING_2     _UxGT("Patienter SVP...")
+  #define MSG_FILAMENT_CHANGE_UNLOAD_1      _UxGT("Attente")
+  #define MSG_FILAMENT_CHANGE_UNLOAD_2      _UxGT("retrait du filament")
+  #define MSG_FILAMENT_CHANGE_LOAD_1        _UxGT("Attente")
+  #define MSG_FILAMENT_CHANGE_LOAD_2        _UxGT("chargement filament")
   #define MSG_FILAMENT_CHANGE_PURGE_1       _UxGT("Attente")
-  #define MSG_FILAMENT_CHANGE_PURGE_2       _UxGT("Purger filament")
-  #define MSG_FILAMENT_CHANGE_RESUME_1      _UxGT("Attente impression")
-  #define MSG_FILAMENT_CHANGE_RESUME_2      _UxGT("pour reprendre")
+  #define MSG_FILAMENT_CHANGE_PURGE_2       _UxGT("Purge filament")
+  #define MSG_FILAMENT_CHANGE_CONT_PURGE_1  _UxGT("Presser pour finir")
+  #define MSG_FILAMENT_CHANGE_CONT_PURGE_2  _UxGT("la purge du filament")
+  #define MSG_FILAMENT_CHANGE_RESUME_1      _UxGT("Attente reprise")
+  #define MSG_FILAMENT_CHANGE_RESUME_2      _UxGT("impression")
 #else // LCD_HEIGHT < 4
   // Up to 2 lines allowed
-  #define MSG_FILAMENT_CHANGE_INIT_1        _UxGT("Patientez...")
-  #define MSG_FILAMENT_CHANGE_UNLOAD_1      _UxGT("Ejection...")
-  #define MSG_FILAMENT_CHANGE_INSERT_1      _UxGT("Insérer et clic")
+  #define MSG_ADVANCED_PAUSE_WAITING_1      _UxGT("Presser pr continuer")
+  #define MSG_FILAMENT_CHANGE_INIT_1        _UxGT("Patience...")
+  #define MSG_FILAMENT_CHANGE_INSERT_1      _UxGT("Insérer fil.")
+  #define MSG_FILAMENT_CHANGE_HEAT_1        _UxGT("Chauffer ?")
+  #define MSG_FILAMENT_CHANGE_HEATING_1     _UxGT("Chauffage...")
+  #define MSG_FILAMENT_CHANGE_UNLOAD_1      _UxGT("Ejecting...")
   #define MSG_FILAMENT_CHANGE_LOAD_1        _UxGT("Chargement...")
+  #define MSG_FILAMENT_CHANGE_PURGE_1       _UxGT("Purge...")
+  #define MSG_FILAMENT_CHANGE_CONT_PURGE_1  _UxGT("Terminer ?")
   #define MSG_FILAMENT_CHANGE_RESUME_1      _UxGT("Reprise...")
 #endif // LCD_HEIGHT < 4
+
+#define MSG_TMC_DRIVERS                     _UxGT("Drivers TMC")
+#define MSG_TMC_CURRENT                     _UxGT("Courant driver")
+#define MSG_TMC_HYBRID_THRS                 _UxGT("Seuil hybride")
+#define MSG_TMC_HOMING_THRS                 _UxGT("Home sans capteur")
+#define MSG_TMC_STEPPING_MODE               _UxGT("Mode pas à pas")
+#define MSG_TMC_STEALTH_ENABLED             _UxGT("StealthChop activé")
+#define MSG_SERVICE_RESET                   _UxGT("Réinit.")
+#define MSG_SERVICE_IN                      _UxGT("  dans:")
+#define MSG_BACKLASH                        _UxGT("Backlash")
+#define MSG_BACKLASH_CORRECTION             _UxGT("Correction")
+#define MSG_BACKLASH_SMOOTHING              _UxGT("Lissage")
diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h
index 36bfd70f19..78450b47bd 100644
--- a/Marlin/src/lcd/language/language_it.h
+++ b/Marlin/src/lcd/language/language_it.h
@@ -330,9 +330,11 @@
 #define MSG_ENDSTOP_ABORT                   _UxGT("Finecorsa annullati")
 #define MSG_HEATING_FAILED_LCD              _UxGT("Riscald. Fallito")
 #define MSG_HEATING_FAILED_LCD_BED          _UxGT("Risc. piatto fallito")
+#define MSG_HEATING_FAILED_LCD_CHAMBER      _UxGT("Risc. camera fallito")
 #define MSG_ERR_REDUNDANT_TEMP              _UxGT("Err: TEMP RIDONDANTE")
 #define MSG_THERMAL_RUNAWAY                 _UxGT("TEMP FUORI CONTROLLO")
 #define MSG_THERMAL_RUNAWAY_BED             _UxGT("TEMP PIAT.FUORI CTRL")
+#define MSG_THERMAL_RUNAWAY_CHAMBER         _UxGT("T.CAMERA FUORI CTRL")
 #define MSG_ERR_MAXTEMP                     _UxGT("Err: TEMP MASSIMA")
 #define MSG_ERR_MINTEMP                     _UxGT("Err: TEMP MINIMA")
 #define MSG_ERR_MAXTEMP_BED                 _UxGT("Err: TEMP MAX PIATTO")
diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp
index 1a053ad850..ba6957ddaf 100644
--- a/Marlin/src/lcd/menu/menu.cpp
+++ b/Marlin/src/lcd/menu/menu.cpp
@@ -268,6 +268,8 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co
     #if HAS_GRAPHICAL_LCD
       drawing_screen = false;
     #endif
+
+    set_ui_selection(false);
   }
 }
 
@@ -436,12 +438,21 @@ void _lcd_draw_homing() {
   void _lcd_toggle_bed_leveling() { set_bed_leveling_enabled(!planner.leveling_active); }
 #endif
 
-void do_select_screen(PGM_P const yes, PGM_P const no, bool &yesno, PGM_P const pref, const char * const string, PGM_P const suff) {
+//
+// Selection screen presents a prompt and two options
+//
+bool ui_selection; // = false
+void set_ui_selection(const bool sel) { ui_selection = sel; }
+void do_select_screen(PGM_P const yes, PGM_P const no, selectFunc_t yesFunc, selectFunc_t noFunc, PGM_P const pref, const char * const string/*=NULL*/, PGM_P const suff/*=NULL*/) {
   if (ui.encoderPosition) {
-    yesno = int16_t(ui.encoderPosition) > 0;
+    ui_selection = int16_t(ui.encoderPosition) > 0;
     ui.encoderPosition = 0;
   }
-  draw_select_screen(yes, no, yesno, pref, string, suff);
+  const bool got_click = ui.use_click();
+  if (got_click || ui.should_draw()) {
+    draw_select_screen(yes, no, ui_selection, pref, string, suff);
+    if (got_click) { ui_selection ? yesFunc() : noFunc(); }
+  }
 }
 
 #endif // HAS_LCD_MENU
diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h
index acc51a2ae0..de3bd210fb 100644
--- a/Marlin/src/lcd/menu/menu.h
+++ b/Marlin/src/lcd/menu/menu.h
@@ -65,12 +65,15 @@ DECLARE_MENU_EDIT_TYPE(uint32_t, long5,       ftostr5rj,       0.01f );   // 123
 ///////// Menu Item Draw Functions /////////
 ////////////////////////////////////////////
 
-void draw_edit_screen(PGM_P const pstr, const char* const value=NULL);
+typedef void (*selectFunc_t)();
 void draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string, PGM_P const suff);
-void do_select_screen(PGM_P const yes, PGM_P const no, bool &yesno, PGM_P const pref, const char * const string=NULL, PGM_P const suff=NULL);
-inline void do_select_screen_yn(bool &yesno, PGM_P const pref, const char * const string, PGM_P const suff) {
-  do_select_screen(PSTR(MSG_YES), PSTR(MSG_NO), yesno, pref, string, suff);
+void set_ui_selection(const bool sel);
+void do_select_screen(PGM_P const yes, PGM_P const no, selectFunc_t yesFunc, selectFunc_t noFunc, PGM_P const pref, const char * const string=NULL, PGM_P const suff=NULL);
+inline void do_select_screen_yn(selectFunc_t yesFunc, selectFunc_t noFunc, PGM_P const pref, const char * const string=NULL, PGM_P const suff=NULL) {
+  do_select_screen(PSTR(MSG_YES), PSTR(MSG_NO), yesFunc, noFunc, pref, string, suff);
 }
+
+void draw_edit_screen(PGM_P const pstr, const char* const value=NULL);
 void draw_menu_item(const bool sel, const uint8_t row, PGM_P const pstr, const char pre_char, const char post_char);
 void draw_menu_item_static(const uint8_t row, PGM_P const pstr, const bool center=true, const bool invert=false, const char *valstr=NULL);
 void _draw_menu_item_edit(const bool sel, const uint8_t row, PGM_P const pstr, const char* const data, const bool pgm);
diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp
index 05396f8507..9d99d03962 100644
--- a/Marlin/src/lcd/menu/menu_advanced.cpp
+++ b/Marlin/src/lcd/menu/menu_advanced.cpp
@@ -604,16 +604,13 @@ void menu_backlash();
 
     #include "../../module/configuration_store.h"
 
-    static void lcd_init_eeprom() {
-      ui.completion_feedback(settings.init_eeprom());
-      ui.goto_previous_screen();
-    }
-
     static void lcd_init_eeprom_confirm() {
-      START_MENU();
-      MENU_BACK(MSG_ADVANCED_SETTINGS);
-      MENU_ITEM(function, MSG_INIT_EEPROM, lcd_init_eeprom);
-      END_MENU();
+      do_select_screen(
+        PSTR(MSG_BUTTON_INIT), PSTR(MSG_BUTTON_CANCEL),
+        []{ ui.completion_feedback(settings.init_eeprom()); },
+        ui.goto_previous_screen,
+        PSTR(MSG_INIT_EEPROM), NULL, PSTR("?")
+      );
     }
 
   #endif
diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp
index b36d8dd3b1..de24ed5a56 100644
--- a/Marlin/src/lcd/menu/menu_bed_corners.cpp
+++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp
@@ -50,13 +50,6 @@ static_assert(LEVEL_CORNERS_Z_HOP >= 0, "LEVEL_CORNERS_Z_HOP must be >= 0. Pleas
   static bool leveling_was_active = false;
 #endif
 
-static inline void _lcd_level_bed_corners_back() {
-  #if HAS_LEVELING
-    set_bed_leveling_enabled(leveling_was_active);
-  #endif
-  ui.goto_previous_screen_no_defer();
-}
-
 /**
  * Level corners, starting in the front-left corner.
  */
@@ -94,17 +87,23 @@ static inline void _lcd_goto_next_corner() {
 }
 
 static inline void menu_level_bed_corners() {
-  START_MENU();
-  MENU_ITEM(function,
-    #if ENABLED(LEVEL_CENTER_TOO)
-      MSG_LEVEL_BED_NEXT_POINT
-    #else
-      MSG_NEXT_CORNER
-    #endif
-    , _lcd_goto_next_corner
+  do_select_screen(
+    PSTR(MSG_BUTTON_NEXT), PSTR(MSG_BUTTON_DONE),
+    _lcd_goto_next_corner,
+    []{
+      #if HAS_LEVELING
+        set_bed_leveling_enabled(leveling_was_active);
+      #endif
+      ui.goto_previous_screen_no_defer();
+    },
+    PSTR(
+      #if ENABLED(LEVEL_CENTER_TOO)
+        MSG_LEVEL_BED_NEXT_POINT
+      #else
+        MSG_NEXT_CORNER
+      #endif
+    ), NULL, PSTR("?")
   );
-  MENU_ITEM(function, MSG_BACK, _lcd_level_bed_corners_back);
-  END_MENU();
 }
 
 static inline void _lcd_level_bed_corners_homing() {
@@ -112,6 +111,7 @@ static inline void _lcd_level_bed_corners_homing() {
   if (all_axes_homed()) {
     bed_corner = 0;
     ui.goto_screen(menu_level_bed_corners);
+    set_ui_selection(true);
     _lcd_goto_next_corner();
   }
 }
diff --git a/Marlin/src/lcd/menu/menu_job_recovery.cpp b/Marlin/src/lcd/menu/menu_job_recovery.cpp
index 6d584948c4..f819052977 100644
--- a/Marlin/src/lcd/menu/menu_job_recovery.cpp
+++ b/Marlin/src/lcd/menu/menu_job_recovery.cpp
@@ -44,6 +44,8 @@ static void lcd_power_loss_recovery_cancel() {
   ui.return_to_status();
 }
 
+// TODO: Display long filename with Cancel/Resume buttons
+//       Requires supporting methods in PLR class.
 void menu_job_recovery() {
   ui.defer_status_screen();
   START_MENU();
diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp
index 325f09b9b4..db9c6c867c 100644
--- a/Marlin/src/lcd/menu/menu_main.cpp
+++ b/Marlin/src/lcd/menu/menu_main.cpp
@@ -101,10 +101,7 @@
   }
 
   void menu_abort_confirm() {
-    START_MENU();
-    MENU_BACK(MSG_MAIN);
-    MENU_ITEM(function, MSG_STOP_PRINT, lcd_abort_job);
-    END_MENU();
+    do_select_screen(PSTR(MSG_BUTTON_STOP), PSTR(MSG_BACK), lcd_abort_job, ui.goto_previous_screen, PSTR(MSG_STOP_PRINT), NULL, PSTR("?"));
   }
 
 #endif // MACHINE_CAN_STOP
diff --git a/Marlin/src/lcd/menu/menu_mixer.cpp b/Marlin/src/lcd/menu/menu_mixer.cpp
index 8e5b6f4d0f..77124d1146 100644
--- a/Marlin/src/lcd/menu/menu_mixer.cpp
+++ b/Marlin/src/lcd/menu/menu_mixer.cpp
@@ -250,17 +250,17 @@ void lcd_mixer_mix_edit() {
 //
 // Reset All V-Tools
 //
-inline void _lcd_reset_vtools() {
-  LCD_MESSAGEPGM(MSG_VTOOLS_RESET);
-  ui.return_to_status();
-  mixer.reset_vtools();
-}
-
 void menu_mixer_vtools_reset_confirm() {
-  START_MENU();
-  MENU_BACK(MSG_BACK);
-  MENU_ITEM(function, MSG_RESET_VTOOLS, _lcd_reset_vtools);
-  END_MENU();
+  do_select_screen(
+    PSTR(MSG_BUTTON_RESET), PSTR(MSG_BUTTON_CANCEL),
+    []{
+      mixer.reset_vtools();
+      LCD_MESSAGEPGM(MSG_VTOOLS_RESET);
+      ui.return_to_status();
+    },
+    ui.goto_previous_screen,
+    PSTR(MSG_RESET_VTOOLS), NULL, PSTR("?")
+  );
 }
 
 void menu_mixer() {
diff --git a/Marlin/src/lcd/menu/menu_sdcard.cpp b/Marlin/src/lcd/menu/menu_sdcard.cpp
index 274643841f..d574dc150e 100644
--- a/Marlin/src/lcd/menu/menu_sdcard.cpp
+++ b/Marlin/src/lcd/menu/menu_sdcard.cpp
@@ -81,17 +81,12 @@ inline void sdcard_start_selected_file() {
 
 #if ENABLED(SD_MENU_CONFIRM_START)
 
-  bool do_print_file;
   void menu_sd_confirm() {
-    if (ui.should_draw())
-      do_select_screen(PSTR(MSG_BUTTON_PRINT), PSTR(MSG_BUTTON_CANCEL), do_print_file, PSTR(MSG_START_PRINT " "), card.longest_filename(), PSTR("?"));
-
-    if (ui.use_click()) {
-      if (do_print_file)
-        sdcard_start_selected_file();
-      else
-        ui.goto_previous_screen();
-    }
+    do_select_screen(
+      PSTR(MSG_BUTTON_PRINT), PSTR(MSG_BUTTON_CANCEL),
+      sdcard_start_selected_file, ui.goto_previous_screen,
+      PSTR(MSG_START_PRINT " "), card.longest_filename(), PSTR("?")
+    );
   }
 
 #endif
@@ -106,7 +101,6 @@ class MenuItem_sdfile {
         sd_items = screen_items;
       #endif
       #if ENABLED(SD_MENU_CONFIRM_START)
-        do_print_file = false;
         MenuItem_submenu::action(menu_sd_confirm);
       #else
         sdcard_start_selected_file();
diff --git a/Marlin/src/lcd/menu/menu_service.cpp b/Marlin/src/lcd/menu/menu_service.cpp
index 05d43f5fd0..3ab890d7bb 100644
--- a/Marlin/src/lcd/menu/menu_service.cpp
+++ b/Marlin/src/lcd/menu/menu_service.cpp
@@ -31,52 +31,32 @@
 #include "menu.h"
 #include "../../module/printcounter.h"
 
-inline void _lcd_reset_service(const int index) {
-  print_job_timer.resetServiceInterval(index);
-  BUZZ(200, 404);
-  ui.reset_status();
-  ui.return_to_status();
+inline void _menu_service(const int index, PGM_P const name) {
+  char sram[30];
+  strncpy_P(sram, name, 29);
+  do_select_screen(
+    PSTR(MSG_BUTTON_RESET), PSTR(MSG_BUTTON_CANCEL),
+    []{
+      print_job_timer.resetServiceInterval(index);
+      ui.completion_feedback(true);
+      ui.reset_status();
+      ui.return_to_status();
+    },
+    ui.goto_previous_screen,
+    PSTR(MSG_SERVICE_RESET), sram, PSTR("?")
+  );
 }
 
 #if SERVICE_INTERVAL_1 > 0
-  void menu_action_reset_service1() { _lcd_reset_service(1); }
+  void menu_service1() { _menu_service(1, PSTR(SERVICE_NAME_1)); }
 #endif
 
 #if SERVICE_INTERVAL_2 > 0
-  void menu_action_reset_service2() { _lcd_reset_service(2); }
+  void menu_service2() { _menu_service(2, PSTR(SERVICE_NAME_2)); }
 #endif
 
 #if SERVICE_INTERVAL_3 > 0
-  void menu_action_reset_service3() { _lcd_reset_service(3); }
-#endif
-
-inline void _menu_service(const int index) {
-  START_MENU();
-  MENU_BACK(MSG_MAIN);
-  switch (index) {
-    #if SERVICE_INTERVAL_1 > 0
-      case 1: MENU_ITEM(function, MSG_SERVICE_RESET, menu_action_reset_service1); break;
-    #endif
-    #if SERVICE_INTERVAL_2 > 0
-      case 2: MENU_ITEM(function, MSG_SERVICE_RESET, menu_action_reset_service2); break;
-    #endif
-    #if SERVICE_INTERVAL_3 > 0
-      case 3: MENU_ITEM(function, MSG_SERVICE_RESET, menu_action_reset_service3); break;
-    #endif
-  }
-  END_MENU();
-}
-
-#if SERVICE_INTERVAL_1 > 0
-  void menu_service1() { _menu_service(1); }
-#endif
-
-#if SERVICE_INTERVAL_2 > 0
-  void menu_service2() { _menu_service(2); }
-#endif
-
-#if SERVICE_INTERVAL_3 > 0
-  void menu_service3() { _menu_service(3); }
+  void menu_service3() { _menu_service(3, PSTR(SERVICE_NAME_3)); }
 #endif
 
 #endif // HAS_LCD_MENU && HAS_SERVICE_INTERVALS && PRINTCOUNTER
diff --git a/Marlin/src/lcd/menu/menu_tmc.cpp b/Marlin/src/lcd/menu/menu_tmc.cpp
index 3d44649599..13634c5894 100644
--- a/Marlin/src/lcd/menu/menu_tmc.cpp
+++ b/Marlin/src/lcd/menu/menu_tmc.cpp
@@ -32,7 +32,7 @@
 #include "../../module/stepper_indirection.h"
 #include "../../feature/tmc_util.h"
 
-#define TMC_EDIT_STORED_I_RMS(ST) MENU_ITEM_EDIT_CALLBACK(uint16_4, MSG_##ST, &stepper##ST.val_mA, 100, 3000, refresh_stepper_current_##ST)
+#define TMC_EDIT_STORED_I_RMS(ST,MSG) MENU_ITEM_EDIT_CALLBACK(uint16_4, MSG, &stepper##ST.val_mA, 100, 3000, refresh_stepper_current_##ST)
 
 #if AXIS_IS_TMC(X)
   void refresh_stepper_current_X()  { stepperX.refresh_stepper_current();  }
@@ -78,50 +78,50 @@ void menu_tmc_current() {
   START_MENU();
   MENU_BACK(MSG_TMC_DRIVERS);
   #if AXIS_IS_TMC(X)
-    TMC_EDIT_STORED_I_RMS(X);
+    TMC_EDIT_STORED_I_RMS(X, MSG_X);
   #endif
   #if AXIS_IS_TMC(Y)
-    TMC_EDIT_STORED_I_RMS(Y);
+    TMC_EDIT_STORED_I_RMS(Y, MSG_Y);
   #endif
   #if AXIS_IS_TMC(Z)
-    TMC_EDIT_STORED_I_RMS(Z);
+    TMC_EDIT_STORED_I_RMS(Z, MSG_Z);
   #endif
   #if AXIS_IS_TMC(X2)
-    TMC_EDIT_STORED_I_RMS(X2);
+    TMC_EDIT_STORED_I_RMS(X2, MSG_X2);
   #endif
   #if AXIS_IS_TMC(Y2)
-    TMC_EDIT_STORED_I_RMS(Y2);
+    TMC_EDIT_STORED_I_RMS(Y2, MSG_Y2);
   #endif
   #if AXIS_IS_TMC(Z2)
-    TMC_EDIT_STORED_I_RMS(Z2);
+    TMC_EDIT_STORED_I_RMS(Z2, MSG_Z2);
   #endif
   #if AXIS_IS_TMC(Z3)
-    TMC_EDIT_STORED_I_RMS(Z3);
+    TMC_EDIT_STORED_I_RMS(Z3, MSG_Z3);
   #endif
   #if AXIS_IS_TMC(E0)
-    TMC_EDIT_STORED_I_RMS(E0);
+    TMC_EDIT_STORED_I_RMS(E0, MSG_E1);
   #endif
   #if AXIS_IS_TMC(E1)
-    TMC_EDIT_STORED_I_RMS(E1);
+    TMC_EDIT_STORED_I_RMS(E1, MSG_E2);
   #endif
   #if AXIS_IS_TMC(E2)
-    TMC_EDIT_STORED_I_RMS(E2);
+    TMC_EDIT_STORED_I_RMS(E2, MSG_E3);
   #endif
   #if AXIS_IS_TMC(E3)
-    TMC_EDIT_STORED_I_RMS(E3);
+    TMC_EDIT_STORED_I_RMS(E3, MSG_E4);
   #endif
   #if AXIS_IS_TMC(E4)
-    TMC_EDIT_STORED_I_RMS(E4);
+    TMC_EDIT_STORED_I_RMS(E4, MSG_E5);
   #endif
   #if AXIS_IS_TMC(E5)
-    TMC_EDIT_STORED_I_RMS(E5);
+    TMC_EDIT_STORED_I_RMS(E5, MSG_E6);
   #endif
   END_MENU();
 }
 
 #if ENABLED(HYBRID_THRESHOLD)
 
-  #define TMC_EDIT_STORED_HYBRID_THRS(ST) MENU_ITEM_EDIT_CALLBACK(uint8, MSG_##ST, &stepper##ST.stored.hybrid_thrs, 0, 255, refresh_hybrid_thrs_##ST);
+  #define TMC_EDIT_STORED_HYBRID_THRS(ST, MSG) MENU_ITEM_EDIT_CALLBACK(uint8, MSG, &stepper##ST.stored.hybrid_thrs, 0, 255, refresh_hybrid_thrs_##ST);
 
   #if AXIS_HAS_STEALTHCHOP(X)
     void refresh_hybrid_thrs_X()  {  stepperX.refresh_hybrid_thrs(planner.settings.axis_steps_per_mm[X_AXIS]); }
@@ -167,43 +167,43 @@ void menu_tmc_current() {
     START_MENU();
     MENU_BACK(MSG_TMC_DRIVERS);
     #if AXIS_HAS_STEALTHCHOP(X)
-      TMC_EDIT_STORED_HYBRID_THRS(X);
+      TMC_EDIT_STORED_HYBRID_THRS(X, MSG_X);
     #endif
     #if AXIS_HAS_STEALTHCHOP(Y)
-      TMC_EDIT_STORED_HYBRID_THRS(Y);
+      TMC_EDIT_STORED_HYBRID_THRS(Y, MSG_Y);
     #endif
     #if AXIS_HAS_STEALTHCHOP(Z)
-      TMC_EDIT_STORED_HYBRID_THRS(Z);
+      TMC_EDIT_STORED_HYBRID_THRS(Z, MSG_Z);
     #endif
     #if AXIS_HAS_STEALTHCHOP(X2)
-      TMC_EDIT_STORED_HYBRID_THRS(X2);
+      TMC_EDIT_STORED_HYBRID_THRS(X2, MSG_X2);
     #endif
     #if AXIS_HAS_STEALTHCHOP(Y2)
-      TMC_EDIT_STORED_HYBRID_THRS(Y2);
+      TMC_EDIT_STORED_HYBRID_THRS(Y2, MSG_Y2);
     #endif
     #if AXIS_HAS_STEALTHCHOP(Z2)
-      TMC_EDIT_STORED_HYBRID_THRS(Z2);
+      TMC_EDIT_STORED_HYBRID_THRS(Z2, MSG_Z2);
     #endif
     #if AXIS_HAS_STEALTHCHOP(Z3)
-      TMC_EDIT_STORED_HYBRID_THRS(Z3);
+      TMC_EDIT_STORED_HYBRID_THRS(Z3, MSG_Z3);
     #endif
     #if AXIS_HAS_STEALTHCHOP(E0)
-      TMC_EDIT_STORED_HYBRID_THRS(E0);
+      TMC_EDIT_STORED_HYBRID_THRS(E0, MSG_E1);
     #endif
     #if AXIS_HAS_STEALTHCHOP(E1)
-      TMC_EDIT_STORED_HYBRID_THRS(E1);
+      TMC_EDIT_STORED_HYBRID_THRS(E1, MSG_E2);
     #endif
     #if AXIS_HAS_STEALTHCHOP(E2)
-      TMC_EDIT_STORED_HYBRID_THRS(E2);
+      TMC_EDIT_STORED_HYBRID_THRS(E2, MSG_E3);
     #endif
     #if AXIS_HAS_STEALTHCHOP(E3)
-      TMC_EDIT_STORED_HYBRID_THRS(E3);
+      TMC_EDIT_STORED_HYBRID_THRS(E3, MSG_E4);
     #endif
     #if AXIS_HAS_STEALTHCHOP(E4)
-      TMC_EDIT_STORED_HYBRID_THRS(E4);
+      TMC_EDIT_STORED_HYBRID_THRS(E4, MSG_E5);
     #endif
     #if AXIS_HAS_STEALTHCHOP(E5)
-      TMC_EDIT_STORED_HYBRID_THRS(E5);
+      TMC_EDIT_STORED_HYBRID_THRS(E5, MSG_E6);
     #endif
     END_MENU();
   }
@@ -243,7 +243,7 @@ void menu_tmc_current() {
 
 #if HAS_STEALTHCHOP
 
-  #define TMC_EDIT_STEP_MODE(ST) MENU_ITEM_EDIT_CALLBACK(bool, MSG_##ST, &stepper##ST.stored.stealthChop_enabled, refresh_stepping_mode_##ST)
+  #define TMC_EDIT_STEP_MODE(ST, MSG) MENU_ITEM_EDIT_CALLBACK(bool, MSG, &stepper##ST.stored.stealthChop_enabled, refresh_stepping_mode_##ST)
 
   #if AXIS_HAS_STEALTHCHOP(X)
     void refresh_stepping_mode_X()  { stepperX.refresh_stepping_mode();  }
@@ -290,43 +290,43 @@ void menu_tmc_current() {
     STATIC_ITEM(MSG_TMC_STEALTH_ENABLED);
     MENU_BACK(MSG_TMC_DRIVERS);
     #if AXIS_HAS_STEALTHCHOP(X)
-      TMC_EDIT_STEP_MODE(X);
+      TMC_EDIT_STEP_MODE(X, MSG_X);
     #endif
     #if AXIS_HAS_STEALTHCHOP(Y)
-      TMC_EDIT_STEP_MODE(Y);
+      TMC_EDIT_STEP_MODE(Y, MSG_Y);
     #endif
     #if AXIS_HAS_STEALTHCHOP(Z)
-      TMC_EDIT_STEP_MODE(Z);
+      TMC_EDIT_STEP_MODE(Z, MSG_Z);
     #endif
     #if AXIS_HAS_STEALTHCHOP(X2)
-      TMC_EDIT_STEP_MODE(X2);
+      TMC_EDIT_STEP_MODE(X2, MSG_X2);
     #endif
     #if AXIS_HAS_STEALTHCHOP(Y2)
-      TMC_EDIT_STEP_MODE(Y2);
+      TMC_EDIT_STEP_MODE(Y2, MSG_Y2);
     #endif
     #if AXIS_HAS_STEALTHCHOP(Z2)
-      TMC_EDIT_STEP_MODE(Z2);
+      TMC_EDIT_STEP_MODE(Z2, MSG_Z2);
     #endif
     #if AXIS_HAS_STEALTHCHOP(Z3)
-      TMC_EDIT_STEP_MODE(Z3);
+      TMC_EDIT_STEP_MODE(Z3, MSG_Z3);
     #endif
     #if AXIS_HAS_STEALTHCHOP(E0)
-      TMC_EDIT_STEP_MODE(E0);
+      TMC_EDIT_STEP_MODE(E0, MSG_E1);
     #endif
     #if AXIS_HAS_STEALTHCHOP(E1)
-      TMC_EDIT_STEP_MODE(E1);
+      TMC_EDIT_STEP_MODE(E1, MSG_E2);
     #endif
     #if AXIS_HAS_STEALTHCHOP(E2)
-      TMC_EDIT_STEP_MODE(E2);
+      TMC_EDIT_STEP_MODE(E2, MSG_E3);
     #endif
     #if AXIS_HAS_STEALTHCHOP(E3)
-      TMC_EDIT_STEP_MODE(E3);
+      TMC_EDIT_STEP_MODE(E3, MSG_E4);
     #endif
     #if AXIS_HAS_STEALTHCHOP(E4)
-      TMC_EDIT_STEP_MODE(E4);
+      TMC_EDIT_STEP_MODE(E4, MSG_E5);
     #endif
     #if AXIS_HAS_STEALTHCHOP(E5)
-      TMC_EDIT_STEP_MODE(E5);
+      TMC_EDIT_STEP_MODE(E5, MSG_E6);
     #endif
     END_MENU();
   }
diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp
index 9b7a5b5fa6..8b182b89b9 100644
--- a/Marlin/src/lcd/menu/menu_ubl.cpp
+++ b/Marlin/src/lcd/menu/menu_ubl.cpp
@@ -615,8 +615,10 @@ void _lcd_ubl_step_by_step() {
 void _lcd_ubl_level_bed() {
   START_MENU();
   MENU_BACK(MSG_MOTION);
-  MENU_ITEM(gcode, MSG_UBL_ACTIVATE_MESH, PSTR("G29 A"));
-  MENU_ITEM(gcode, MSG_UBL_DEACTIVATE_MESH, PSTR("G29 D"));
+  if (planner.leveling_active)
+    MENU_ITEM(gcode, MSG_UBL_DEACTIVATE_MESH, PSTR("G29 D"));
+  else
+    MENU_ITEM(gcode, MSG_UBL_ACTIVATE_MESH, PSTR("G29 A"));
   MENU_ITEM(submenu, MSG_UBL_STEP_BY_STEP_MENU, _lcd_ubl_step_by_step);
   MENU_ITEM(function, MSG_UBL_MESH_EDIT, _lcd_ubl_output_map_lcd_cmd);
   MENU_ITEM(submenu, MSG_UBL_STORAGE_MESH_MENU, _lcd_ubl_storage_mesh);
diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp
index cb8b308df3..0d4b88d2c3 100644
--- a/Marlin/src/lcd/ultralcd.cpp
+++ b/Marlin/src/lcd/ultralcd.cpp
@@ -192,24 +192,39 @@ millis_t next_button_update_ms;
 
   #endif
 
-  void wrap_string(uint8_t y, const char * const string) {
-    uint8_t x = LCD_WIDTH;
+  void _wrap_string(uint8_t &x, uint8_t &y, const char * const string, read_byte_cb_t cb_read_byte) {
+    SETCURSOR(x, y);
     if (string) {
       uint8_t *p = (uint8_t*)string;
       for (;;) {
-        if (x >= LCD_WIDTH) {
-          x = 0;
-          SETCURSOR(0, y++);
-        }
         wchar_t ch;
-        p = get_utf8_value_cb(p, read_byte_ram, &ch);
+        p = get_utf8_value_cb(p, cb_read_byte, &ch);
         if (!ch) break;
         lcd_put_wchar(ch);
         x++;
+        if (x >= LCD_WIDTH) {
+          x = 0; y++;
+          SETCURSOR(0, y);
+        }
       }
     }
   }
 
+  void MarlinUI::draw_select_screen_prompt(PGM_P const pref, const char * const string/*=NULL*/, PGM_P const suff/*=NULL*/) {
+    const uint8_t plen = utf8_strlen_P(pref), slen = suff ? utf8_strlen_P(suff) : 0;
+    uint8_t x = 0, y = 0;
+    if (!string && plen + slen <= LCD_WIDTH) {
+      x = (LCD_WIDTH - plen - slen) / 2;
+      y = LCD_HEIGHT > 3 ? 1 : 0;
+    }
+    wrap_string_P(x, y, pref);
+    if (string) {
+      if (x) { x = 0; y++; } // Move to the start of the next line
+      wrap_string(x, y, string);
+    }
+    if (suff) wrap_string_P(x, y, suff);
+  }
+
 #endif // HAS_LCD_MENU
 
 void MarlinUI::init() {
@@ -668,6 +683,7 @@ void MarlinUI::update() {
 
   static uint16_t max_display_update_time = 0;
   static millis_t next_lcd_update_ms;
+  millis_t ms = millis();
 
   #if HAS_LCD_MENU
 
@@ -729,11 +745,12 @@ void MarlinUI::update() {
 
       refresh();
       init_lcd(); // May revive the LCD if static electricity killed it
+      ms = millis();
+      next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL;  // delay LCD update until after SD activity completes
     }
 
   #endif // SDSUPPORT && SD_DETECT_PIN
 
-  const millis_t ms = millis();
   if (ELAPSED(ms, next_lcd_update_ms)
     #if HAS_GRAPHICAL_LCD
       || drawing_screen
diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h
index be694ddfe4..2ea7f45279 100644
--- a/Marlin/src/lcd/ultralcd.h
+++ b/Marlin/src/lcd/ultralcd.h
@@ -72,7 +72,11 @@
       #define LCDWRITE(c) lcd_put_wchar(c)
     #endif
 
-    void wrap_string(uint8_t y, const char * const string);
+    #include "fontutils.h"
+
+    void _wrap_string(uint8_t &x, uint8_t &y, const char * const string, read_byte_cb_t cb_read_byte);
+    inline void wrap_string_P(uint8_t &x, uint8_t &y, PGM_P const pstr) { _wrap_string(x, y, pstr, read_byte_rom); }
+    inline void wrap_string(uint8_t &x, uint8_t &y, const char * const string) { _wrap_string(x, y, string, read_byte_ram); }
 
     #if ENABLED(SDSUPPORT)
       #include "../sd/cardreader.h"
@@ -457,6 +461,8 @@ public:
       static void ubl_plot(const uint8_t x, const uint8_t inverted_y);
     #endif
 
+    static void draw_select_screen_prompt(PGM_P const pref, const char * const string=NULL, PGM_P const suff=NULL);
+
   #elif HAS_SPI_LCD
 
     static constexpr bool lcd_clicked = false;
diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp
index 0552f555a5..a766d91b6e 100644
--- a/Marlin/src/module/configuration_store.cpp
+++ b/Marlin/src/module/configuration_store.cpp
@@ -64,6 +64,10 @@
   #include "../feature/bedlevel/bedlevel.h"
 #endif
 
+#if ENABLED(EXTENSIBLE_UI)
+  #include "../lcd/extensible_ui/ui_api.h"
+#endif
+
 #if HAS_SERVOS
   #include "servo.h"
 #endif
@@ -1120,6 +1124,10 @@ void MarlinSettings::postprocess() {
         store_mesh(ubl.storage_slot);
     #endif
 
+    #if ENABLED(EXTENSIBLE_UI)
+      if (!eeprom_error) ExtUI::onStoreSettings();
+    #endif
+
     return !eeprom_error;
   }
 
@@ -1874,7 +1882,13 @@ void MarlinSettings::postprocess() {
   }
 
   bool MarlinSettings::load() {
-    if (validate()) return _load();
+    if (validate()) {
+      const bool success = _load();
+      #if ENABLED(EXTENSIBLE_UI)
+        if (success) ExtUI::onLoadSettings();
+      #endif
+      return success;
+    }
     reset();
     return true;
   }
@@ -2290,6 +2304,10 @@ void MarlinSettings::reset() {
 
   DEBUG_ECHO_START();
   DEBUG_ECHOLNPGM("Hardcoded Default Settings Loaded");
+
+  #if ENABLED(EXTENSIBLE_UI)
+    ExtUI::onFactoryReset();
+  #endif
 }
 
 #if DISABLED(DISABLE_M503)
diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp
index 8f3361944d..25a45661aa 100644
--- a/Marlin/src/module/temperature.cpp
+++ b/Marlin/src/module/temperature.cpp
@@ -86,17 +86,17 @@ Temperature thermalManager;
  */
 
 #if HAS_HEATED_BED
-  #define _BED_PSTR(E) (E) == -1 ? PSTR(MSG ## _BED) :
+  #define _BED_PSTR(M,E) (E) == -1 ? PSTR(M) :
 #else
-  #define _BED_PSTR(E)
+  #define _BED_PSTR(M,E)
 #endif
 #if HAS_HEATED_CHAMBER
-  #define _CHAMBER_PSTR(E) (E) == -2 ? PSTR(MSG ## _CHAMBER) :
+  #define _CHAMBER_PSTR(M,E) (E) == -2 ? PSTR(M) :
 #else
-  #define _CHAMBER_PSTR(E)
+  #define _CHAMBER_PSTR(M,E)
 #endif
-#define _E_PSTR(M,E,N) (HOTENDS >= (N) && (E) == (N)-1) ? PSTR(MSG_E##N " " M) :
-#define TEMP_ERR_PSTR(M,E) _BED_PSTR(E) _CHAMBER_PSTR(E) _E_PSTR(M,E,2) _E_PSTR(M,E,3) _E_PSTR(M,E,4) _E_PSTR(M,E,5) _E_PSTR(M,E,6) PSTR(MSG_E1 " " M)
+#define _E_PSTR(M,E,N) ((HOTENDS) >= (N) && (E) == (N)-1) ? PSTR(MSG_E##N " " M) :
+#define TEMP_ERR_PSTR(M,E) _BED_PSTR(M##_BED,E) _CHAMBER_PSTR(M##_CHAMBER,E) _E_PSTR(M,E,2) _E_PSTR(M,E,3) _E_PSTR(M,E,4) _E_PSTR(M,E,5) _E_PSTR(M,E,6) PSTR(MSG_E1 " " M)
 
 // public:
 
@@ -944,11 +944,29 @@ void Temperature::manage_heater() {
     if (temp_hotend[1].current < MAX(HEATER_1_MINTEMP, HEATER_1_MAX6675_TMIN + .01)) min_temp_error(1);
   #endif
 
-  #if WATCH_HOTENDS || WATCH_BED || DISABLED(PIDTEMPBED) || HAS_AUTO_FAN || HEATER_IDLE_HANDLER || WATCH_CHAMBER
+  #define HAS_THERMAL_PROTECTION (ENABLED(THERMAL_PROTECTION_HOTENDS) || HAS_THERMALLY_PROTECTED_BED || ENABLED(THERMAL_PROTECTION_CHAMBER))
+
+  #if HAS_THERMAL_PROTECTION || DISABLED(PIDTEMPBED) || HAS_AUTO_FAN || HEATER_IDLE_HANDLER
     millis_t ms = millis();
   #endif
 
+  #if HAS_THERMAL_PROTECTION
+    #ifndef THERMAL_PROTECTION_GRACE_PERIOD
+      #define THERMAL_PROTECTION_GRACE_PERIOD 0 // No grace period needed on well-behaved boards
+    #endif
+    #if THERMAL_PROTECTION_GRACE_PERIOD > 0
+      static millis_t grace_period = ms + THERMAL_PROTECTION_GRACE_PERIOD;
+      if (ELAPSED(ms, grace_period)) grace_period = 0UL;
+    #else
+      static constexpr millis_t grace_period = 0UL;
+    #endif
+  #endif
+
   HOTEND_LOOP() {
+    #if ENABLED(THERMAL_PROTECTION_HOTENDS)
+      if (!grace_period && degHotend(e) > temp_range[e].maxtemp)
+        _temp_error(e, PSTR(MSG_T_THERMAL_RUNAWAY), TEMP_ERR_PSTR(MSG_THERMAL_RUNAWAY, e));
+    #endif
 
     #if HEATER_IDLE_HANDLER
       hotend_idle[e].update(ms);
@@ -1001,6 +1019,11 @@ void Temperature::manage_heater() {
 
   #if HAS_HEATED_BED
 
+    #if ENABLED(THERMAL_PROTECTION_BED)
+      if (!grace_period && degBed() > BED_MAXTEMP)
+        _temp_error(-1, PSTR(MSG_T_THERMAL_RUNAWAY), TEMP_ERR_PSTR(MSG_THERMAL_RUNAWAY, -1));
+    #endif
+
     #if WATCH_BED
       // Make sure temperature is increasing
       if (watch_bed.elapsed(ms)) {        // Time to check the bed?
@@ -1071,6 +1094,11 @@ void Temperature::manage_heater() {
 
     #if HAS_HEATED_CHAMBER
 
+      #if ENABLED(THERMAL_PROTECTION_CHAMBER)
+        if (!grace_period && degChamber() > CHAMBER_MAXTEMP)
+          _temp_error(-2, PSTR(MSG_T_THERMAL_RUNAWAY), TEMP_ERR_PSTR(MSG_THERMAL_RUNAWAY, -2));
+      #endif
+
       #if WATCH_CHAMBER
         // Make sure temperature is increasing
         if (watch_chamber.elapsed(ms)) {                  // Time to check the chamber?
@@ -1602,7 +1630,7 @@ void Temperature::init() {
   }
 #endif
 
-#if ENABLED(THERMAL_PROTECTION_HOTENDS) || HAS_THERMALLY_PROTECTED_BED || ENABLED(THERMAL_PROTECTION_CHAMBER)
+#if HAS_THERMAL_PROTECTION
 
   #if ENABLED(THERMAL_PROTECTION_HOTENDS)
     Temperature::tr_state_machine_t Temperature::tr_state_machine[HOTENDS]; // = { { TRInactive, 0 } };
@@ -1619,17 +1647,17 @@ void Temperature::init() {
     static float tr_target_temperature[HOTENDS + 1] = { 0.0 };
 
     /**
-        SERIAL_ECHO_START();
-        SERIAL_ECHOPGM("Thermal Thermal Runaway Running. Heater ID: ");
-        if (heater_id == -2) SERIAL_ECHOPGM("chamber");
-        if (heater_id < 0) SERIAL_ECHOPGM("bed"); else SERIAL_ECHO(heater_id);
-        SERIAL_ECHOPAIR(" ;  State:", sm.state, " ;  Timer:", sm.timer, " ;  Temperature:", current, " ;  Target Temp:", target);
-        if (heater_id >= 0)
-          SERIAL_ECHOPAIR(" ;  Idle Timeout:", hotend_idle[heater_id].timed_out);
-        else
-          SERIAL_ECHOPAIR(" ;  Idle Timeout:", bed_idle.timed_out);
-        SERIAL_EOL();
-    */
+      SERIAL_ECHO_START();
+      SERIAL_ECHOPGM("Thermal Thermal Runaway Running. Heater ID: ");
+      if (heater_id == -2) SERIAL_ECHOPGM("chamber");
+      if (heater_id < 0) SERIAL_ECHOPGM("bed"); else SERIAL_ECHO(heater_id);
+      SERIAL_ECHOPAIR(" ;  State:", sm.state, " ;  Timer:", sm.timer, " ;  Temperature:", current, " ;  Target Temp:", target);
+      if (heater_id >= 0)
+        SERIAL_ECHOPAIR(" ;  Idle Timeout:", hotend_idle[heater_id].timed_out);
+      else
+        SERIAL_ECHOPAIR(" ;  Idle Timeout:", bed_idle.timed_out);
+      SERIAL_EOL();
+    //*/
 
     const int heater_index = heater_id >= 0 ? heater_id : HOTENDS;
 
@@ -2647,7 +2675,7 @@ void Temperature::isr() {
     void Temperature::set_heating_message(const uint8_t e) {
       const bool heating = isHeatingHotend(e);
       #if HOTENDS > 1
-        ui.status_printf_P(0, heating ? PSTR("E%i " MSG_HEATING) : PSTR("E%i " MSG_COOLING), int(e + 1));
+        ui.status_printf_P(0, heating ? PSTR("E%c " MSG_HEATING) : PSTR("E%c " MSG_COOLING), '1' + e);
       #else
         ui.set_status_P(heating ? PSTR("E " MSG_HEATING) : PSTR("E " MSG_COOLING));
       #endif
diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp
index 9108a23ab4..3b97cb60c1 100644
--- a/Marlin/src/module/tool_change.cpp
+++ b/Marlin/src/module/tool_change.cpp
@@ -280,47 +280,37 @@ inline void fast_line_to_current(const AxisEnum fr_axis) {
                   grabpos = parkingposx[tmp_extruder] + (tmp_extruder ? PARKING_EXTRUDER_GRAB_DISTANCE : -(PARKING_EXTRUDER_GRAB_DISTANCE)) + x_offset;
 
       /**
-       * 1. Raise Z-Axis to give enough clearance
-       * 2. Move to park position of old extruder
-       * 3. Disengage magnetic field, wait for delay
-       * 4. Move near new extruder
-       * 5. Engage magnetic field for new extruder
-       * 6. Move to parking incl. offset of new extruder
-       * 7. Lower Z-Axis
+       * 1. Move to park position of old extruder
+       * 2. Disengage magnetic field, wait for delay
+       * 3. Move near new extruder
+       * 4. Engage magnetic field for new extruder
+       * 5. Move to parking incl. offset of new extruder
+       * 6. Lower Z-Axis
        */
 
       // STEP 1
 
       if (DEBUGGING(LEVELING)) DEBUG_POS("Start Autopark", current_position);
 
-      current_position[Z_AXIS] += toolchange_settings.z_raise;
-
-      if (DEBUGGING(LEVELING)) DEBUG_POS("(1) Raise Z-Axis", current_position);
-
-      fast_line_to_current(Z_AXIS);
-      planner.synchronize();
-
-      // STEP 2
-
       current_position[X_AXIS] = parkingposx[active_extruder] + x_offset;
 
       if (DEBUGGING(LEVELING)) {
-        DEBUG_ECHOLNPAIR("(2) Park extruder ", int(active_extruder));
+        DEBUG_ECHOLNPAIR("(1) Park extruder ", int(active_extruder));
         DEBUG_POS("Moving ParkPos", current_position);
       }
 
       fast_line_to_current(X_AXIS);
       planner.synchronize();
 
-      // STEP 3
+      // STEP 2
 
-      if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("(3) Disengage magnet ");
+      if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("(2) Disengage magnet ");
 
       pe_deactivate_solenoid(active_extruder);
 
-      // STEP 4
+      // STEP 3
 
-      if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("(4) Move to position near new extruder");
+      if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("(3) Move to position near new extruder");
 
       current_position[X_AXIS] += active_extruder ? -10 : 10; // move 10mm away from parked extruder
 
@@ -329,8 +319,8 @@ inline void fast_line_to_current(const AxisEnum fr_axis) {
       fast_line_to_current(X_AXIS);
       planner.synchronize();
 
-      // STEP 5
-      if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("(5) Engage magnetic field");
+      // STEP 4
+      if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("(4) Engage magnetic field");
 
       #if ENABLED(PARKING_EXTRUDER_SOLENOIDS_INVERT)
         pe_activate_solenoid(active_extruder); //just save power for inverted magnets
@@ -338,16 +328,16 @@ inline void fast_line_to_current(const AxisEnum fr_axis) {
 
       pe_activate_solenoid(tmp_extruder);
 
-      // STEP 6
+      // STEP 5
 
       current_position[X_AXIS] = grabpos + (tmp_extruder ? -10 : 10);
       fast_line_to_current(X_AXIS);
       current_position[X_AXIS] = grabpos;
-      if (DEBUGGING(LEVELING)) DEBUG_POS("(6) Unpark extruder", current_position);
+      if (DEBUGGING(LEVELING)) DEBUG_POS("(5) Unpark extruder", current_position);
       planner.buffer_line(current_position, planner.settings.max_feedrate_mm_s[X_AXIS] * 0.5, active_extruder);
       planner.synchronize();
 
-      // STEP 7
+      // STEP 6
 
       current_position[X_AXIS] = midpos
         #if HAS_HOTEND_OFFSET
@@ -355,7 +345,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) {
         #endif
       ;
 
-      if (DEBUGGING(LEVELING)) DEBUG_POS("(7) Move midway between hotends", current_position);
+      if (DEBUGGING(LEVELING)) DEBUG_POS("(6) Move midway between hotends", current_position);
 
       fast_line_to_current(X_AXIS);
       planner.synchronize();
@@ -385,30 +375,20 @@ inline void fast_line_to_current(const AxisEnum fr_axis) {
                 grabxpos = toolheadposx[tmp_extruder];
 
     /**
-     * 1. Raise Z to give enough clearance
-     * 2. Move to switch position of current toolhead
-     * 3. Unlock tool and drop it in the dock
-     * 4. Move to the new toolhead
-     * 5. Grab and lock the new toolhead
+     * 1. Move to switch position of current toolhead
+     * 2. Unlock tool and drop it in the dock
+     * 3. Move to the new toolhead
+     * 4. Grab and lock the new toolhead
      */
 
-    // 1. Raise Z to give enough clearance
+    // 1. Move to switch position of current toolhead
 
     if (DEBUGGING(LEVELING)) DEBUG_POS("Starting Toolhead change", current_position);
 
-    current_position[Z_AXIS] += toolchange_settings.z_raise;
-
-    if (DEBUGGING(LEVELING)) DEBUG_POS("(1) Raise Z-Axis", current_position);
-
-    fast_line_to_current(Z_AXIS);
-    planner.synchronize();
-
-    // 2. Move to switch position of current toolhead
-
     current_position[X_AXIS] = placexpos;
 
     if (DEBUGGING(LEVELING)) {
-      DEBUG_ECHOLNPAIR("(2) Place old tool ", int(active_extruder));
+      DEBUG_ECHOLNPAIR("(1) Place old tool ", int(active_extruder));
       DEBUG_POS("Move X SwitchPos", current_position);
     }
 
@@ -422,9 +402,9 @@ inline void fast_line_to_current(const AxisEnum fr_axis) {
     fast_line_to_current(Y_AXIS);
     planner.synchronize();
 
-    // 3. Unlock tool and drop it in the dock
+    // 2. Unlock tool and drop it in the dock
 
-    if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("(3) Unlock and Place Toolhead");
+    if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("(2) Unlock and Place Toolhead");
 
     MOVE_SERVO(SWITCHING_TOOLHEAD_SERVO_NR, angles[1]);
     safe_delay(500);
@@ -443,9 +423,9 @@ inline void fast_line_to_current(const AxisEnum fr_axis) {
     fast_line_to_current(Y_AXIS); // move away from docked toolhead
     planner.synchronize();
 
-    // 4. Move to the new toolhead
+    // 3. Move to the new toolhead
 
-    if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("(4) Move to new toolhead position");
+    if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("(3) Move to new toolhead position");
 
     current_position[X_AXIS] = grabxpos;
 
@@ -460,9 +440,9 @@ inline void fast_line_to_current(const AxisEnum fr_axis) {
     fast_line_to_current(Y_AXIS);
     planner.synchronize();
 
-    // 5. Grab and lock the new toolhead
+    // 4. Grab and lock the new toolhead
 
-    if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("(5) Grab and lock new toolhead ");
+    if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("(4) Grab and lock new toolhead ");
 
     current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS;
 
@@ -497,30 +477,20 @@ inline void fast_line_to_current(const AxisEnum fr_axis) {
                 grabxpos = toolheadposx[tmp_extruder];
 
     /**
-     * 1. Raise Z to give enough clearance
-     * 2. Move to switch position of current toolhead
-     * 3. Release and place toolhead in the dock
-     * 4. Move to the new toolhead
-     * 5. Grab the new toolhead and move to security position
+     * 1. Move to switch position of current toolhead
+     * 2. Release and place toolhead in the dock
+     * 3. Move to the new toolhead
+     * 4. Grab the new toolhead and move to security position
      */
 
     if (DEBUGGING(LEVELING)) DEBUG_POS("Starting Toolhead change", current_position);
 
-    // 1. Raise Z to give enough clearance
-
-    current_position[Z_AXIS] += toolchange_settings.z_raise;
-
-    if (DEBUGGING(LEVELING)) DEBUG_POS("(1) Raise Z-Axis", current_position);
-
-    planner.buffer_line(current_position, planner.settings.max_feedrate_mm_s[Z_AXIS], active_extruder);
-    planner.synchronize();
-
-    // 2. Move to switch position current toolhead
+    // 1. Move to switch position current toolhead
 
     current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_CLEAR;
 
     if (DEBUGGING(LEVELING)) {
-      SERIAL_ECHOLNPAIR("(2) Place old tool ", int(active_extruder));
+      SERIAL_ECHOLNPAIR("(1) Place old tool ", int(active_extruder));
       DEBUG_POS("Move Y SwitchPos + Security", current_position);
     }
 
@@ -548,9 +518,9 @@ inline void fast_line_to_current(const AxisEnum fr_axis) {
     planner.buffer_line(current_position, (planner.settings.max_feedrate_mm_s[X_AXIS] * 0.25), active_extruder);
     planner.synchronize();
 
-    // 3. Release and place toolhead in the dock
+    // 2. Release and place toolhead in the dock
 
-    if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("(3) Release and Place Toolhead");
+    if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("(2) Release and Place Toolhead");
 
     current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_RELEASE;
 
@@ -566,9 +536,9 @@ inline void fast_line_to_current(const AxisEnum fr_axis) {
     planner.buffer_line(current_position, (planner.settings.max_feedrate_mm_s[Y_AXIS]), active_extruder);
     planner.synchronize();
 
-    // 4. Move to new toolhead position
+    // 3. Move to new toolhead position
 
-    if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("(4) Move to new toolhead position");
+    if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("(3) Move to new toolhead position");
 
     current_position[X_AXIS] = grabxpos;
 
@@ -577,9 +547,9 @@ inline void fast_line_to_current(const AxisEnum fr_axis) {
     planner.buffer_line(current_position, planner.settings.max_feedrate_mm_s[X_AXIS], active_extruder);
     planner.synchronize();
 
-    // 5. Grab the new toolhead and move to security position
+    // 4. Grab the new toolhead and move to security position
 
-    if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("(5) Grab new toolhead and move to security position");
+    if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("(4) Grab new toolhead and move to security position");
 
     current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_RELEASE;
 
@@ -732,7 +702,11 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n
     if (tmp_extruder >= EXTRUDERS)
       return invalid_extruder_error(tmp_extruder);
 
-    if (!no_move && !all_axes_homed()) {
+    if (!no_move && (!all_axes_homed()
+      #if ENABLED(DUAL_X_CARRIAGE)
+        || dual_x_carriage_mode == DXC_FULL_CONTROL_MODE
+      #endif
+    )) {
       no_move = true;
       if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("No move on toolchange");
     }
@@ -785,14 +759,15 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n
       if (!no_move) {
         #if DISABLED(SWITCHING_NOZZLE)
           // Do a small lift to avoid the workpiece in the move back (below)
-          #if ENABLED(TOOLCHANGE_PARK)
-            current_position[X_AXIS] = toolchange_settings.change_point.x;
-            current_position[Y_AXIS] = toolchange_settings.change_point.y;
-          #endif
           current_position[Z_AXIS] += toolchange_settings.z_raise;
           #if HAS_SOFTWARE_ENDSTOPS
             NOMORE(current_position[Z_AXIS], soft_endstop[Z_AXIS].max);
           #endif
+          fast_line_to_current(Z_AXIS);
+          #if ENABLED(TOOLCHANGE_PARK)
+            current_position[X_AXIS] = toolchange_settings.change_point.x;
+            current_position[Y_AXIS] = toolchange_settings.change_point.y;
+          #endif
           planner.buffer_line(current_position, feedrate_mm_s, active_extruder);
         #endif
         planner.synchronize();
@@ -875,10 +850,10 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n
         #if ENABLED(TOOLCHANGE_FILAMENT_SWAP)
           if (should_swap && !too_cold) {
             #if ENABLED(ADVANCED_PAUSE_FEATURE)
-              do_pause_e_move(toolchange_settings.swap_length + TOOLCHANGE_FIL_EXTRA_PRIME, toolchange_settings.prime_speed);
+              do_pause_e_move(toolchange_settings.swap_length + TOOLCHANGE_FIL_EXTRA_PRIME, MMM_TO_MMS(toolchange_settings.prime_speed));
             #else
               current_position[E_AXIS] += (toolchange_settings.swap_length + TOOLCHANGE_FIL_EXTRA_PRIME) / planner.e_factor[tmp_extruder];
-              planner.buffer_line(current_position, toolchange_settings.prime_speed, tmp_extruder);
+              planner.buffer_line(current_position, MMM_TO_MMS(toolchange_settings.prime_speed), tmp_extruder);
             #endif
             planner.synchronize();
 
diff --git a/Marlin/src/pins/pins_BIGTREE_SKR_V1.3.h b/Marlin/src/pins/pins_BIGTREE_SKR_V1.3.h
index 92f7dddfaa..319c56f31f 100644
--- a/Marlin/src/pins/pins_BIGTREE_SKR_V1.3.h
+++ b/Marlin/src/pins/pins_BIGTREE_SKR_V1.3.h
@@ -190,28 +190,70 @@
     #define LCD_PINS_D4     P1_21
 
   #else
-
     #define LCD_PINS_RS     P1_19
 
     #define BTN_EN1         P3_26   // (31) J3-2 & AUX-4
     #define BTN_EN2         P3_25   // (33) J3-4 & AUX-4
-    #define SD_DETECT_PIN   P1_31   // (49) (NOT 5V tolerant)
-
-    #define LCD_SDSS        P0_16   // (16) J3-7 & AUX-4
 
     #define LCD_PINS_ENABLE P1_18
     #define LCD_PINS_D4     P1_20
 
-    #if ENABLED(ULTIPANEL)
-      #define LCD_PINS_D5   P1_21
-      #define LCD_PINS_D6   P1_22
-      #define LCD_PINS_D7   P1_23
-    #endif
+    #define LCD_SDSS        P0_16   // (16) J3-7 & AUX-4
+    #define SD_DETECT_PIN   P1_31   // (49) (NOT 5V tolerant)
 
-    #if ENABLED(MKS_MINI_12864)
-      #define DOGLCD_CS     P1_21
-      #define DOGLCD_A0     P1_22
-    #endif
+    #if ENABLED(FYSETC_MINI_12864)
+      #define DOGLCD_CS     P1_18
+      #define DOGLCD_A0     P1_19
+
+      #define LCD_BACKLIGHT_PIN -1
+
+      #define LCD_RESET_PIN P1_20   // Must be high or open for LCD to operate normally.
+                                    // Seems to work best if left open.
+
+      #define FYSETC_MINI_12864_REV_1_2
+      //#define FYSETC_MINI_12864_REV_2_0
+      //#define FYSETC_MINI_12864_REV_2_1
+      #if EITHER(FYSETC_MINI_12864_REV_1_2, FYSETC_MINI_12864_REV_2_0)
+        #define RGB_LED
+        #ifndef RGB_LED_R_PIN
+          #define RGB_LED_R_PIN P1_21
+        #endif
+        #ifndef RGB_LED_G_PIN
+          #define RGB_LED_G_PIN P1_22
+        #endif
+        #ifndef RGB_LED_B_PIN
+          #define RGB_LED_B_PIN P1_23
+        #endif
+      #elif defined(FYSETC_MINI_12864_REV_2_1)
+        #define NEOPIXEL_LED
+        #define NEOPIXEL_TYPE   NEO_GRB  // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
+        #define NEOPIXEL_PIN    P1_21    // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
+        #define NEOPIXEL_PIXELS  3       // Number of LEDs in the strip
+        #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
+        #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
+        #define NEOPIXEL_STARTUP_TEST    // Cycle through colors at startup
+      #else
+        #error "Either FYSETC_MINI_12864_REV_1_2, FYSETC_MINI_12864_REV_2_0 or FYSETC_MINI_12864_REV_2_1 must be defined"
+      #endif
+
+      #if !defined(LED_USER_PRESET_STARTUP) && EITHER(FYSETC_MINI_12864_REV_2_0, FYSETC_MINI_12864_REV_2_1)
+        #error "LED_USER_PRESET_STARTUP must be enabled when using FYSETC_MINI_12864 REV 2.0 and later"
+      #endif
+
+    #else // !FYSETC_MINI_12864
+
+      #if ENABLED(MKS_MINI_12864)
+        #define DOGLCD_CS     P1_21
+        #define DOGLCD_A0     P1_22
+      #endif
+
+      #if ENABLED(ULTIPANEL)
+        #define LCD_PINS_D5   P1_21
+        #define LCD_PINS_D6   P1_22
+        #define LCD_PINS_D7   P1_23
+      #endif
+
+    #endif // !FYSETC_MINI_12864
 
   #endif
 
diff --git a/Marlin/src/pins/pins_ESP32.h b/Marlin/src/pins/pins_ESP32.h
index 343f3841a6..9901dde200 100644
--- a/Marlin/src/pins/pins_ESP32.h
+++ b/Marlin/src/pins/pins_ESP32.h
@@ -72,3 +72,6 @@
 #define HEATER_0_PIN         2
 #define FAN_PIN             13
 #define HEATER_BED_PIN       4
+
+// SPI
+#define SDSS                 5
diff --git a/Marlin/src/pins/pins_FORMBOT_RAPTOR.h b/Marlin/src/pins/pins_FORMBOT_RAPTOR.h
index 5944be04af..10a517aec4 100644
--- a/Marlin/src/pins/pins_FORMBOT_RAPTOR.h
+++ b/Marlin/src/pins/pins_FORMBOT_RAPTOR.h
@@ -181,16 +181,16 @@
 // Formbot only supports REPRAP_DISCOUNT_SMART_CONTROLLER
 //
 #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER)
-  #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
-  #define LCD_PINS_D7      29
   #define BEEPER_PIN       37
   #define BTN_EN1          31
   #define BTN_EN2          33
   #define BTN_ENC          35
   #define SD_DETECT_PIN    49
   #define KILL_PIN         41
+  #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
+  #define LCD_PINS_D7      29
 #endif
diff --git a/Marlin/src/pins/pins_FORMBOT_TREX2PLUS.h b/Marlin/src/pins/pins_FORMBOT_TREX2PLUS.h
index 5970123e1f..16649e42b5 100644
--- a/Marlin/src/pins/pins_FORMBOT_TREX2PLUS.h
+++ b/Marlin/src/pins/pins_FORMBOT_TREX2PLUS.h
@@ -155,9 +155,8 @@
 //
 // Misc. Functions
 //
-#define CASE_LIGHT_PIN      8
 #define SDSS               53
-#ifndef ROXYs_TRex
+#ifndef LED_PIN
   #define LED_PIN          13   // The Formbot v 1 board has almost no unassigned pins on it.  The Board's LED
 #endif                          // is a good place to get a signal to control the Max7219 LED Matrix.
 
@@ -168,24 +167,28 @@
   #define PS_ON_PIN        12
 #endif
 
+#define CASE_LIGHT_PIN      8
+
 //
 // LCD / Controller
 //
 // Formbot only supports REPRAP_DISCOUNT_SMART_CONTROLLER
 //
 #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER)
+  #ifndef BEEPER_PIN
+    #define BEEPER_PIN     37
+  #endif
+  #define BTN_EN1          31
+  #define BTN_EN2          33
+  #define BTN_ENC          35
+  #define SD_DETECT_PIN    49
+  #ifndef KILL_PIN
+    #define KILL_PIN       41
+  #endif
   #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
   #define LCD_PINS_D7      29
-  #define BTN_EN1          31
-  #define BTN_EN2          33
-  #define BTN_ENC          35
-  #define SD_DETECT_PIN    49
-  #ifndef ROXYs_TRex
-    #define KILL_PIN       41
-    #define BEEPER_PIN     37
-  #endif
 #endif
diff --git a/Marlin/src/pins/pins_FORMBOT_TREX3.h b/Marlin/src/pins/pins_FORMBOT_TREX3.h
index 5b4bd8b533..8ff09f47c5 100644
--- a/Marlin/src/pins/pins_FORMBOT_TREX3.h
+++ b/Marlin/src/pins/pins_FORMBOT_TREX3.h
@@ -139,7 +139,7 @@
 //
 #define CASE_LIGHT_PIN      5
 #define SDSS               53
-#ifndef ROXYs_TRex
+#ifndef LED_PIN
   #define LED_PIN          13
 #endif
 
@@ -165,8 +165,10 @@
   #define BTN_EN2          33
   #define BTN_ENC          35
   #define SD_DETECT_PIN    49
-  #ifndef ROXYs_TRex
+  #ifndef KILL_PIN
     #define KILL_PIN       41
+  #endif
+  #ifndef BEEPER_PIN
     #define BEEPER_PIN     37
   #endif
 #endif
diff --git a/Marlin/src/pins/pins_FYSETC_F6_13.h b/Marlin/src/pins/pins_FYSETC_F6_13.h
index e725583008..d40abd1024 100644
--- a/Marlin/src/pins/pins_FYSETC_F6_13.h
+++ b/Marlin/src/pins/pins_FYSETC_F6_13.h
@@ -28,8 +28,8 @@
   #error "Oops! Select 'FYSETC F6' in 'Tools > Board.'"
 #endif
 
-#ifdef SD_DETECT_INVERTED
-  #error "SD_DETECT_INVERTED must be disabled for the FYSETC_F6_13 board."
+#if ENABLED(SD_DETECT_INVERTED)
+  //#error "SD_DETECT_INVERTED must be disabled for the FYSETC_F6_13 board."
 #endif
 
 #define BOARD_NAME "FYSETC F6 1.3"
@@ -184,25 +184,46 @@
 #define BEEPER_PIN         37
 #define SD_DETECT_PIN      49
 
-#if ENABLED(MKS_MINI_12864)
-  #define DOGLCD_A0        27
-  #define DOGLCD_CS        25
-#endif
-
 #if ENABLED(FYSETC_MINI_12864)
   //
   // See https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
   //
   #define DOGLCD_A0        16
   #define DOGLCD_CS        17
-  #ifndef RGB_LED_R_PIN
-    #define RGB_LED_R_PIN  25
+
+  #define LCD_BACKLIGHT_PIN -1
+  #define KILL_PIN         41
+
+  #define LCD_RESET_PIN    23   // Must be high or open for LCD to operate normally.
+                                // Seems to work best if left open.
+
+  #define FYSETC_MINI_12864_REV_1_2
+  //#define FYSETC_MINI_12864_REV_2_0
+  //#define FYSETC_MINI_12864_REV_2_1
+  #if EITHER(FYSETC_MINI_12864_REV_1_2, FYSETC_MINI_12864_REV_2_0)
+    #ifndef RGB_LED_R_PIN
+      #define RGB_LED_R_PIN 25
+    #endif
+    #ifndef RGB_LED_G_PIN
+      #define RGB_LED_G_PIN 27
+    #endif
+    #ifndef RGB_LED_B_PIN
+      #define RGB_LED_B_PIN 29
+    #endif
+  #elif defined(FYSETC_MINI_12864_REV_2_1)
+    #define NEOPIXEL_LED
+    #define NEOPIXEL_TYPE   NEO_GRB  // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
+    #define NEOPIXEL_PIN    25       // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
+    #define NEOPIXEL_PIXELS  3       // Number of LEDs in the strip
+    #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
+    #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
+    #define NEOPIXEL_STARTUP_TEST    // Cycle through colors at startup
+  #else
+    #error "Either FYSETC_MINI_12864_REV_1_2, FYSETC_MINI_12864_REV_2_0 or FYSETC_MINI_12864_REV_2_1 must be defined"
   #endif
-  #ifndef RGB_LED_G_PIN
-    #define RGB_LED_G_PIN  27
-  #endif
-  #ifndef RGB_LED_B_PIN
-    #define RGB_LED_B_PIN  29
+
+  #if !defined(LED_USER_PRESET_STARTUP) && EITHER(FYSETC_MINI_12864_REV_2_0, FYSETC_MINI_12864_REV_2_1)
+    #error "LED_USER_PRESET_STARTUP must be enabled when using FYSETC_MINI_12864 REV 2.0 and later"
   #endif
 
 #elif HAS_GRAPHICAL_LCD
@@ -214,6 +235,11 @@
   #define LCD_PINS_D6      27
   #define LCD_PINS_D7      29
 
+  #if ENABLED(MKS_MINI_12864)
+    #define DOGLCD_CS      25
+    #define DOGLCD_A0      27
+  #endif
+
 #endif
 
 #if ENABLED(NEWPANEL)
@@ -222,20 +248,6 @@
   #define BTN_ENC          35
 #endif
 
-#if ENABLED(FYSETC_MINI_12864)
-  #define LCD_BACKLIGHT_PIN -1
-  #define LCD_RESET_PIN    23
-  #define KILL_PIN         41
-  #ifndef RGB_LED_R_PIN
-    #define RGB_LED_R_PIN  25
-  #endif
-  #ifndef RGB_LED_G_PIN
-    #define RGB_LED_G_PIN  27
-  #endif
-  #ifndef RGB_LED_B_PIN
-    #define RGB_LED_B_PIN  29
-  #endif
-#endif
 #ifndef RGB_LED_R_PIN
   #define RGB_LED_R_PIN     3
 #endif
diff --git a/Marlin/src/pins/pins_GEN7_13.h b/Marlin/src/pins/pins_GEN7_13.h
index 60c62bdc71..9b1f0d242e 100644
--- a/Marlin/src/pins/pins_GEN7_13.h
+++ b/Marlin/src/pins/pins_GEN7_13.h
@@ -24,7 +24,7 @@
  * Gen7 v1.3 pin assignments
  */
 
- /**
+/**
  * Rev B    26 DEC 2016
  *
  * added pointer to a current Arduino IDE extension
diff --git a/Marlin/src/pins/pins_RAMPS.h b/Marlin/src/pins/pins_RAMPS.h
index 40d3dd11e2..120748eeb3 100644
--- a/Marlin/src/pins/pins_RAMPS.h
+++ b/Marlin/src/pins/pins_RAMPS.h
@@ -436,7 +436,9 @@
       #endif
 
       #define BTN_ENC           35
-      #define SD_DETECT_PIN     49
+      #ifndef SD_DETECT_PIN
+        #define SD_DETECT_PIN   49
+      #endif
       #define KILL_PIN          41
 
       #if ENABLED(BQ_LCD_SMART_CONTROLLER)
@@ -526,7 +528,6 @@
 
       // From https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
       #define BEEPER_PIN        37
-      #define LCD_RESET_PIN     23
 
       #define DOGLCD_A0         16
       #define DOGLCD_CS         17
@@ -537,14 +538,36 @@
 
       #define SD_DETECT_PIN     49
 
-      #ifndef RGB_LED_R_PIN
-        #define RGB_LED_R_PIN   25
+      #define LCD_RESET_PIN     23   // Must be high or open for LCD to operate normally.
+                                     // Seems to work best if left open.
+
+      #define FYSETC_MINI_12864_REV_1_2
+      //#define FYSETC_MINI_12864_REV_2_0
+      //#define FYSETC_MINI_12864_REV_2_1
+      #if EITHER(FYSETC_MINI_12864_REV_1_2, FYSETC_MINI_12864_REV_2_0)
+        #ifndef RGB_LED_R_PIN
+          #define RGB_LED_R_PIN 25
+        #endif
+        #ifndef RGB_LED_G_PIN
+          #define RGB_LED_G_PIN 27
+        #endif
+        #ifndef RGB_LED_B_PIN
+          #define RGB_LED_B_PIN 29
+        #endif
+      #elif defined(FYSETC_MINI_12864_REV_2_1)
+        #define NEOPIXEL_LED
+        #define NEOPIXEL_TYPE   NEO_GRB  // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
+        #define NEOPIXEL_PIN    25       // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
+        #define NEOPIXEL_PIXELS  3       // Number of LEDs in the strip
+        #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
+        #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
+        #define NEOPIXEL_STARTUP_TEST    // Cycle through colors at startup
+      #else
+        #error "Either FYSETC_MINI_12864_REV_1_2, FYSETC_MINI_12864_REV_2_0 or FYSETC_MINI_12864_REV_2_1 must be defined"
       #endif
-      #ifndef RGB_LED_G_PIN
-        #define RGB_LED_G_PIN   27
-      #endif
-      #ifndef RGB_LED_B_PIN
-        #define RGB_LED_B_PIN   29
+
+      #if !defined(LED_USER_PRESET_STARTUP) && EITHER(FYSETC_MINI_12864_REV_2_0, FYSETC_MINI_12864_REV_2_1)
+        #error "LED_USER_PRESET_STARTUP must be enabled when using FYSETC_MINI_12864 REV 2.0 and later"
       #endif
 
     #elif ENABLED(MINIPANEL)
diff --git a/Marlin/src/pins/pins_RAMPS_FD_V1.h b/Marlin/src/pins/pins_RAMPS_FD_V1.h
index a8bec209ef..78e75d9116 100644
--- a/Marlin/src/pins/pins_RAMPS_FD_V1.h
+++ b/Marlin/src/pins/pins_RAMPS_FD_V1.h
@@ -150,32 +150,71 @@
   #if ENABLED(NEWPANEL)
     #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
-    #define LCD_PINS_D7    29
   #endif
 
   #if ENABLED(FYSETC_MINI_12864)
     #define DOGLCD_CS      LCD_PINS_ENABLE
     #define DOGLCD_A0      LCD_PINS_RS
-  #elif ENABLED(MINIPANEL)
-    #define DOGLCD_CS      25
-    #define DOGLCD_A0      27
+
+    //#define FORCE_SOFT_SPI    // Use this if default of hardware SPI causes problems
+
+    #define LCD_RESET_PIN  23   // Must be high or open for LCD to operate normally.
+                                // Seems to work best if left open.
+
+    #define FYSETC_MINI_12864_REV_1_2
+    //#define FYSETC_MINI_12864_REV_2_0
+    //#define FYSETC_MINI_12864_REV_2_1
+    #if EITHER(FYSETC_MINI_12864_REV_1_2, FYSETC_MINI_12864_REV_2_0)
+      #ifndef RGB_LED_R_PIN
+        #define RGB_LED_R_PIN 25
+      #endif
+      #ifndef RGB_LED_G_PIN
+        #define RGB_LED_G_PIN 27
+      #endif
+      #ifndef RGB_LED_B_PIN
+        #define RGB_LED_B_PIN 29
+      #endif
+    #elif defined(FYSETC_MINI_12864_REV_2_1)
+      #define NEOPIXEL_LED
+      #define NEOPIXEL_TYPE NEO_GRB    // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
+      #define NEOPIXEL_PIN    25       // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
+      #define NEOPIXEL_PIXELS  3       // Number of LEDs in the strip
+      #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
+      #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
+      #define NEOPIXEL_STARTUP_TEST    // Cycle through colors at startup
+    #else
+      #error "Either FYSETC_MINI_12864_REV_1_2, FYSETC_MINI_12864_REV_2_0 or FYSETC_MINI_12864_REV_2_1 must be defined"
+    #endif
+
+    #if !defined(LED_USER_PRESET_STARTUP) && EITHER(FYSETC_MINI_12864_REV_2_0, FYSETC_MINI_12864_REV_2_1)
+      #error "LED_USER_PRESET_STARTUP must be enabled when using FYSETC_MINI_12864 REV 2.0 and later"
+    #endif
+
+  #elif ENABLED(NEWPANEL)
+
+    #define LCD_PINS_D4    23
+    #define LCD_PINS_D5    25
+    #define LCD_PINS_D6    27
+    #define LCD_PINS_D7    29
+
+    #if ENABLED(MINIPANEL)
+      #define DOGLCD_CS    25
+      #define DOGLCD_A0    27
+    #endif
+
   #endif
 
   #if ANY(VIKI2, miniVIKI)
-    #define DOGLCD_A0           16
-    #define KILL_PIN            51
-    #define STAT_LED_BLUE_PIN   29
-    #define STAT_LED_RED_PIN    23
-    #define DOGLCD_CS           17
-    #define DOGLCD_SCK          76   // SCK_PIN   - These are required for DUE Hardware SPI
-    #define DOGLCD_MOSI         75   // MOSI_PIN
-    #define DOGLCD_MISO         74   // MISO_PIN
+    #define DOGLCD_A0      16
+    #define KILL_PIN       51
+    #define STAT_LED_BLUE_PIN 29
+    #define STAT_LED_RED_PIN 23
+    #define DOGLCD_CS      17
+    #define DOGLCD_SCK     76   // SCK_PIN   - Required for DUE Hardware SPI
+    #define DOGLCD_MOSI    75   // MOSI_PIN
+    #define DOGLCD_MISO    74   // MISO_PIN
   #endif
 
-
 #endif // ULTRA_LCD
 
 #if HAS_DRIVER(TMC2208)
@@ -201,10 +240,8 @@
 //
 // M3/M4/M5 - Spindle/Laser Control
 //
-#if ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENA)
-  #if HOTENDS < 3
-    #define SPINDLE_LASER_ENA_PIN     45   // Use E2 ENA
-    #define SPINDLE_LASER_PWM_PIN     12   // MUST BE HARDWARE PWM
-    #define SPINDLE_DIR_PIN           47   // Use E2 DIR
-  #endif
+#if HOTENDS < 3 && ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENA)
+  #define SPINDLE_LASER_ENA_PIN 45   // Use E2 ENA
+  #define SPINDLE_LASER_PWM_PIN 12   // MUST BE HARDWARE PWM
+  #define SPINDLE_DIR_PIN       47   // Use E2 DIR
 #endif
diff --git a/Marlin/src/pins/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/pins_RAMPS_RE_ARM.h
index 9c7bbf4eea..5871b80d15 100644
--- a/Marlin/src/pins/pins_RAMPS_RE_ARM.h
+++ b/Marlin/src/pins/pins_RAMPS_RE_ARM.h
@@ -320,6 +320,7 @@
       #define DOGLCD_MOSI  P0_18
       #define DOGLCD_CS    P1_09  // use Ethernet connector for EXP1 cable signals
       #define DOGLCD_A0    P1_14
+      #define FORCE_SOFT_SPI      // required on a Re-ARM system
     #else
       #define DOGLCD_CS    P0_26   // (63) J5-3 & AUX-2
       #define DOGLCD_A0    P2_06   // (59) J3-8 & AUX-2
diff --git a/Marlin/src/pins/pins_RURAMPS4D_11.h b/Marlin/src/pins/pins_RURAMPS4D_11.h
index 517be5b9b5..718e44651e 100644
--- a/Marlin/src/pins/pins_RURAMPS4D_11.h
+++ b/Marlin/src/pins/pins_RURAMPS4D_11.h
@@ -202,31 +202,24 @@
 //
 #if ENABLED(ULTRA_LCD)
 
-  #if EITHER(RADDS_DISPLAY, REPRAP_DISCOUNT_SMART_CONTROLLER)
-
+  #if ANY(RADDS_DISPLAY, REPRAP_DISCOUNT_SMART_CONTROLLER, REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
     #define BEEPER_PIN      62
+    #define LCD_PINS_D4     48
+    #define LCD_PINS_D5     50
+    #define LCD_PINS_D6     52
+    #define LCD_PINS_D7     53
+    #define SD_DETECT_PIN   51
+  #endif
+
+  #if EITHER(RADDS_DISPLAY, REPRAP_DISCOUNT_SMART_CONTROLLER)
 
     #define LCD_PINS_RS     63
     #define LCD_PINS_ENABLE 64
-    #define LCD_PINS_D4     48
-    #define LCD_PINS_D5     50
-    #define LCD_PINS_D6     52
-    #define LCD_PINS_D7     53
-
-    #define SD_DETECT_PIN   51
 
   #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
 
-    #define BEEPER_PIN      62
-
     #define LCD_PINS_RS     52
     #define LCD_PINS_ENABLE 53
-    #define LCD_PINS_D4     48
-    #define LCD_PINS_D5     50
-    #define LCD_PINS_D6     52
-    #define LCD_PINS_D7     53
-
-    #define SD_DETECT_PIN   51
 
   #elif HAS_SSD1306_OLED_I2C
 
@@ -234,16 +227,57 @@
     #define LCD_SDSS        10
     #define SD_DETECT_PIN   51
 
+  #elif ENABLED(FYSETC_MINI_12864)
+
+    #define BEEPER_PIN      62
+    #define DOGLCD_CS       64
+    #define DOGLCD_A0       63
+
+    //#define FORCE_SOFT_SPI     // Use this if default of hardware SPI causes problems
+
+    #define LCD_RESET_PIN   48   // Must be high or open for LCD to operate normally.
+                                 // Seems to work best if left open.
+
+    #define FYSETC_MINI_12864_REV_1_2
+    //#define FYSETC_MINI_12864_REV_2_0
+    //#define FYSETC_MINI_12864_REV_2_1
+    #if EITHER(FYSETC_MINI_12864_REV_1_2, FYSETC_MINI_12864_REV_2_0)
+      #define RGB_LED
+      #ifndef RGB_LED_R_PIN
+        #define RGB_LED_R_PIN 50   // D5
+      #endif
+      #ifndef RGB_LED_G_PIN
+        #define RGB_LED_G_PIN 52   // D6
+      #endif
+      #ifndef RGB_LED_B_PIN
+        #define RGB_LED_B_PIN 53   // D7
+      #endif
+    #elif defined(FYSETC_MINI_12864_REV_2_1)
+      #define NEOPIXEL_LED
+      #define NEOPIXEL_TYPE   NEO_GRB  // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
+      #define NEOPIXEL_PIN  50         // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
+      #define NEOPIXEL_PIXELS  3       // Number of LEDs in the strip
+      #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
+      #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
+      #define NEOPIXEL_STARTUP_TEST    // Cycle through colors at startup
+    #else
+      #error "Either FYSETC_MINI_12864_REV_1_2, FYSETC_MINI_12864_REV_2_0 or FYSETC_MINI_12864_REV_2_1 must be defined"
+    #endif
+
+    #if !defined(LED_USER_PRESET_STARTUP) && EITHER(FYSETC_MINI_12864_REV_2_0, FYSETC_MINI_12864_REV_2_1)
+      #error "LED_USER_PRESET_STARTUP must be enabled when using FYSETC_MINI_12864 REV 2.0 and later"
+    #endif
+
   #elif ENABLED(SPARK_FULL_GRAPHICS)
 
     //http://doku.radds.org/dokumentation/other-electronics/sparklcd/
     #error "Oops! SPARK_FULL_GRAPHICS not supported with RURAMPS4D."
-    //#define LCD_PINS_D4     29//?
-    //#define LCD_PINS_ENABLE 27//?
-    //#define LCD_PINS_RS     25//?
-    //#define BTN_EN1         35//?
-    //#define BTN_EN2         33//?
-    //#define BTN_ENC         37//?
+    //#define LCD_PINS_D4     29   //?
+    //#define LCD_PINS_ENABLE 27   //?
+    //#define LCD_PINS_RS     25   //?
+    //#define BTN_EN1         35   //?
+    //#define BTN_EN2         33   //?
+    //#define BTN_ENC         37   //?
 
   #endif // SPARK_FULL_GRAPHICS
 
diff --git a/Marlin/src/pins/pins_RURAMPS4D_13.h b/Marlin/src/pins/pins_RURAMPS4D_13.h
index ab4aea0f2b..ddae87c245 100644
--- a/Marlin/src/pins/pins_RURAMPS4D_13.h
+++ b/Marlin/src/pins/pins_RURAMPS4D_13.h
@@ -188,31 +188,24 @@
 //
 #if ENABLED(ULTRA_LCD)
 
-  #if EITHER(RADDS_DISPLAY, REPRAP_DISCOUNT_SMART_CONTROLLER)
-
+  #if ANY(RADDS_DISPLAY, REPRAP_DISCOUNT_SMART_CONTROLLER, REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
     #define BEEPER_PIN      62
+    #define LCD_PINS_D4     48
+    #define LCD_PINS_D5     50
+    #define LCD_PINS_D6     52
+    #define LCD_PINS_D7     53
+    #define SD_DETECT_PIN   51
+  #endif
+
+  #if EITHER(RADDS_DISPLAY, REPRAP_DISCOUNT_SMART_CONTROLLER)
 
     #define LCD_PINS_RS     63
     #define LCD_PINS_ENABLE 64
-    #define LCD_PINS_D4     48
-    #define LCD_PINS_D5     50
-    #define LCD_PINS_D6     52
-    #define LCD_PINS_D7     53
-
-    #define SD_DETECT_PIN   51
 
   #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
 
-    #define BEEPER_PIN      62
-
     #define LCD_PINS_RS     52
     #define LCD_PINS_ENABLE 53
-    #define LCD_PINS_D4     48
-    #define LCD_PINS_D5     50
-    #define LCD_PINS_D6     52
-    #define LCD_PINS_D7     53
-
-    #define SD_DETECT_PIN   51
 
   #elif HAS_SSD1306_OLED_I2C
 
@@ -220,6 +213,47 @@
     #define LCD_SDSS        10
     #define SD_DETECT_PIN   51
 
+  #elif ENABLED(FYSETC_MINI_12864)
+
+    #define BEEPER_PIN      62
+    #define DOGLCD_CS       64
+    #define DOGLCD_A0       63
+
+    //#define FORCE_SOFT_SPI     // Use this if default of hardware SPI causes problems
+
+    #define LCD_RESET_PIN   48   // Must be high or open for LCD to operate normally.
+                                 // Seems to work best if left open.
+
+    #define FYSETC_MINI_12864_REV_1_2
+    //#define FYSETC_MINI_12864_REV_2_0
+    //#define FYSETC_MINI_12864_REV_2_1
+    #if EITHER(FYSETC_MINI_12864_REV_1_2, FYSETC_MINI_12864_REV_2_0)
+      #define RGB_LED
+      #ifndef RGB_LED_R_PIN
+        #define RGB_LED_R_PIN 50   // D5
+      #endif
+      #ifndef RGB_LED_G_PIN
+        #define RGB_LED_G_PIN 52   // D6
+      #endif
+      #ifndef RGB_LED_B_PIN
+        #define RGB_LED_B_PIN 53   // D7
+      #endif
+    #elif defined(FYSETC_MINI_12864_REV_2_1)
+      #define NEOPIXEL_LED
+      #define NEOPIXEL_TYPE   NEO_GRB  // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
+      #define NEOPIXEL_PIN  50         // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
+      #define NEOPIXEL_PIXELS  3       // Number of LEDs in the strip
+      #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
+      #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
+      #define NEOPIXEL_STARTUP_TEST    // Cycle through colors at startup
+    #else
+      #error "Either FYSETC_MINI_12864_REV_1_2, FYSETC_MINI_12864_REV_2_0 or FYSETC_MINI_12864_REV_2_1 must be defined"
+    #endif
+
+    #if !defined(LED_USER_PRESET_STARTUP) && EITHER(FYSETC_MINI_12864_REV_2_0, FYSETC_MINI_12864_REV_2_1)
+      #error "LED_USER_PRESET_STARTUP must be enabled when using FYSETC_MINI_12864 REV 2.0 and later"
+    #endif
+
   #elif ENABLED(MKS_MINI_12864)
 
     #define ORIG_BEEPER_PIN 62
diff --git a/README.md b/README.md
index 115d3d10c2..414efa5e89 100644
--- a/README.md
+++ b/README.md
@@ -1,7 +1,9 @@
 # Marlin 3D Printer Firmware
 
-[![Build Status](https://travis-ci.org/MarlinFirmware/Marlin.svg?branch=RCBugFix)](https://travis-ci.org/MarlinFirmware/Marlin)
-[![Coverity Scan Build Status](https://scan.coverity.com/projects/2224/badge.svg)](https://scan.coverity.com/projects/2224)
+[![Build Status](https://travis-ci.org/MarlinFirmware/Marlin.svg?branch=bugfix-2.0.x)](https://travis-ci.org/MarlinFirmware/Marlin)
+![GitHub](https://img.shields.io/github/license/marlinfirmware/marlin.svg)
+![GitHub contributors](https://img.shields.io/github/contributors/marlinfirmware/marlin.svg)
+![GitHub Release Date](https://img.shields.io/github/release-date/marlinfirmware/marlin.svg)
 
 <img align="top" width=175 src="buildroot/share/pixmaps/logo/marlin-250.png" />
 
@@ -65,7 +67,7 @@ The current Marlin dev team consists of:
  - Roxanne Neufeld [[@Roxy-3D](https://github.com/Roxy-3D)] - USA
  - Bob Kuhn [[@Bob-the-Kuhn](https://github.com/Bob-the-Kuhn)] - USA
  - Chris Pepper [[@p3p](https://github.com/p3p)] - UK
- - João Brazio [[@jbrazio](https://github.com/jbrazio)] - Brazil
+ - João Brazio [[@jbrazio](https://github.com/jbrazio)] - Portugal
  - Erik van der Zalm [[@ErikZalm](https://github.com/ErikZalm)] - Netherlands &nbsp; [![Flattr Erik](http://api.flattr.com/button/flattr-badge-large.png)](https://flattr.com/submit/auto?user_id=ErikZalm&url=https://github.com/MarlinFirmware/Marlin&title=Marlin&language=&tags=github&category=software)
 
 ## License
diff --git a/config/default/Configuration.h b/config/default/Configuration.h
index 7ea040803c..6b24012db1 100644
--- a/config/default/Configuration.h
+++ b/config/default/Configuration.h
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/3DFabXYZ/Migbot/Configuration.h b/config/examples/3DFabXYZ/Migbot/Configuration.h
index 7b459d3c33..a236c65cfa 100644
--- a/config/examples/3DFabXYZ/Migbot/Configuration.h
+++ b/config/examples/3DFabXYZ/Migbot/Configuration.h
@@ -2044,6 +2044,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/AlephObjects/TAZ4/Configuration.h b/config/examples/AlephObjects/TAZ4/Configuration.h
index 60c94e8e02..23a18ca030 100644
--- a/config/examples/AlephObjects/TAZ4/Configuration.h
+++ b/config/examples/AlephObjects/TAZ4/Configuration.h
@@ -2033,6 +2033,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/AliExpress/CL-260/Configuration.h b/config/examples/AliExpress/CL-260/Configuration.h
index 1be8dde594..86a9d1bf6a 100644
--- a/config/examples/AliExpress/CL-260/Configuration.h
+++ b/config/examples/AliExpress/CL-260/Configuration.h
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/AliExpress/UM2pExt/Configuration.h b/config/examples/AliExpress/UM2pExt/Configuration.h
index f9de2247b8..19920c0161 100644
--- a/config/examples/AliExpress/UM2pExt/Configuration.h
+++ b/config/examples/AliExpress/UM2pExt/Configuration.h
@@ -2024,6 +2024,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Anet/A2/Configuration.h b/config/examples/Anet/A2/Configuration.h
index db89142199..fed0e75f09 100644
--- a/config/examples/Anet/A2/Configuration.h
+++ b/config/examples/Anet/A2/Configuration.h
@@ -2015,6 +2015,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Anet/A2plus/Configuration.h b/config/examples/Anet/A2plus/Configuration.h
index 68190a9ef9..23f1cf5f36 100644
--- a/config/examples/Anet/A2plus/Configuration.h
+++ b/config/examples/Anet/A2plus/Configuration.h
@@ -2015,6 +2015,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Anet/A6/Configuration.h b/config/examples/Anet/A6/Configuration.h
index e0b5c1a282..b33abd387f 100644
--- a/config/examples/Anet/A6/Configuration.h
+++ b/config/examples/Anet/A6/Configuration.h
@@ -2167,6 +2167,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Anet/A8/Configuration.h b/config/examples/Anet/A8/Configuration.h
index fee9dad53d..430e175824 100644
--- a/config/examples/Anet/A8/Configuration.h
+++ b/config/examples/Anet/A8/Configuration.h
@@ -2028,6 +2028,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/AnyCubic/i3/Configuration.h b/config/examples/AnyCubic/i3/Configuration.h
index af01e1cf45..540956d7fa 100644
--- a/config/examples/AnyCubic/i3/Configuration.h
+++ b/config/examples/AnyCubic/i3/Configuration.h
@@ -2023,6 +2023,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/ArmEd/Configuration.h b/config/examples/ArmEd/Configuration.h
index 31a10f05c2..7d23ad27ee 100644
--- a/config/examples/ArmEd/Configuration.h
+++ b/config/examples/ArmEd/Configuration.h
@@ -2014,6 +2014,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Azteeg/X5GT/Configuration.h b/config/examples/Azteeg/X5GT/Configuration.h
index 1d22e52b70..959ec9c669 100644
--- a/config/examples/Azteeg/X5GT/Configuration.h
+++ b/config/examples/Azteeg/X5GT/Configuration.h
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/BIBO/TouchX/cyclops/Configuration.h b/config/examples/BIBO/TouchX/cyclops/Configuration.h
index 7cbe3edd9d..b8c873de36 100644
--- a/config/examples/BIBO/TouchX/cyclops/Configuration.h
+++ b/config/examples/BIBO/TouchX/cyclops/Configuration.h
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/BIBO/TouchX/default/Configuration.h b/config/examples/BIBO/TouchX/default/Configuration.h
index 5ff9eb893b..847a0dbc43 100644
--- a/config/examples/BIBO/TouchX/default/Configuration.h
+++ b/config/examples/BIBO/TouchX/default/Configuration.h
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/BQ/Hephestos/Configuration.h b/config/examples/BQ/Hephestos/Configuration.h
index 91d315373e..a98e73d97a 100644
--- a/config/examples/BQ/Hephestos/Configuration.h
+++ b/config/examples/BQ/Hephestos/Configuration.h
@@ -2001,6 +2001,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/BQ/Hephestos_2/Configuration.h b/config/examples/BQ/Hephestos_2/Configuration.h
index 64c950f285..474110f36f 100644
--- a/config/examples/BQ/Hephestos_2/Configuration.h
+++ b/config/examples/BQ/Hephestos_2/Configuration.h
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/BQ/WITBOX/Configuration.h b/config/examples/BQ/WITBOX/Configuration.h
index ef5a1ddb84..3b1eafc686 100644
--- a/config/examples/BQ/WITBOX/Configuration.h
+++ b/config/examples/BQ/WITBOX/Configuration.h
@@ -2001,6 +2001,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Cartesio/Configuration.h b/config/examples/Cartesio/Configuration.h
index 09b003c572..06586f2e0d 100644
--- a/config/examples/Cartesio/Configuration.h
+++ b/config/examples/Cartesio/Configuration.h
@@ -2012,6 +2012,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Creality/CR-10/Configuration.h b/config/examples/Creality/CR-10/Configuration.h
index 0e0c476888..93f1daf401 100644
--- a/config/examples/Creality/CR-10/Configuration.h
+++ b/config/examples/Creality/CR-10/Configuration.h
@@ -2023,6 +2023,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Creality/CR-10S/Configuration.h b/config/examples/Creality/CR-10S/Configuration.h
index bbb5c4114b..a2c0418d01 100644
--- a/config/examples/Creality/CR-10S/Configuration.h
+++ b/config/examples/Creality/CR-10S/Configuration.h
@@ -2014,6 +2014,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Creality/CR-10_5S/Configuration.h b/config/examples/Creality/CR-10_5S/Configuration.h
index a8222e3b33..bb8872c622 100644
--- a/config/examples/Creality/CR-10_5S/Configuration.h
+++ b/config/examples/Creality/CR-10_5S/Configuration.h
@@ -2016,6 +2016,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Creality/CR-10mini/Configuration.h b/config/examples/Creality/CR-10mini/Configuration.h
index 1c6b3d0b8b..2639fc587b 100644
--- a/config/examples/Creality/CR-10mini/Configuration.h
+++ b/config/examples/Creality/CR-10mini/Configuration.h
@@ -2032,6 +2032,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Creality/CR-8/Configuration.h b/config/examples/Creality/CR-8/Configuration.h
index eb2c0bf4d0..9fb629a362 100644
--- a/config/examples/Creality/CR-8/Configuration.h
+++ b/config/examples/Creality/CR-8/Configuration.h
@@ -2023,6 +2023,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Creality/Ender-2/Configuration.h b/config/examples/Creality/Ender-2/Configuration.h
index bd22dd9007..1d093d064c 100644
--- a/config/examples/Creality/Ender-2/Configuration.h
+++ b/config/examples/Creality/Ender-2/Configuration.h
@@ -2017,6 +2017,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Creality/Ender-3/Configuration.h b/config/examples/Creality/Ender-3/Configuration.h
index 377e344e82..195440f59e 100644
--- a/config/examples/Creality/Ender-3/Configuration.h
+++ b/config/examples/Creality/Ender-3/Configuration.h
@@ -2017,6 +2017,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Creality/Ender-4/Configuration.h b/config/examples/Creality/Ender-4/Configuration.h
index 608e6dccfd..e6d585d7a2 100644
--- a/config/examples/Creality/Ender-4/Configuration.h
+++ b/config/examples/Creality/Ender-4/Configuration.h
@@ -2023,6 +2023,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Einstart-S/Configuration.h b/config/examples/Einstart-S/Configuration.h
index 45f0ef3f41..246bd987b7 100644
--- a/config/examples/Einstart-S/Configuration.h
+++ b/config/examples/Einstart-S/Configuration.h
@@ -2019,6 +2019,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Felix/Configuration.h b/config/examples/Felix/Configuration.h
index f02a9e2203..1183a2e898 100644
--- a/config/examples/Felix/Configuration.h
+++ b/config/examples/Felix/Configuration.h
@@ -1995,6 +1995,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Felix/DUAL/Configuration.h b/config/examples/Felix/DUAL/Configuration.h
index 530c1e9797..ec3992e801 100644
--- a/config/examples/Felix/DUAL/Configuration.h
+++ b/config/examples/Felix/DUAL/Configuration.h
@@ -1995,6 +1995,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/FlashForge/CreatorPro/Configuration.h b/config/examples/FlashForge/CreatorPro/Configuration.h
index 8978fb3baa..410c3052b4 100644
--- a/config/examples/FlashForge/CreatorPro/Configuration.h
+++ b/config/examples/FlashForge/CreatorPro/Configuration.h
@@ -2004,6 +2004,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/FolgerTech/i3-2020/Configuration.h b/config/examples/FolgerTech/i3-2020/Configuration.h
index f2b962411a..5f8a8717ad 100644
--- a/config/examples/FolgerTech/i3-2020/Configuration.h
+++ b/config/examples/FolgerTech/i3-2020/Configuration.h
@@ -2019,6 +2019,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Formbot/Raptor/Configuration.h b/config/examples/Formbot/Raptor/Configuration.h
index 116014d3c1..dcff640026 100644
--- a/config/examples/Formbot/Raptor/Configuration.h
+++ b/config/examples/Formbot/Raptor/Configuration.h
@@ -2118,6 +2118,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Formbot/T_Rex_2+/Configuration.h b/config/examples/Formbot/T_Rex_2+/Configuration.h
index 82d24eb43f..3432036702 100644
--- a/config/examples/Formbot/T_Rex_2+/Configuration.h
+++ b/config/examples/Formbot/T_Rex_2+/Configuration.h
@@ -2048,6 +2048,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
@@ -2159,3 +2160,9 @@
 
 // Allow servo angle to be edited and saved to EEPROM
 //#define EDITABLE_SERVO_ANGLES
+
+#ifdef ROXYs_TRex
+  #define LED_PIN     -1
+  #define BEEPER_PIN  -1
+  #define KILL_PIN    -1
+#endif
diff --git a/config/examples/Formbot/T_Rex_3/Configuration.h b/config/examples/Formbot/T_Rex_3/Configuration.h
index 992d2c0e17..9c133527a8 100644
--- a/config/examples/Formbot/T_Rex_3/Configuration.h
+++ b/config/examples/Formbot/T_Rex_3/Configuration.h
@@ -2041,6 +2041,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
@@ -2152,3 +2153,9 @@
 
 // Allow servo angle to be edited and saved to EEPROM
 //#define EDITABLE_SERVO_ANGLES
+
+#ifdef ROXYs_TRex
+  #define LED_PIN     -1
+  #define BEEPER_PIN  -1
+  #define KILL_PIN    -1
+#endif
diff --git a/config/examples/Geeetech/A10M/Configuration.h b/config/examples/Geeetech/A10M/Configuration.h
index 0aa45ee20a..462f7f9dee 100644
--- a/config/examples/Geeetech/A10M/Configuration.h
+++ b/config/examples/Geeetech/A10M/Configuration.h
@@ -1998,6 +1998,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Geeetech/A20M/Configuration.h b/config/examples/Geeetech/A20M/Configuration.h
index 6c7b93cff8..1f3b8b66b1 100644
--- a/config/examples/Geeetech/A20M/Configuration.h
+++ b/config/examples/Geeetech/A20M/Configuration.h
@@ -2002,6 +2002,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Geeetech/GT2560/Configuration.h b/config/examples/Geeetech/GT2560/Configuration.h
index bd7800bb7e..197e85680a 100644
--- a/config/examples/Geeetech/GT2560/Configuration.h
+++ b/config/examples/Geeetech/GT2560/Configuration.h
@@ -2028,6 +2028,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Geeetech/I3_Pro_X-GT2560/Configuration.h b/config/examples/Geeetech/I3_Pro_X-GT2560/Configuration.h
index 6605797f21..930e6dedcb 100644
--- a/config/examples/Geeetech/I3_Pro_X-GT2560/Configuration.h
+++ b/config/examples/Geeetech/I3_Pro_X-GT2560/Configuration.h
@@ -2002,6 +2002,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Geeetech/MeCreator2/Configuration.h b/config/examples/Geeetech/MeCreator2/Configuration.h
index d969f9803d..2ad7cb0931 100644
--- a/config/examples/Geeetech/MeCreator2/Configuration.h
+++ b/config/examples/Geeetech/MeCreator2/Configuration.h
@@ -2020,6 +2020,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Geeetech/Prusa i3 Pro B/bltouch/Configuration.h b/config/examples/Geeetech/Prusa i3 Pro B/bltouch/Configuration.h
index 604ec61f2b..babbbf0afc 100644
--- a/config/examples/Geeetech/Prusa i3 Pro B/bltouch/Configuration.h	
+++ b/config/examples/Geeetech/Prusa i3 Pro B/bltouch/Configuration.h	
@@ -2029,6 +2029,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Geeetech/Prusa i3 Pro B/noprobe/Configuration.h b/config/examples/Geeetech/Prusa i3 Pro B/noprobe/Configuration.h
index 03917da9a7..e65c48122f 100644
--- a/config/examples/Geeetech/Prusa i3 Pro B/noprobe/Configuration.h	
+++ b/config/examples/Geeetech/Prusa i3 Pro B/noprobe/Configuration.h	
@@ -2028,6 +2028,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Geeetech/Prusa i3 Pro C/Configuration.h b/config/examples/Geeetech/Prusa i3 Pro C/Configuration.h
index 666ce89889..7f2ae01d6d 100644
--- a/config/examples/Geeetech/Prusa i3 Pro C/Configuration.h	
+++ b/config/examples/Geeetech/Prusa i3 Pro C/Configuration.h	
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Geeetech/Prusa i3 Pro W/Configuration.h b/config/examples/Geeetech/Prusa i3 Pro W/Configuration.h
index 6edcc7494e..49b71294ab 100644
--- a/config/examples/Geeetech/Prusa i3 Pro W/Configuration.h	
+++ b/config/examples/Geeetech/Prusa i3 Pro W/Configuration.h	
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Infitary/i3-M508/Configuration.h b/config/examples/Infitary/i3-M508/Configuration.h
index f859c70128..7cc745496f 100644
--- a/config/examples/Infitary/i3-M508/Configuration.h
+++ b/config/examples/Infitary/i3-M508/Configuration.h
@@ -2017,6 +2017,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/JGAurora/A5/Configuration.h b/config/examples/JGAurora/A5/Configuration.h
index 4e2e0c7f30..5497ce8616 100644
--- a/config/examples/JGAurora/A5/Configuration.h
+++ b/config/examples/JGAurora/A5/Configuration.h
@@ -2025,6 +2025,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/MakerParts/Configuration.h b/config/examples/MakerParts/Configuration.h
index e06c956457..4048345289 100644
--- a/config/examples/MakerParts/Configuration.h
+++ b/config/examples/MakerParts/Configuration.h
@@ -2033,6 +2033,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Malyan/M150/Configuration.h b/config/examples/Malyan/M150/Configuration.h
index e382233f69..0efe5b988e 100644
--- a/config/examples/Malyan/M150/Configuration.h
+++ b/config/examples/Malyan/M150/Configuration.h
@@ -2041,6 +2041,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Malyan/M200/Configuration.h b/config/examples/Malyan/M200/Configuration.h
index c9051fb748..270dd7c6a5 100644
--- a/config/examples/Malyan/M200/Configuration.h
+++ b/config/examples/Malyan/M200/Configuration.h
@@ -2012,6 +2012,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Micromake/C1/basic/Configuration.h b/config/examples/Micromake/C1/basic/Configuration.h
index 24e930d20b..90e2b17c45 100644
--- a/config/examples/Micromake/C1/basic/Configuration.h
+++ b/config/examples/Micromake/C1/basic/Configuration.h
@@ -2017,6 +2017,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Micromake/C1/enhanced/Configuration.h b/config/examples/Micromake/C1/enhanced/Configuration.h
index 2b0413b90b..c399906143 100644
--- a/config/examples/Micromake/C1/enhanced/Configuration.h
+++ b/config/examples/Micromake/C1/enhanced/Configuration.h
@@ -2017,6 +2017,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Mks/Robin/Configuration.h b/config/examples/Mks/Robin/Configuration.h
index 97af15a496..ecfc05ead3 100644
--- a/config/examples/Mks/Robin/Configuration.h
+++ b/config/examples/Mks/Robin/Configuration.h
@@ -2015,6 +2015,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Mks/Sbase/Configuration.h b/config/examples/Mks/Sbase/Configuration.h
index 0bdf95a2c4..8883141cc6 100644
--- a/config/examples/Mks/Sbase/Configuration.h
+++ b/config/examples/Mks/Sbase/Configuration.h
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Printrbot/PrintrboardG2/Configuration.h b/config/examples/Printrbot/PrintrboardG2/Configuration.h
index e944085fc9..b0dfb4c4c9 100644
--- a/config/examples/Printrbot/PrintrboardG2/Configuration.h
+++ b/config/examples/Printrbot/PrintrboardG2/Configuration.h
@@ -2021,6 +2021,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/RapideLite/RL200/Configuration.h b/config/examples/RapideLite/RL200/Configuration.h
index d3c2f4cc94..ff20725785 100644
--- a/config/examples/RapideLite/RL200/Configuration.h
+++ b/config/examples/RapideLite/RL200/Configuration.h
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/RepRapPro/Huxley/Configuration.h b/config/examples/RepRapPro/Huxley/Configuration.h
index 749afb889a..d58be3ee4a 100644
--- a/config/examples/RepRapPro/Huxley/Configuration.h
+++ b/config/examples/RepRapPro/Huxley/Configuration.h
@@ -2062,6 +2062,7 @@ Black rubber belt(MXL), 18 - tooth aluminium pulley : 87.489 step per mm (Huxley
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/RepRapWorld/Megatronics/Configuration.h b/config/examples/RepRapWorld/Megatronics/Configuration.h
index 79fceac73a..82a30f4549 100644
--- a/config/examples/RepRapWorld/Megatronics/Configuration.h
+++ b/config/examples/RepRapWorld/Megatronics/Configuration.h
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/RigidBot/Configuration.h b/config/examples/RigidBot/Configuration.h
index 3fbd34e9c3..2add4143c6 100644
--- a/config/examples/RigidBot/Configuration.h
+++ b/config/examples/RigidBot/Configuration.h
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/SCARA/Configuration.h b/config/examples/SCARA/Configuration.h
index 86a0b9e88a..14c30d0362 100644
--- a/config/examples/SCARA/Configuration.h
+++ b/config/examples/SCARA/Configuration.h
@@ -2026,6 +2026,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/STM32/Black_STM32F407VET6/Configuration.h b/config/examples/STM32/Black_STM32F407VET6/Configuration.h
index f34dee19d3..978acbf91d 100644
--- a/config/examples/STM32/Black_STM32F407VET6/Configuration.h
+++ b/config/examples/STM32/Black_STM32F407VET6/Configuration.h
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/STM32/STM32F10/Configuration.h b/config/examples/STM32/STM32F10/Configuration.h
index 76cbc4575b..abe8d54c4b 100644
--- a/config/examples/STM32/STM32F10/Configuration.h
+++ b/config/examples/STM32/STM32F10/Configuration.h
@@ -2015,6 +2015,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/STM32/STM32F4/Configuration.h b/config/examples/STM32/STM32F4/Configuration.h
index 3c4a93c816..49b92aefd1 100644
--- a/config/examples/STM32/STM32F4/Configuration.h
+++ b/config/examples/STM32/STM32F4/Configuration.h
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/STM32/stm32f103ret6/Configuration.h b/config/examples/STM32/stm32f103ret6/Configuration.h
index 6ee6cbbcef..ba17e68c14 100644
--- a/config/examples/STM32/stm32f103ret6/Configuration.h
+++ b/config/examples/STM32/stm32f103ret6/Configuration.h
@@ -2015,6 +2015,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Sanguinololu/Configuration.h b/config/examples/Sanguinololu/Configuration.h
index 8b8e85259d..8fcfb0b6b4 100644
--- a/config/examples/Sanguinololu/Configuration.h
+++ b/config/examples/Sanguinololu/Configuration.h
@@ -2044,6 +2044,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/TheBorg/Configuration.h b/config/examples/TheBorg/Configuration.h
index 9fb8ed0298..dd6e1d845a 100644
--- a/config/examples/TheBorg/Configuration.h
+++ b/config/examples/TheBorg/Configuration.h
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/TinyBoy2/Configuration.h b/config/examples/TinyBoy2/Configuration.h
index 7f1935c531..cd89ad5a93 100644
--- a/config/examples/TinyBoy2/Configuration.h
+++ b/config/examples/TinyBoy2/Configuration.h
@@ -2069,6 +2069,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Tronxy/X1/Configuration.h b/config/examples/Tronxy/X1/Configuration.h
index 02af26a50f..b13a74ed42 100644
--- a/config/examples/Tronxy/X1/Configuration.h
+++ b/config/examples/Tronxy/X1/Configuration.h
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Tronxy/X3A/Configuration.h b/config/examples/Tronxy/X3A/Configuration.h
index 549b9a3ccd..9a58226861 100644
--- a/config/examples/Tronxy/X3A/Configuration.h
+++ b/config/examples/Tronxy/X3A/Configuration.h
@@ -2017,6 +2017,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Tronxy/X5S-2E/Configuration.h b/config/examples/Tronxy/X5S-2E/Configuration.h
index 0658378a25..a91d1a0f96 100644
--- a/config/examples/Tronxy/X5S-2E/Configuration.h
+++ b/config/examples/Tronxy/X5S-2E/Configuration.h
@@ -2034,6 +2034,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Tronxy/X5S/Configuration.h b/config/examples/Tronxy/X5S/Configuration.h
index 736f158d93..381b760d9f 100644
--- a/config/examples/Tronxy/X5S/Configuration.h
+++ b/config/examples/Tronxy/X5S/Configuration.h
@@ -2012,6 +2012,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Tronxy/XY100/Configuration.h b/config/examples/Tronxy/XY100/Configuration.h
index 0634641812..612942ead1 100644
--- a/config/examples/Tronxy/XY100/Configuration.h
+++ b/config/examples/Tronxy/XY100/Configuration.h
@@ -2024,6 +2024,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/UltiMachine/Archim1/Configuration.h b/config/examples/UltiMachine/Archim1/Configuration.h
index 06cd59ad41..e95be76d2d 100644
--- a/config/examples/UltiMachine/Archim1/Configuration.h
+++ b/config/examples/UltiMachine/Archim1/Configuration.h
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/UltiMachine/Archim2/Configuration.h b/config/examples/UltiMachine/Archim2/Configuration.h
index fd4fe1e07c..772f7e963a 100644
--- a/config/examples/UltiMachine/Archim2/Configuration.h
+++ b/config/examples/UltiMachine/Archim2/Configuration.h
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/VORONDesign/Configuration.h b/config/examples/VORONDesign/Configuration.h
index f043405d23..27be2081d8 100644
--- a/config/examples/VORONDesign/Configuration.h
+++ b/config/examples/VORONDesign/Configuration.h
@@ -2022,6 +2022,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Velleman/K8200/Configuration.h b/config/examples/Velleman/K8200/Configuration.h
index fb749e8433..2cf1d85c6b 100644
--- a/config/examples/Velleman/K8200/Configuration.h
+++ b/config/examples/Velleman/K8200/Configuration.h
@@ -2048,6 +2048,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Velleman/K8400/Configuration.h b/config/examples/Velleman/K8400/Configuration.h
index 24aeab6486..262dbfce16 100644
--- a/config/examples/Velleman/K8400/Configuration.h
+++ b/config/examples/Velleman/K8400/Configuration.h
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Velleman/K8400/Dual-head/Configuration.h b/config/examples/Velleman/K8400/Dual-head/Configuration.h
index 2438b75856..7cf031922a 100644
--- a/config/examples/Velleman/K8400/Dual-head/Configuration.h
+++ b/config/examples/Velleman/K8400/Dual-head/Configuration.h
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/WASP/PowerWASP/Configuration.h b/config/examples/WASP/PowerWASP/Configuration.h
index 5b234bf0a3..c6d9db2f57 100644
--- a/config/examples/WASP/PowerWASP/Configuration.h
+++ b/config/examples/WASP/PowerWASP/Configuration.h
@@ -2032,6 +2032,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/Wanhao/Duplicator 6/Configuration.h b/config/examples/Wanhao/Duplicator 6/Configuration.h
index 78d8d6bf1a..a52db9f8ad 100644
--- a/config/examples/Wanhao/Duplicator 6/Configuration.h	
+++ b/config/examples/Wanhao/Duplicator 6/Configuration.h	
@@ -2026,6 +2026,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/adafruit/ST7565/Configuration.h b/config/examples/adafruit/ST7565/Configuration.h
index 4ceeb498ba..f7d21c2013 100644
--- a/config/examples/adafruit/ST7565/Configuration.h
+++ b/config/examples/adafruit/ST7565/Configuration.h
@@ -2013,6 +2013,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/delta/Anycubic/Kossel/Configuration.h b/config/examples/delta/Anycubic/Kossel/Configuration.h
index f59af6179e..7a97646ae5 100644
--- a/config/examples/delta/Anycubic/Kossel/Configuration.h
+++ b/config/examples/delta/Anycubic/Kossel/Configuration.h
@@ -2200,6 +2200,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/delta/FLSUN/auto_calibrate/Configuration.h b/config/examples/delta/FLSUN/auto_calibrate/Configuration.h
index f83290a9eb..d1ba36e9a8 100644
--- a/config/examples/delta/FLSUN/auto_calibrate/Configuration.h
+++ b/config/examples/delta/FLSUN/auto_calibrate/Configuration.h
@@ -2141,6 +2141,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/delta/FLSUN/kossel/Configuration.h b/config/examples/delta/FLSUN/kossel/Configuration.h
index d95d6da056..3b01bfed59 100644
--- a/config/examples/delta/FLSUN/kossel/Configuration.h
+++ b/config/examples/delta/FLSUN/kossel/Configuration.h
@@ -2140,6 +2140,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/delta/FLSUN/kossel_mini/Configuration.h b/config/examples/delta/FLSUN/kossel_mini/Configuration.h
index 22154ab350..8be2d2e29e 100644
--- a/config/examples/delta/FLSUN/kossel_mini/Configuration.h
+++ b/config/examples/delta/FLSUN/kossel_mini/Configuration.h
@@ -2140,6 +2140,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/delta/Geeetech/Rostock 301/Configuration.h b/config/examples/delta/Geeetech/Rostock 301/Configuration.h
index 42d183a8e4..090409f534 100644
--- a/config/examples/delta/Geeetech/Rostock 301/Configuration.h	
+++ b/config/examples/delta/Geeetech/Rostock 301/Configuration.h	
@@ -2128,6 +2128,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/delta/Hatchbox_Alpha/Configuration.h b/config/examples/delta/Hatchbox_Alpha/Configuration.h
index fd9fc95c84..6f2292bb80 100644
--- a/config/examples/delta/Hatchbox_Alpha/Configuration.h
+++ b/config/examples/delta/Hatchbox_Alpha/Configuration.h
@@ -2143,6 +2143,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/delta/MKS/SBASE/Configuration.h b/config/examples/delta/MKS/SBASE/Configuration.h
index 94ddadc040..99696d4526 100644
--- a/config/examples/delta/MKS/SBASE/Configuration.h
+++ b/config/examples/delta/MKS/SBASE/Configuration.h
@@ -2128,6 +2128,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/delta/Tevo Little Monster/Configuration.h b/config/examples/delta/Tevo Little Monster/Configuration.h
index c27c9fd11b..6eb82bc85b 100644
--- a/config/examples/delta/Tevo Little Monster/Configuration.h	
+++ b/config/examples/delta/Tevo Little Monster/Configuration.h	
@@ -2121,6 +2121,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/delta/generic/Configuration.h b/config/examples/delta/generic/Configuration.h
index 685b30bc5a..36cea0c6f2 100644
--- a/config/examples/delta/generic/Configuration.h
+++ b/config/examples/delta/generic/Configuration.h
@@ -2128,6 +2128,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/delta/kossel_mini/Configuration.h b/config/examples/delta/kossel_mini/Configuration.h
index bd668c0745..94131fd952 100644
--- a/config/examples/delta/kossel_mini/Configuration.h
+++ b/config/examples/delta/kossel_mini/Configuration.h
@@ -2130,6 +2130,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/delta/kossel_pro/Configuration.h b/config/examples/delta/kossel_pro/Configuration.h
index 44cc6a30a3..5a12ddc97f 100644
--- a/config/examples/delta/kossel_pro/Configuration.h
+++ b/config/examples/delta/kossel_pro/Configuration.h
@@ -2131,6 +2131,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/delta/kossel_xl/Configuration.h b/config/examples/delta/kossel_xl/Configuration.h
index 1b18389b42..5a92c6a13a 100644
--- a/config/examples/delta/kossel_xl/Configuration.h
+++ b/config/examples/delta/kossel_xl/Configuration.h
@@ -2131,6 +2131,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/gCreate/gMax1.5+/Configuration.h b/config/examples/gCreate/gMax1.5+/Configuration.h
index 9c372a0ea0..95d5844778 100644
--- a/config/examples/gCreate/gMax1.5+/Configuration.h
+++ b/config/examples/gCreate/gMax1.5+/Configuration.h
@@ -2016,6 +2016,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/makibox/Configuration.h b/config/examples/makibox/Configuration.h
index 495190c9cf..791b3afcb9 100644
--- a/config/examples/makibox/Configuration.h
+++ b/config/examples/makibox/Configuration.h
@@ -2016,6 +2016,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/tvrrug/Round2/Configuration.h b/config/examples/tvrrug/Round2/Configuration.h
index d46552e33c..82eef350cf 100644
--- a/config/examples/tvrrug/Round2/Configuration.h
+++ b/config/examples/tvrrug/Round2/Configuration.h
@@ -2008,6 +2008,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
diff --git a/config/examples/wt150/Configuration.h b/config/examples/wt150/Configuration.h
index 5c22c426c5..1e009ff19a 100644
--- a/config/examples/wt150/Configuration.h
+++ b/config/examples/wt150/Configuration.h
@@ -2018,6 +2018,7 @@
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
 // However, control resolution will be halved for each increment;
 // at zero value, there are 128 effective control positions.
+// :[0,1,2,3,4,5,6,7]
 #define SOFT_PWM_SCALE 0
 
 // If SOFT_PWM_SCALE is set to a value higher than 0, dithering can