diff --git a/.travis.yml b/.travis.yml
index d3ef785f7e1eccf1e5ed142ed060e066b7b681cd..4d5a00f1b23ae18a49a40e76193ba220beece916 100644
--- a/.travis.yml
+++ b/.travis.yml
@@ -202,9 +202,9 @@ script:
   #
   # Enable COREYX (swapped)
   #
-  - restore_configs
-  - opt_enable COREYX
-  - build_marlin
+  #- restore_configs
+  #- opt_enable COREYX
+  #- build_marlin
   #
   #
   ######## Other Standard LCD/Panels ##############
diff --git a/Marlin/Makefile b/Marlin/Makefile
index b6b3ebdc7ec123f8d75de2f8f61987c5f70f5f8b..d366f4ae5f64f75586793cabccaf93a9c82b729a 100644
--- a/Marlin/Makefile
+++ b/Marlin/Makefile
@@ -290,8 +290,8 @@ ifeq ($(HARDWARE_VARIANT), Teensy)
 SRC = wiring.c
 VPATH += $(ARDUINO_INSTALL_DIR)/hardware/teensy/cores/teensy
 endif
-CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp	\
-	MarlinSerial.cpp Sd2Card.cpp SdBaseFile.cpp SdFatUtil.cpp	\
+CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp \
+	MarlinSerial.cpp Sd2Card.cpp SdBaseFile.cpp SdFatUtil.cpp \
 	SdFile.cpp SdVolume.cpp planner.cpp stepper.cpp \
 	temperature.cpp cardreader.cpp configuration_store.cpp \
 	watchdog.cpp SPI.cpp servo.cpp Tone.cpp ultralcd.cpp digipot_mcp4451.cpp \
diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp
index de275d192c01b142cffb936deac2d5fc1d740a31..bf5ab604677674adb05746a4b06dfb22f6b68397 100644
--- a/Marlin/Marlin_main.cpp
+++ b/Marlin/Marlin_main.cpp
@@ -9677,10 +9677,13 @@ inline void gcode_M503() {
  */
 inline void gcode_M907() {
   #if HAS_DIGIPOTSS
+
     LOOP_XYZE(i) if (parser.seen(axis_codes[i])) stepper.digipot_current(i, parser.value_int());
     if (parser.seen('B')) stepper.digipot_current(4, parser.value_int());
     if (parser.seen('S')) for (uint8_t i = 0; i <= 4; i++) stepper.digipot_current(i, parser.value_int());
+
   #elif HAS_MOTOR_CURRENT_PWM
+
     #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
       if (parser.seen('X')) stepper.digipot_current(0, parser.value_int());
     #endif
@@ -9690,13 +9693,16 @@ inline void gcode_M907() {
     #if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
       if (parser.seen('E')) stepper.digipot_current(2, parser.value_int());
     #endif
+
   #endif
+
   #if ENABLED(DIGIPOT_I2C)
     // this one uses actual amps in floating point
     LOOP_XYZE(i) if (parser.seen(axis_codes[i])) digipot_i2c_set_current(i, parser.value_float());
     // for each additional extruder (named B,C,D,E..., channels 4,5,6,7...)
     for (uint8_t i = NUM_AXIS; i < DIGIPOT_I2C_NUM_CHANNELS; i++) if (parser.seen('B' + i - (NUM_AXIS))) digipot_i2c_set_current(i, parser.value_float());
   #endif
+
   #if ENABLED(DAC_STEPPER_CURRENT)
     if (parser.seen('S')) {
       const float dac_percent = parser.value_float();
diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp
index 2e48701c704446f073193c95317fb73940e8548a..840d6b88f5d821f7de1e0fcaf27304d2299a568b 100644
--- a/Marlin/configuration_store.cpp
+++ b/Marlin/configuration_store.cpp
@@ -36,13 +36,13 @@
  *
  */
 
-#define EEPROM_VERSION "V38"
+#define EEPROM_VERSION "V39"
 
 // Change EEPROM version if these are changed:
 #define EEPROM_OFFSET 100
 
 /**
- * V38 EEPROM Layout:
+ * V39 EEPROM Layout:
  *
  *  100  Version                                    (char x4)
  *  104  EEPROM CRC16                               (uint16_t)
@@ -140,24 +140,29 @@
  *  534  M200 T D  filament_size                    (float x5) (T0..3)
  *
  * HAVE_TMC2130:                                    20 bytes
- *  554  M906 X    stepperX current                 (uint16_t)
- *  556  M906 Y    stepperY current                 (uint16_t)
- *  558  M906 Z    stepperZ current                 (uint16_t)
- *  560  M906 X2   stepperX2 current                (uint16_t)
- *  562  M906 Y2   stepperY2 current                (uint16_t)
- *  564  M906 Z2   stepperZ2 current                (uint16_t)
- *  566  M906 E0   stepperE0 current                (uint16_t)
- *  568  M906 E1   stepperE1 current                (uint16_t)
- *  570  M906 E2   stepperE2 current                (uint16_t)
- *  572  M906 E3   stepperE3 current                (uint16_t)
- *  576  M906 E4   stepperE4 current                (uint16_t)
+ *  554  M906 X    Stepper X current                (uint16_t)
+ *  556  M906 Y    Stepper Y current                (uint16_t)
+ *  558  M906 Z    Stepper Z current                (uint16_t)
+ *  560  M906 X2   Stepper X2 current               (uint16_t)
+ *  562  M906 Y2   Stepper Y2 current               (uint16_t)
+ *  564  M906 Z2   Stepper Z2 current               (uint16_t)
+ *  566  M906 E0   Stepper E0 current               (uint16_t)
+ *  568  M906 E1   Stepper E1 current               (uint16_t)
+ *  570  M906 E2   Stepper E2 current               (uint16_t)
+ *  572  M906 E3   Stepper E3 current               (uint16_t)
+ *  576  M906 E4   Stepper E4 current               (uint16_t)
  *
  * LIN_ADVANCE:                                     8 bytes
  *  580  M900 K    extruder_advance_k               (float)
  *  584  M900 WHD  advance_ed_ratio                 (float)
  *
- *  588                                Minimum end-point
- * 1909 (588 + 36 + 9 + 288 + 988)     Maximum end-point
+ * HAS_MOTOR_CURRENT_PWM:
+ *  588  M907 X    Stepper XY current               (uint32_t)
+ *  592  M907 Z    Stepper Z current                (uint32_t)
+ *  596  M907 E    Stepper E current                (uint32_t)
+ *
+ *  600                                Minimum end-point
+ * 1921 (600 + 36 + 9 + 288 + 988)     Maximum end-point
  *
  * ========================================================================
  * meshes_begin (between max and min end-point, directly above)
@@ -177,6 +182,7 @@ MarlinSettings settings;
 #include "planner.h"
 #include "temperature.h"
 #include "ultralcd.h"
+#include "stepper.h"
 
 #if ENABLED(INCH_MODE_SUPPORT) || (ENABLED(ULTIPANEL) && ENABLED(TEMPERATURE_UNITS_SUPPORT))
   #include "gcode.h"
@@ -238,6 +244,10 @@ void MarlinSettings::postprocess() {
     refresh_bed_level();
     //set_bed_leveling_enabled(leveling_is_on);
   #endif
+
+  #if HAS_MOTOR_CURRENT_PWM
+    stepper.refresh_motor_power();
+  #endif
 }
 
 #if ENABLED(EEPROM_SETTINGS)
@@ -626,6 +636,13 @@ void MarlinSettings::postprocess() {
       EEPROM_WRITE(dummy);
     #endif
 
+    #if HAS_MOTOR_CURRENT_PWM
+      for (uint8_t q = 3; q--;) EEPROM_WRITE(stepper.motor_current_setting[q]);
+    #else
+      const uint32_t dummyui32 = 0;
+      for (uint8_t q = 3; q--;) EEPROM_WRITE(dummyui32);
+    #endif
+
     if (!eeprom_error) {
       const int eeprom_size = eeprom_index;
 
@@ -979,6 +996,13 @@ void MarlinSettings::postprocess() {
         EEPROM_READ(dummy);
       #endif
 
+      #if HAS_MOTOR_CURRENT_PWM
+        for (uint8_t q = 3; q--;) EEPROM_READ(stepper.motor_current_setting[q]);
+      #else
+        uint32_t dummyui32;
+        for (uint8_t q = 3; q--;) EEPROM_READ(dummyui32);
+      #endif
+
       if (working_crc == stored_crc) {
           postprocess();
           SERIAL_ECHO_START();
@@ -1309,6 +1333,12 @@ void MarlinSettings::reset() {
     planner.advance_ed_ratio = LIN_ADVANCE_E_D_RATIO;
   #endif
 
+  #if HAS_MOTOR_CURRENT_PWM
+    uint32_t tmp_motor_current_setting[3] = PWM_MOTOR_CURRENT;
+    for (uint8_t q = 3; q--;)
+      stepper.digipot_current(q, (stepper.motor_current_setting[q] = tmp_motor_current_setting[q]));
+  #endif
+
   #if ENABLED(AUTO_BED_LEVELING_UBL)
     ubl.reset();
   #endif
@@ -1788,6 +1818,18 @@ void MarlinSettings::reset() {
       SERIAL_ECHOPAIR("  M900 K", planner.extruder_advance_k);
       SERIAL_ECHOLNPAIR(" R", planner.advance_ed_ratio);
     #endif
+
+    #if HAS_MOTOR_CURRENT_PWM
+      CONFIG_ECHO_START;
+      if (!forReplay) {
+        SERIAL_ECHOLNPGM("Stepper motor currents:");
+        CONFIG_ECHO_START;
+      }
+      SERIAL_ECHOPAIR("  M907 X", stepper.motor_current_setting[0]);
+      SERIAL_ECHOPAIR(" Z", stepper.motor_current_setting[1]);
+      SERIAL_ECHOPAIR(" E", stepper.motor_current_setting[2]);
+      SERIAL_EOL();
+    #endif
   }
 
 #endif // !DISABLE_M503
diff --git a/Marlin/pins_MINIRAMBO.h b/Marlin/pins_MINIRAMBO.h
index de3c6b08ae55e60fcffe77c4b5545474b4ed215c..6a95a3c4b1cf05688644da8cfd00832bb90e1e64 100644
--- a/Marlin/pins_MINIRAMBO.h
+++ b/Marlin/pins_MINIRAMBO.h
@@ -85,7 +85,9 @@
 #define MOTOR_CURRENT_PWM_Z_PIN  45
 #define MOTOR_CURRENT_PWM_E_PIN  44
 // Motor current PWM conversion, PWM value = MotorCurrentSetting * 255 / range
-#define MOTOR_CURRENT_PWM_RANGE 2000
+#ifndef MOTOR_CURRENT_PWM_RANGE
+  #define MOTOR_CURRENT_PWM_RANGE 2000
+#endif
 #define DEFAULT_PWM_MOTOR_CURRENT  {1300, 1300, 1250}
 
 //
diff --git a/Marlin/pins_ULTIMAIN_2.h b/Marlin/pins_ULTIMAIN_2.h
index d4b99fafc7ed043148149db60daaec26ca1aa6f3..4ac26c6af2b336724c7148d48efe1166167ebe62 100644
--- a/Marlin/pins_ULTIMAIN_2.h
+++ b/Marlin/pins_ULTIMAIN_2.h
@@ -74,7 +74,9 @@
 #define MOTOR_CURRENT_PWM_Z_PIN 45
 #define MOTOR_CURRENT_PWM_E_PIN 46
 // Motor current PWM conversion, PWM value = MotorCurrentSetting * 255 / range
-#define MOTOR_CURRENT_PWM_RANGE 2000
+#ifndef MOTOR_CURRENT_PWM_RANGE
+  #define MOTOR_CURRENT_PWM_RANGE 2000
+#endif
 #define DEFAULT_PWM_MOTOR_CURRENT  {1300, 1300, 1250}
 
 //
diff --git a/Marlin/stepper.cpp b/Marlin/stepper.cpp
index 2f8fc6dfcf5bc32afd811b908f45b665c1fe19bc..c7ea4ba15c38534bee15e4c201ba081c99511929 100644
--- a/Marlin/stepper.cpp
+++ b/Marlin/stepper.cpp
@@ -72,10 +72,14 @@ block_t* Stepper::current_block = NULL;  // A pointer to the block currently bei
   bool Stepper::performing_homing = false;
 #endif
 
+#if HAS_MOTOR_CURRENT_PWM
+  uint32_t Stepper::motor_current_setting[3] = PWM_MOTOR_CURRENT;
+#endif
+
 // private:
 
-unsigned char Stepper::last_direction_bits = 0;        // The next stepping-bits to be output
-unsigned int Stepper::cleaning_buffer_counter = 0;
+uint8_t Stepper::last_direction_bits = 0;        // The next stepping-bits to be output
+uint16_t Stepper::cleaning_buffer_counter = 0;
 
 #if ENABLED(Z_DUAL_ENDSTOPS)
   bool Stepper::locked_z_motor = false;
@@ -1447,62 +1451,98 @@ void Stepper::report_positions() {
 #if HAS_DIGIPOTSS
 
   // From Arduino DigitalPotControl example
-  void Stepper::digitalPotWrite(int address, int value) {
-    WRITE(DIGIPOTSS_PIN, LOW); // take the SS pin low to select the chip
-    SPI.transfer(address); //  send in the address and value via SPI:
+  void Stepper::digitalPotWrite(const int16_t address, const int16_t value) {
+    WRITE(DIGIPOTSS_PIN, LOW);  // Take the SS pin low to select the chip
+    SPI.transfer(address);      // Send the address and value via SPI
     SPI.transfer(value);
-    WRITE(DIGIPOTSS_PIN, HIGH); // take the SS pin high to de-select the chip:
+    WRITE(DIGIPOTSS_PIN, HIGH); // Take the SS pin high to de-select the chip
     //delay(10);
   }
 
 #endif // HAS_DIGIPOTSS
 
+#if HAS_MOTOR_CURRENT_PWM
+
+  void Stepper::refresh_motor_power() {
+    for (uint8_t i = 0; i < COUNT(motor_current_setting); ++i) {
+      switch (i) {
+        #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
+          case 0:
+        #endif
+        #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
+          case 1:
+        #endif
+        #if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
+          case 2:
+        #endif
+            digipot_current(i, motor_current_setting[i]);
+        default: break;
+      }
+    }
+  }
+
+#endif // HAS_MOTOR_CURRENT_PWM
+
 #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM
 
+  void Stepper::digipot_current(const uint8_t driver, const int current) {
+
+    #if HAS_DIGIPOTSS
+
+      const uint8_t digipot_ch[] = DIGIPOT_CHANNELS;
+      digitalPotWrite(digipot_ch[driver], current);
+
+    #elif HAS_MOTOR_CURRENT_PWM
+
+      if (WITHIN(driver, 0, 2))
+        motor_current_setting[driver] = current; // update motor_current_setting
+
+      #define _WRITE_CURRENT_PWM(P) analogWrite(MOTOR_CURRENT_PWM_## P ##_PIN, 255L * current / (MOTOR_CURRENT_PWM_RANGE))
+      switch (driver) {
+        #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
+          case 0: _WRITE_CURRENT_PWM(XY); break;
+        #endif
+        #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
+          case 1: _WRITE_CURRENT_PWM(Z); break;
+        #endif
+        #if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
+          case 2: _WRITE_CURRENT_PWM(E); break;
+        #endif
+      }
+    #endif
+  }
+
   void Stepper::digipot_init() {
+
     #if HAS_DIGIPOTSS
+
       static const uint8_t digipot_motor_current[] = DIGIPOT_MOTOR_CURRENT;
+
       SPI.begin();
       SET_OUTPUT(DIGIPOTSS_PIN);
+
       for (uint8_t i = 0; i < COUNT(digipot_motor_current); i++) {
         //digitalPotWrite(digipot_ch[i], digipot_motor_current[i]);
         digipot_current(i, digipot_motor_current[i]);
       }
+
     #elif HAS_MOTOR_CURRENT_PWM
+
       #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
         SET_OUTPUT(MOTOR_CURRENT_PWM_XY_PIN);
-        digipot_current(0, motor_current_setting[0]);
       #endif
       #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
         SET_OUTPUT(MOTOR_CURRENT_PWM_Z_PIN);
-        digipot_current(1, motor_current_setting[1]);
       #endif
       #if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
         SET_OUTPUT(MOTOR_CURRENT_PWM_E_PIN);
-        digipot_current(2, motor_current_setting[2]);
       #endif
-      //Set timer5 to 31khz so the PWM of the motor power is as constant as possible. (removes a buzzing noise)
-      TCCR5B = (TCCR5B & ~(_BV(CS50) | _BV(CS51) | _BV(CS52))) | _BV(CS50);
-    #endif
-  }
 
-  void Stepper::digipot_current(uint8_t driver, int current) {
-    #if HAS_DIGIPOTSS
-      const uint8_t digipot_ch[] = DIGIPOT_CHANNELS;
-      digitalPotWrite(digipot_ch[driver], current);
-    #elif HAS_MOTOR_CURRENT_PWM
-      #define _WRITE_CURRENT_PWM(P) analogWrite(P, 255L * current / (MOTOR_CURRENT_PWM_RANGE))
-      switch (driver) {
-        #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
-          case 0: _WRITE_CURRENT_PWM(MOTOR_CURRENT_PWM_XY_PIN); break;
-        #endif
-        #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
-          case 1: _WRITE_CURRENT_PWM(MOTOR_CURRENT_PWM_Z_PIN); break;
-        #endif
-        #if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
-          case 2: _WRITE_CURRENT_PWM(MOTOR_CURRENT_PWM_E_PIN); break;
-        #endif
-      }
+      refresh_motor_power();
+
+      // Set Timer5 to 31khz so the PWM of the motor power is as constant as possible. (removes a buzzing noise)
+      SET_CS5(PRESCALER_1);
+
     #endif
   }
 
@@ -1550,7 +1590,7 @@ void Stepper::report_positions() {
       microstep_mode(i, microstep_modes[i]);
   }
 
-  void Stepper::microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2) {
+  void Stepper::microstep_ms(const uint8_t driver, const int8_t ms1, const int8_t ms2) {
     if (ms1 >= 0) switch (driver) {
       case 0: WRITE(X_MS1_PIN, ms1); break;
       #if HAS_Y_MICROSTEPS
@@ -1601,7 +1641,7 @@ void Stepper::report_positions() {
     }
   }
 
-  void Stepper::microstep_mode(uint8_t driver, uint8_t stepping_mode) {
+  void Stepper::microstep_mode(const uint8_t driver, const uint8_t stepping_mode) {
     switch (stepping_mode) {
       case 1: microstep_ms(driver, MICROSTEP1); break;
       case 2: microstep_ms(driver, MICROSTEP2); break;
diff --git a/Marlin/stepper.h b/Marlin/stepper.h
index 429e8f1d7a6dc918c9c8306e9eb69ec3d71d48a0..3ca1926193fcf43552c211952fc02f4990ad9fd4 100644
--- a/Marlin/stepper.h
+++ b/Marlin/stepper.h
@@ -91,10 +91,17 @@ class Stepper {
       static bool performing_homing;
     #endif
 
+    #if HAS_MOTOR_CURRENT_PWM
+      #ifndef PWM_MOTOR_CURRENT
+        #define PWM_MOTOR_CURRENT DEFAULT_PWM_MOTOR_CURRENT
+      #endif
+      static uint32_t motor_current_setting[3];
+    #endif
+
   private:
 
-    static unsigned char last_direction_bits;        // The next stepping-bits to be output
-    static unsigned int cleaning_buffer_counter;
+    static uint8_t last_direction_bits;        // The next stepping-bits to be output
+    static uint16_t cleaning_buffer_counter;
 
     #if ENABLED(Z_DUAL_ENDSTOPS)
       static bool locked_z_motor, locked_z2_motor;
@@ -132,13 +139,6 @@ class Stepper {
     static volatile long endstops_trigsteps[XYZ];
     static volatile long endstops_stepsTotal, endstops_stepsDone;
 
-    #if HAS_MOTOR_CURRENT_PWM
-      #ifndef PWM_MOTOR_CURRENT
-        #define PWM_MOTOR_CURRENT DEFAULT_PWM_MOTOR_CURRENT
-      #endif
-      static constexpr int motor_current_setting[3] = PWM_MOTOR_CURRENT;
-    #endif
-
     //
     // Positions of stepper motors, in step units
     //
@@ -243,20 +243,20 @@ class Stepper {
     static FORCE_INLINE bool motor_direction(AxisEnum axis) { return TEST(last_direction_bits, axis); }
 
     #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM
-      static void digitalPotWrite(int address, int value);
-      static void digipot_current(uint8_t driver, int current);
+      static void digitalPotWrite(const int16_t address, const int16_t value);
+      static void digipot_current(const uint8_t driver, const int16_t current);
     #endif
 
     #if HAS_MICROSTEPS
-      static void microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2);
-      static void microstep_mode(uint8_t driver, uint8_t stepping);
+      static void microstep_ms(const uint8_t driver, const int8_t ms1, const int8_t ms2);
+      static void microstep_mode(const uint8_t driver, const uint8_t stepping);
       static void microstep_readings();
     #endif
 
     #if ENABLED(Z_DUAL_ENDSTOPS)
-      static FORCE_INLINE void set_homing_flag(bool state) { performing_homing = state; }
-      static FORCE_INLINE void set_z_lock(bool state) { locked_z_motor = state; }
-      static FORCE_INLINE void set_z2_lock(bool state) { locked_z2_motor = state; }
+      static FORCE_INLINE void set_homing_flag(const bool state) { performing_homing = state; }
+      static FORCE_INLINE void set_z_lock(const bool state) { locked_z_motor = state; }
+      static FORCE_INLINE void set_z2_lock(const bool state) { locked_z2_motor = state; }
     #endif
 
     #if ENABLED(BABYSTEPPING)
@@ -279,6 +279,10 @@ class Stepper {
       return endstops_trigsteps[axis] * planner.steps_to_mm[axis];
     }
 
+    #if HAS_MOTOR_CURRENT_PWM
+      static void refresh_motor_power();
+    #endif
+
   private:
 
     static FORCE_INLINE unsigned short calc_timer(unsigned short step_rate) {
@@ -380,7 +384,9 @@ class Stepper {
       // SERIAL_ECHOLN(current_block->final_advance/256.0);
     }
 
-    static void digipot_init();
+    #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM
+      static void digipot_init();
+    #endif
 
     #if HAS_MICROSTEPS
       static void microstep_init();
diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp
index ed26888db80820eae53aafaf94d80c5ca7c0f9f2..a136503116789b07d2338195f9f58b90a8e7dfba 100644
--- a/Marlin/ultralcd.cpp
+++ b/Marlin/ultralcd.cpp
@@ -1249,6 +1249,7 @@ void kill_screen(const char* lcd_msg) {
    *
    */
   #if ENABLED(DAC_STEPPER_CURRENT)
+
     void dac_driver_getValues() { LOOP_XYZE(i) driverPercent[i] = dac_current_get_percent((AxisEnum)i); }
 
     void dac_driver_commit() { dac_current_set_percents(driverPercent); }
@@ -1266,7 +1267,27 @@ void kill_screen(const char* lcd_msg) {
       MENU_ITEM(function, MSG_DAC_EEPROM_WRITE, dac_driver_eeprom_write);
       END_MENU();
     }
-  #endif
+
+  #endif // DAC_STEPPER_CURRENT
+
+  #if HAS_MOTOR_CURRENT_PWM
+
+    void lcd_pwm_menu() {
+      START_MENU();
+      MENU_BACK(MSG_CONTROL);
+      #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
+        MENU_ITEM_EDIT_CALLBACK(long5, MSG_X MSG_Y, &stepper.motor_current_setting[0], 100, 2000, Stepper::refresh_motor_power);
+      #endif
+      #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
+        MENU_ITEM_EDIT_CALLBACK(long5, MSG_Z, &stepper.motor_current_setting[1], 100, 2000, Stepper::refresh_motor_power);
+      #endif
+      #if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
+        MENU_ITEM_EDIT_CALLBACK(long5, MSG_E, &stepper.motor_current_setting[2], 100, 2000, Stepper::refresh_motor_power);
+      #endif
+      END_MENU();
+    }
+
+  #endif // HAS_MOTOR_CURRENT_PWM
 
   constexpr int16_t heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP);
 
@@ -2894,6 +2915,9 @@ void kill_screen(const char* lcd_msg) {
     #if ENABLED(DAC_STEPPER_CURRENT)
       MENU_ITEM(submenu, MSG_DRIVE_STRENGTH, lcd_dac_menu);
     #endif
+    #if HAS_MOTOR_CURRENT_PWM
+      MENU_ITEM(submenu, MSG_DRIVE_STRENGTH, lcd_pwm_menu);
+    #endif
 
     #if ENABLED(BLTOUCH)
       MENU_ITEM(submenu, MSG_BLTOUCH, bltouch_menu);