Browse Source

Merge branch 'bugfix-2.0.x' of https://github.com/MarlinFirmware/Marlin into bugfix-2.0.x

Bob-the-Kuhn 6 years ago
parent
commit
9dd4252b39
100 changed files with 1327 additions and 835 deletions
  1. 33
    18
      Marlin/Configuration.h
  2. 31
    5
      Marlin/Configuration_adv.h
  3. 12
    12
      Marlin/src/HAL/HAL_AVR/MarlinSerial.cpp
  4. 1
    1
      Marlin/src/HAL/HAL_AVR/MarlinSerial.h
  5. 2
    2
      Marlin/src/HAL/HAL_AVR/SanityCheck.h
  6. 33
    0
      Marlin/src/HAL/HAL_ESP32/FlushableHardwareSerial.cpp
  7. 36
    0
      Marlin/src/HAL/HAL_ESP32/FlushableHardwareSerial.h
  8. 8
    2
      Marlin/src/HAL/HAL_ESP32/HAL.cpp
  9. 4
    3
      Marlin/src/HAL/HAL_ESP32/HAL.h
  10. 19
    7
      Marlin/src/HAL/HAL_ESP32/HAL_spi_ESP32.cpp
  11. 1
    1
      Marlin/src/HAL/HAL_ESP32/WebSocketSerial.cpp
  12. 1
    1
      Marlin/src/HAL/HAL_ESP32/WebSocketSerial.h
  13. 3
    0
      Marlin/src/HAL/HAL_ESP32/fastio_ESP32.h
  14. 93
    0
      Marlin/src/HAL/HAL_ESP32/persistent_store_spiffs.cpp
  15. 16
    12
      Marlin/src/HAL/HAL_ESP32/spiffs.cpp
  16. 26
    0
      Marlin/src/HAL/HAL_ESP32/spiffs.h
  17. 7
    11
      Marlin/src/HAL/HAL_ESP32/web.cpp
  18. 5
    2
      Marlin/src/HAL/HAL_ESP32/web.h
  19. 5
    2
      Marlin/src/HAL/HAL_ESP32/wifi.cpp
  20. 5
    2
      Marlin/src/HAL/HAL_ESP32/wifi.h
  21. 2
    2
      Marlin/src/HAL/HAL_LINUX/SanityCheck.h
  22. 6
    4
      Marlin/src/HAL/HAL_LPC1768/HAL.cpp
  23. 2
    2
      Marlin/src/HAL/HAL_LPC1768/SanityCheck.h
  24. 6
    0
      Marlin/src/HAL/HAL_LPC1768/pinsDebug.h
  25. 4
    2
      Marlin/src/HAL/HAL_LPC1768/watchdog.cpp
  26. 4
    2
      Marlin/src/HAL/HAL_STM32/HAL.cpp
  27. 1
    1
      Marlin/src/HAL/HAL_STM32/HAL.h
  28. 2
    2
      Marlin/src/HAL/HAL_STM32/SanityCheck.h
  29. 2
    2
      Marlin/src/HAL/HAL_STM32F1/SanityCheck.h
  30. 45
    47
      Marlin/src/HAL/HAL_STM32F4/EEPROM_Emul/eeprom_emul.h
  31. 1
    1
      Marlin/src/HAL/HAL_STM32F4/HAL.cpp
  32. 1
    1
      Marlin/src/HAL/HAL_STM32F4/HAL.h
  33. 2
    2
      Marlin/src/HAL/HAL_STM32F4/SanityCheck.h
  34. 45
    47
      Marlin/src/HAL/HAL_STM32F7/EEPROM_Emul/eeprom_emul.h
  35. 1
    1
      Marlin/src/HAL/HAL_STM32F7/HAL.cpp
  36. 1
    1
      Marlin/src/HAL/HAL_STM32F7/HAL.h
  37. 2
    2
      Marlin/src/HAL/HAL_STM32F7/SanityCheck.h
  38. 13
    13
      Marlin/src/Marlin.cpp
  39. 4
    1
      Marlin/src/core/boards.h
  40. 2
    0
      Marlin/src/core/debug_out.h
  41. 38
    13
      Marlin/src/core/drivers.h
  42. 6
    0
      Marlin/src/core/enum.h
  43. 18
    17
      Marlin/src/core/serial.cpp
  44. 6
    9
      Marlin/src/core/serial.h
  45. 18
    5
      Marlin/src/core/utility.cpp
  46. 4
    1
      Marlin/src/core/utility.h
  47. 6
    6
      Marlin/src/feature/I2CPositionEncoder.cpp
  48. 2
    3
      Marlin/src/feature/I2CPositionEncoder.h
  49. 135
    0
      Marlin/src/feature/babystep.cpp
  50. 63
    0
      Marlin/src/feature/babystep.h
  51. 0
    4
      Marlin/src/feature/bedlevel/bedlevel.cpp
  52. 0
    6
      Marlin/src/feature/bedlevel/bedlevel.h
  53. 2
    2
      Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp
  54. 4
    48
      Marlin/src/feature/bedlevel/ubl/ubl.cpp
  55. 0
    8
      Marlin/src/feature/bedlevel/ubl/ubl.h
  56. 2
    6
      Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp
  57. 0
    26
      Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp
  58. 3
    0
      Marlin/src/feature/digipot/digipot_mcp4451.cpp
  59. 1
    1
      Marlin/src/feature/host_actions.cpp
  60. 1
    1
      Marlin/src/feature/host_actions.h
  61. 20
    11
      Marlin/src/feature/leds/leds.h
  62. 40
    44
      Marlin/src/feature/power_loss_recovery.cpp
  63. 5
    3
      Marlin/src/feature/power_loss_recovery.h
  64. 40
    40
      Marlin/src/feature/prusa_MMU2/mmu2.cpp
  65. 18
    18
      Marlin/src/feature/prusa_MMU2/mmu2.h
  66. 1
    1
      Marlin/src/feature/runout.h
  67. 9
    9
      Marlin/src/feature/tmc_util.cpp
  68. 1
    1
      Marlin/src/feature/tmc_util.h
  69. 26
    78
      Marlin/src/gcode/bedlevel/G26.cpp
  70. 26
    15
      Marlin/src/gcode/calibrate/G28.cpp
  71. 1
    1
      Marlin/src/gcode/config/M217.cpp
  72. 8
    8
      Marlin/src/gcode/config/M43.cpp
  73. 6
    6
      Marlin/src/gcode/control/M3-M5.cpp
  74. 2
    2
      Marlin/src/gcode/control/M605.cpp
  75. 1
    1
      Marlin/src/gcode/control/T.cpp
  76. 1
    1
      Marlin/src/gcode/feature/pause/M701_M702.cpp
  77. 13
    13
      Marlin/src/gcode/feature/powerloss/M1000.cpp
  78. 1
    1
      Marlin/src/gcode/feature/prusa_MMU2/M403.cpp
  79. 11
    5
      Marlin/src/gcode/gcode.cpp
  80. 0
    4
      Marlin/src/gcode/gcode.h
  81. 1
    1
      Marlin/src/gcode/geometry/G53-G59.cpp
  82. 1
    1
      Marlin/src/gcode/host/M876.cpp
  83. 4
    3
      Marlin/src/gcode/motion/M290.cpp
  84. 0
    4
      Marlin/src/gcode/queue.cpp
  85. 1
    1
      Marlin/src/gcode/temperature/M141_M191.cpp
  86. 32
    35
      Marlin/src/inc/Conditionals_LCD.h
  87. 2
    5
      Marlin/src/inc/Conditionals_post.h
  88. 9
    0
      Marlin/src/inc/SanityCheck.h
  89. 11
    1
      Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp
  90. 1
    1
      Marlin/src/lcd/dogm/HAL_LCD_com_defines.h
  91. 83
    93
      Marlin/src/lcd/dogm/dogm_Bootscreen.h
  92. 1
    1
      Marlin/src/lcd/dogm/u8g_fontutf8.cpp
  93. 91
    37
      Marlin/src/lcd/dogm/ultralcd_DOGM.cpp
  94. 1
    1
      Marlin/src/lcd/dogm/ultralcd_DOGM.h
  95. 7
    3
      Marlin/src/lcd/extensible_ui/ui_api.cpp
  96. 1
    1
      Marlin/src/lcd/extensible_ui/ui_api.h
  97. 2
    2
      Marlin/src/lcd/fontutils.cpp
  98. 26
    4
      Marlin/src/lcd/language/language_de.h
  99. 27
    9
      Marlin/src/lcd/language/language_en.h
  100. 0
    0
      Marlin/src/lcd/language/language_it.h

+ 33
- 18
Marlin/Configuration.h View File

@@ -249,13 +249,27 @@
249 249
  * the E3D Tool Changer. Toolheads are locked with a servo.
250 250
  */
251 251
 //#define SWITCHING_TOOLHEAD
252
-#if ENABLED(SWITCHING_TOOLHEAD)
253
-  #define SWITCHING_TOOLHEAD_SERVO_NR       2         // Index of the servo connector
254
-  #define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 }  // (degrees) Angles for Lock, Unlock
255
-  #define SWITCHING_TOOLHEAD_Y_POS        235         // (mm) Y position of the toolhead dock
256
-  #define SWITCHING_TOOLHEAD_Y_SECURITY    10         // (mm) Security distance Y axis
257
-  #define SWITCHING_TOOLHEAD_Y_CLEAR       60         // (mm) Minimum distance from dock for unobstructed X axis
258
-  #define SWITCHING_TOOLHEAD_X_POS        { 215, 0 }  // (mm) X positions for parking the extruders
252
+
253
+/**
254
+ * Magnetic Switching Toolhead
255
+ *
256
+ * Support swappable and dockable toolheads with a magnetic
257
+ * docking mechanism using movement and no servo.
258
+ */
259
+//#define MAGNETIC_SWITCHING_TOOLHEAD
260
+
261
+#if EITHER(SWITCHING_TOOLHEAD, MAGNETIC_SWITCHING_TOOLHEAD)
262
+  #define SWITCHING_TOOLHEAD_Y_POS          235         // (mm) Y position of the toolhead dock
263
+  #define SWITCHING_TOOLHEAD_Y_SECURITY      10         // (mm) Security distance Y axis
264
+  #define SWITCHING_TOOLHEAD_Y_CLEAR         60         // (mm) Minimum distance from dock for unobstructed X axis
265
+  #define SWITCHING_TOOLHEAD_X_POS          { 215, 0 }  // (mm) X positions for parking the extruders
266
+  #if ENABLED(SWITCHING_TOOLHEAD)
267
+    #define SWITCHING_TOOLHEAD_SERVO_NR       2         // Index of the servo connector
268
+    #define SWITCHING_TOOLHEAD_SERVO_ANGLES { 0, 180 }  // (degrees) Angles for Lock, Unlock
269
+  #elif ENABLED(MAGNETIC_SWITCHING_TOOLHEAD)
270
+    #define SWITCHING_TOOLHEAD_Y_RELEASE      5         // (mm) Security distance Y axis
271
+    #define SWITCHING_TOOLHEAD_X_SECURITY   -35         // (mm) Security distance X axis
272
+  #endif
259 273
 #endif
260 274
 
261 275
 /**
@@ -377,7 +391,6 @@
377 391
 #define TEMP_SENSOR_5 0
378 392
 #define TEMP_SENSOR_BED 0
379 393
 #define TEMP_SENSOR_CHAMBER 0
380
-#define CHAMBER_HEATER_PIN -1  // On/off pin for enclosure heating system
381 394
 
382 395
 // Dummy thermistor constant temperature readings, for use with 998 and 999
383 396
 #define DUMMY_THERMISTOR_998_VALUE 25
@@ -396,8 +409,6 @@
396 409
 #define TEMP_BED_WINDOW          1  // (°C) Temperature proximity for the "temperature reached" timer
397 410
 #define TEMP_BED_HYSTERESIS      3  // (°C) Temperature proximity considered "close enough" to the target
398 411
 
399
-#define TEMP_CHAMBER_HYSTERESIS  3  // (°C) Temperature proximity considered "close enough" to the target
400
-
401 412
 // Below this temperature the heater will be switched off
402 413
 // because it probably indicates a broken thermistor wire.
403 414
 #define HEATER_0_MINTEMP   5
@@ -407,7 +418,6 @@
407 418
 #define HEATER_4_MINTEMP   5
408 419
 #define HEATER_5_MINTEMP   5
409 420
 #define BED_MINTEMP        5
410
-#define CHAMBER_MINTEMP    5
411 421
 
412 422
 // Above this temperature the heater will be switched off.
413 423
 // This can protect components from overheating, but NOT from shorts and failures.
@@ -419,7 +429,6 @@
419 429
 #define HEATER_4_MAXTEMP 275
420 430
 #define HEATER_5_MAXTEMP 275
421 431
 #define BED_MAXTEMP      150
422
-#define CHAMBER_MAXTEMP  100
423 432
 
424 433
 //===========================================================================
425 434
 //============================= PID Settings ================================
@@ -462,7 +471,7 @@
462 471
 #endif // PIDTEMP
463 472
 
464 473
 //===========================================================================
465
-//============================= PID > Bed Temperature Control ===============
474
+//====================== PID > Bed Temperature Control ======================
466 475
 //===========================================================================
467 476
 
468 477
 /**
@@ -1413,7 +1422,7 @@
1413 1422
 //#define NOZZLE_PARK_FEATURE
1414 1423
 
1415 1424
 #if ENABLED(NOZZLE_PARK_FEATURE)
1416
-  // Specify a park position as { X, Y, Z }
1425
+  // Specify a park position as { X, Y, Z_raise }
1417 1426
   #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 }
1418 1427
   #define NOZZLE_PARK_XY_FEEDRATE 100   // (mm/s) X and Y axes feedrate (also used for delta Z axis)
1419 1428
   #define NOZZLE_PARK_Z_FEEDRATE 5      // (mm/s) Z axis feedrate (not used for delta printers)
@@ -1894,6 +1903,12 @@
1894 1903
 //#define MKS_MINI_12864
1895 1904
 
1896 1905
 //
1906
+// FYSETC variant of the MINI12864 graphic controller with SD support
1907
+// https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8
1908
+//
1909
+//#define FYSETC_MINI_12864
1910
+
1911
+//
1897 1912
 // Factory display for Creality CR-10
1898 1913
 // https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1899 1914
 //
@@ -2050,10 +2065,10 @@
2050 2065
 //#define RGBW_LED
2051 2066
 
2052 2067
 #if EITHER(RGB_LED, RGBW_LED)
2053
-  #define RGB_LED_R_PIN 34
2054
-  #define RGB_LED_G_PIN 43
2055
-  #define RGB_LED_B_PIN 35
2056
-  #define RGB_LED_W_PIN -1
2068
+  //#define RGB_LED_R_PIN 34
2069
+  //#define RGB_LED_G_PIN 43
2070
+  //#define RGB_LED_B_PIN 35
2071
+  //#define RGB_LED_W_PIN -1
2057 2072
 #endif
2058 2073
 
2059 2074
 // Support for Adafruit Neopixel LED driver

+ 31
- 5
Marlin/Configuration_adv.h View File

@@ -50,6 +50,19 @@
50 50
   #define HEATER_BED_INVERTING true
51 51
 #endif
52 52
 
53
+/**
54
+ * Heated Chamber settings
55
+ */
56
+#if TEMP_SENSOR_CHAMBER
57
+  #define CHAMBER_MINTEMP             5
58
+  #define CHAMBER_MAXTEMP            60
59
+  #define TEMP_CHAMBER_HYSTERESIS     1   // (°C) Temperature proximity considered "close enough" to the target
60
+  #define THERMAL_PROTECTION_CHAMBER      // Enable thermal protection for the heated chamber
61
+  //#define CHAMBER_LIMIT_SWITCHING
62
+  //#define HEATER_CHAMBER_PIN       44   // Chamber heater on/off pin
63
+  //#define HEATER_CHAMBER_INVERTING false
64
+#endif
65
+
53 66
 #if DISABLED(PIDTEMPBED)
54 67
   #define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
55 68
   #if ENABLED(BED_LIMIT_SWITCHING)
@@ -127,8 +140,8 @@
127 140
 #endif
128 141
 
129 142
 #if ENABLED(PIDTEMP)
130
-  // this adds an experimental additional term to the heating power, proportional to the extrusion speed.
131
-  // if Kc is chosen well, the additional required power due to increased melting should be compensated.
143
+  // Add an experimental additional term to the heater power, proportional to the extrusion speed.
144
+  // A well-chosen Kc value should add just enough power to melt the increased material volume.
132 145
   //#define PID_EXTRUSION_SCALING
133 146
   #if ENABLED(PID_EXTRUSION_SCALING)
134 147
     #define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
@@ -456,6 +469,7 @@
456 469
 #define Z_HOME_BUMP_MM 2
457 470
 #define HOMING_BUMP_DIVISOR { 2, 2, 4 }  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
458 471
 //#define QUICK_HOME                     // If homing includes X and Y, do a diagonal move initially
472
+//#define HOMING_BACKOFF_MM { 2, 2, 2 }  // (mm) Move away from the endstops after homing
459 473
 
460 474
 // When G28 is called, this option will make Y home before X
461 475
 //#define HOME_Y_BEFORE_X
@@ -678,6 +692,7 @@
678 692
    *                        A   (A shifted)   B   (B shifted)  IC
679 693
    * Smoothie              0x2C (0x58)       0x2D (0x5A)       MCP4451
680 694
    * AZTEEG_X3_PRO         0x2C (0x58)       0x2E (0x5C)       MCP4451
695
+   * AZTEEG_X5_MINI        0x2C (0x58)       0x2E (0x5C)       MCP4451
681 696
    * AZTEEG_X5_MINI_WIFI         0x58              0x5C        MCP4451
682 697
    * MIGHTYBOARD_REVE      0x2F (0x5E)                         MCP4018
683 698
    */
@@ -770,8 +785,11 @@
770 785
   // Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
771 786
   #define SDCARD_RATHERRECENTFIRST
772 787
 
773
-  // Add an option in the menu to run all auto#.g files
774
-  //#define MENU_ADDAUTOSTART
788
+  #define SD_MENU_CONFIRM_START             // Confirm the selected SD file before printing
789
+
790
+  //#define MENU_ADDAUTOSTART               // Add a menu option to run auto#.g files
791
+
792
+  #define EVENT_GCODE_SD_STOP "G28XY"       // G-code to run on Stop Print (e.g., "G28XY" or "G27")
775 793
 
776 794
   /**
777 795
    * Continue after Power-Loss (Creality3D)
@@ -959,6 +977,12 @@
959 977
   //#define STATUS_ALT_FAN_BITMAP     // Use the alternative fan bitmap
960 978
   //#define STATUS_FAN_FRAMES 3       // :[0,1,2,3,4] Number of fan animation frames
961 979
   //#define STATUS_HEAT_PERCENT       // Show heating in a progress bar
980
+  //#define BOOT_MARLIN_LOGO_SMALL    // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash)
981
+
982
+  // Frivolous Game Options
983
+  //#define MARLIN_BRICKOUT
984
+  //#define MARLIN_INVADERS
985
+  //#define MARLIN_SNAKE
962 986
 
963 987
   // Frivolous Game Options
964 988
   //#define MARLIN_BRICKOUT
@@ -1000,13 +1024,15 @@
1000 1024
   #if ENABLED(DOUBLECLICK_FOR_Z_BABYSTEPPING)
1001 1025
     #define DOUBLECLICK_MAX_INTERVAL 1250   // Maximum interval between clicks, in milliseconds.
1002 1026
                                             // Note: Extra time may be added to mitigate controller latency.
1003
-    //#define BABYSTEP_ALWAYS_AVAILABLE     // Allow babystepping at all times (not just during movement).
1027
+    #define BABYSTEP_ALWAYS_AVAILABLE     // Allow babystepping at all times (not just during movement).
1004 1028
     //#define MOVE_Z_WHEN_IDLE              // Jump to the move Z menu on doubleclick when printer is idle.
1005 1029
     #if ENABLED(MOVE_Z_WHEN_IDLE)
1006 1030
       #define MOVE_Z_IDLE_MULTIPLICATOR 1   // Multiply 1mm by this factor for the move step size.
1007 1031
     #endif
1008 1032
   #endif
1009 1033
 
1034
+  //#define BABYSTEP_DISPLAY_TOTAL          // Display total babysteps since last G28
1035
+
1010 1036
   //#define BABYSTEP_ZPROBE_OFFSET          // Combine M851 Z and Babystepping
1011 1037
   #if ENABLED(BABYSTEP_ZPROBE_OFFSET)
1012 1038
     //#define BABYSTEP_HOTEND_Z_OFFSET      // For multiple hotends, babystep relative Z offsets

+ 12
- 12
Marlin/src/HAL/HAL_AVR/MarlinSerial.cpp View File

@@ -739,24 +739,24 @@
739 739
 
740 740
 #endif // !USBCON && (UBRRH || UBRR0H || UBRR1H || UBRR2H || UBRR3H)
741 741
 
742
+#ifdef INTERNAL_SERIAL_PORT
742 743
 
743
-#if defined(INTERNAL_SERIAL_PORT)
744
-
745
-    ISR(SERIAL_REGNAME(USART,INTERNAL_SERIAL_PORT,_RX_vect)) {
746
-      MarlinSerial<MarlinInternalSerialCfg<INTERNAL_SERIAL_PORT>>::store_rxd_char();
747
-    }
744
+  ISR(SERIAL_REGNAME(USART,INTERNAL_SERIAL_PORT,_RX_vect)) {
745
+    MarlinSerial<MarlinInternalSerialCfg<INTERNAL_SERIAL_PORT>>::store_rxd_char();
746
+  }
748 747
 
749
-    ISR(SERIAL_REGNAME(USART,INTERNAL_SERIAL_PORT,_UDRE_vect)) {
750
-      MarlinSerial<MarlinInternalSerialCfg<INTERNAL_SERIAL_PORT>>::_tx_udr_empty_irq();
751
-    }
748
+  ISR(SERIAL_REGNAME(USART,INTERNAL_SERIAL_PORT,_UDRE_vect)) {
749
+    MarlinSerial<MarlinInternalSerialCfg<INTERNAL_SERIAL_PORT>>::_tx_udr_empty_irq();
750
+  }
752 751
 
753
-    // Preinstantiate
754
-    template class MarlinSerial<MarlinInternalSerialCfg<INTERNAL_SERIAL_PORT>>;
752
+  // Preinstantiate
753
+  template class MarlinSerial<MarlinInternalSerialCfg<INTERNAL_SERIAL_PORT>>;
755 754
 
756
-    // Instantiate
757
-    MarlinSerial<MarlinInternalSerialCfg<INTERNAL_SERIAL_PORT>> internalSerial;
755
+  // Instantiate
756
+  MarlinSerial<MarlinInternalSerialCfg<INTERNAL_SERIAL_PORT>> internalSerial;
758 757
 
759 758
 #endif
759
+
760 760
 // For AT90USB targets use the UART for BT interfacing
761 761
 #if defined(USBCON) && ENABLED(BLUETOOTH)
762 762
   HardwareSerial bluetoothSerial;

+ 1
- 1
Marlin/src/HAL/HAL_AVR/MarlinSerial.h View File

@@ -276,7 +276,7 @@
276 276
 #endif // !USBCON
277 277
 
278 278
 
279
-#if defined(INTERNAL_SERIAL_PORT)
279
+#ifdef INTERNAL_SERIAL_PORT
280 280
   template <uint8_t serial>
281 281
   struct MarlinInternalSerialCfg {
282 282
     static constexpr int PORT               = serial;

+ 2
- 2
Marlin/src/HAL/HAL_AVR/SanityCheck.h View File

@@ -46,8 +46,8 @@
46 46
  * Sanity checks for Spindle / Laser
47 47
  */
48 48
 #if ENABLED(SPINDLE_LASER_ENABLE)
49
-  #if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
50
-    #error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
49
+  #if !PIN_EXISTS(SPINDLE_LASER_ENA)
50
+    #error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
51 51
   #elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
52 52
     #error "SPINDLE_DIR_PIN not defined."
53 53
   #elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)

+ 33
- 0
Marlin/src/HAL/HAL_ESP32/FlushableHardwareSerial.cpp View File

@@ -0,0 +1,33 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+#include "FlushableHardwareSerial.h"
24
+
25
+#ifdef ARDUINO_ARCH_ESP32
26
+
27
+FlushableHardwareSerial::FlushableHardwareSerial(int uart_nr)
28
+    : HardwareSerial(uart_nr)
29
+{}
30
+
31
+FlushableHardwareSerial flushableSerial(0);
32
+
33
+#endif // ARDUINO_ARCH_ESP32

+ 36
- 0
Marlin/src/HAL/HAL_ESP32/FlushableHardwareSerial.h View File

@@ -0,0 +1,36 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+#ifdef ARDUINO_ARCH_ESP32
24
+
25
+#include <HardwareSerial.h>
26
+
27
+class FlushableHardwareSerial : public HardwareSerial {
28
+public:
29
+  FlushableHardwareSerial(int uart_nr);
30
+
31
+  inline void flushTX(void) { /* No need to flush the hardware serial, but defined here for compatibility. */ }
32
+};
33
+
34
+extern FlushableHardwareSerial flushableSerial;
35
+
36
+#endif // ARDUINO_ARCH_ESP32

+ 8
- 2
Marlin/src/HAL/HAL_ESP32/HAL.cpp View File

@@ -41,7 +41,10 @@
41 41
   #endif
42 42
   #if ENABLED(WEBSUPPORT)
43 43
     #include "web.h"
44
+    #include "spiffs.h"
44 45
   #endif
46
+#elif ENABLED(EEPROM_SETTINGS)
47
+  #include "spiffs.h"
45 48
 #endif
46 49
 
47 50
 // --------------------------------------------------------------------------
@@ -95,9 +98,12 @@ void HAL_init(void) {
95 98
       OTA_init();
96 99
     #endif
97 100
     #if ENABLED(WEBSUPPORT)
101
+      spiffs_init();
98 102
       web_init();
99 103
     #endif
100 104
     server.begin();
105
+  #elif ENABLED(EEPROM_SETTINGS)
106
+    spiffs_init();
101 107
   #endif
102 108
 
103 109
   i2s_init();
@@ -111,7 +117,7 @@ void HAL_idletask(void) {
111 117
 
112 118
 void HAL_clear_reset_source(void) { }
113 119
 
114
-uint8_t HAL_get_reset_source (void) {
120
+uint8_t HAL_get_reset_source(void) {
115 121
   return rtc_get_reset_reason(1);
116 122
 }
117 123
 
@@ -148,7 +154,7 @@ void HAL_adc_init() {
148 154
   esp_adc_cal_characterize(ADC_UNIT_1, ADC_ATTEN_DB_11, ADC_WIDTH_BIT_12, V_REF, &characteristics);
149 155
 }
150 156
 
151
-void HAL_adc_start_conversion (uint8_t adc_pin) {
157
+void HAL_adc_start_conversion(uint8_t adc_pin) {
152 158
   uint32_t mv;
153 159
   esp_adc_cal_get_voltage((adc_channel_t)get_channel(adc_pin), &characteristics, &mv);
154 160
 

+ 4
- 3
Marlin/src/HAL/HAL_ESP32/HAL.h View File

@@ -48,6 +48,7 @@
48 48
 #include "HAL_timers_ESP32.h"
49 49
 
50 50
 #include "WebSocketSerial.h"
51
+#include "FlushableHardwareSerial.h"
51 52
 
52 53
 // --------------------------------------------------------------------------
53 54
 // Defines
@@ -55,7 +56,7 @@
55 56
 
56 57
 extern portMUX_TYPE spinlock;
57 58
 
58
-#define MYSERIAL0 Serial
59
+#define MYSERIAL0 flushableSerial
59 60
 
60 61
 #if ENABLED(WIFISUPPORT)
61 62
   #define NUM_SERIAL 2
@@ -96,7 +97,7 @@ extern uint16_t HAL_adc_result;
96 97
 void HAL_clear_reset_source (void);
97 98
 
98 99
 // reset reason
99
-uint8_t HAL_get_reset_source (void);
100
+uint8_t HAL_get_reset_source(void);
100 101
 
101 102
 void _delay_ms(int delay);
102 103
 
@@ -119,7 +120,7 @@ void HAL_adc_init(void);
119 120
 #define HAL_READ_ADC()      HAL_adc_result
120 121
 #define HAL_ADC_READY()     true
121 122
 
122
-void HAL_adc_start_conversion (uint8_t adc_pin);
123
+void HAL_adc_start_conversion(uint8_t adc_pin);
123 124
 
124 125
 #define GET_PIN_MAP_PIN(index) index
125 126
 #define GET_PIN_MAP_INDEX(pin) pin

+ 19
- 7
Marlin/src/HAL/HAL_ESP32/HAL_spi_ESP32.cpp View File

@@ -44,6 +44,15 @@ static SPISettings spiConfig;
44 44
 // Public functions
45 45
 // --------------------------------------------------------------------------
46 46
 
47
+#if ENABLED(SOFTWARE_SPI)
48
+
49
+  // --------------------------------------------------------------------------
50
+  // Software SPI
51
+  // --------------------------------------------------------------------------
52
+  #error "Software SPI not supported for ESP32. Use Hardware SPI."
53
+
54
+#else
55
+
47 56
 // --------------------------------------------------------------------------
48 57
 // Hardware SPI
49 58
 // --------------------------------------------------------------------------
@@ -61,13 +70,14 @@ void spiInit(uint8_t spiRate) {
61 70
   uint32_t clock;
62 71
 
63 72
   switch (spiRate) {
64
-    case SPI_FULL_SPEED:    clock = SPI_CLOCK_DIV2;  break;
65
-    case SPI_HALF_SPEED:    clock = SPI_CLOCK_DIV4;  break;
66
-    case SPI_QUARTER_SPEED: clock = SPI_CLOCK_DIV8;  break;
67
-    case SPI_EIGHTH_SPEED:  clock = SPI_CLOCK_DIV16; break;
68
-    case SPI_SPEED_5:       clock = SPI_CLOCK_DIV32; break;
69
-    case SPI_SPEED_6:       clock = SPI_CLOCK_DIV64; break;
70
-    default:                clock = SPI_CLOCK_DIV2; // Default from the SPI library
73
+    case SPI_FULL_SPEED:      clock = 16000000; break;
74
+    case SPI_HALF_SPEED:      clock = 8000000;  break;
75
+    case SPI_QUARTER_SPEED:   clock = 4000000;  break;
76
+    case SPI_EIGHTH_SPEED:    clock = 2000000;  break;
77
+    case SPI_SIXTEENTH_SPEED: clock = 1000000;  break;
78
+    case SPI_SPEED_5:         clock = 500000;   break;
79
+    case SPI_SPEED_6:         clock = 250000;   break;
80
+    default:                  clock = 1000000; // Default from the SPI library
71 81
   }
72 82
 
73 83
   spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0);
@@ -106,4 +116,6 @@ void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode)
106 116
   SPI.beginTransaction(spiConfig);
107 117
 }
108 118
 
119
+#endif // !SOFTWARE_SPI
120
+
109 121
 #endif // ARDUINO_ARCH_ESP32

+ 1
- 1
Marlin/src/HAL/HAL_ESP32/WebSocketSerial.cpp View File

@@ -1,6 +1,6 @@
1 1
 /**
2 2
  * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
3
+ * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4 4
  *
5 5
  * Based on Sprinter and grbl.
6 6
  * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm

+ 1
- 1
Marlin/src/HAL/HAL_ESP32/WebSocketSerial.h View File

@@ -1,6 +1,6 @@
1 1
 /**
2 2
  * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
3
+ * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4 4
  *
5 5
  * Based on Sprinter and grbl.
6 6
  * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm

+ 3
- 0
Marlin/src/HAL/HAL_ESP32/fastio_ESP32.h View File

@@ -64,6 +64,9 @@
64 64
 #define PWM_PIN(P)              true
65 65
 #define USEABLE_HARDWARE_PWM(P) PWM_PIN(P)
66 66
 
67
+// Toggle pin value
68
+#define TOGGLE(IO)              WRITE(IO, !READ(IO))
69
+
67 70
 //
68 71
 // Ports and functions
69 72
 //

+ 93
- 0
Marlin/src/HAL/HAL_ESP32/persistent_store_spiffs.cpp View File

@@ -0,0 +1,93 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+#ifdef ARDUINO_ARCH_ESP32
24
+
25
+#include "../../inc/MarlinConfig.h"
26
+
27
+#if ENABLED(EEPROM_SETTINGS) && DISABLED(FLASH_EEPROM_EMULATION)
28
+
29
+#include "../shared/persistent_store_api.h"
30
+
31
+#include "SPIFFS.h"
32
+#include "FS.h"
33
+#include "spiffs.h"
34
+
35
+#define HAL_ESP32_EEPROM_SIZE 4096
36
+
37
+File eeprom_file;
38
+
39
+bool PersistentStore::access_start() {
40
+  if (spiffs_initialized) {
41
+    eeprom_file = SPIFFS.open("/eeprom.dat", "r+");
42
+
43
+    size_t file_size = eeprom_file.size();
44
+    if (file_size < HAL_ESP32_EEPROM_SIZE) {
45
+      bool write_ok = eeprom_file.seek(file_size);
46
+
47
+      while (write_ok && file_size < HAL_ESP32_EEPROM_SIZE) {
48
+        write_ok = eeprom_file.write(0xFF) == 1;
49
+        file_size++;
50
+      }
51
+    }
52
+    return true;
53
+  }
54
+  return false;
55
+}
56
+
57
+bool PersistentStore::access_finish() {
58
+  eeprom_file.close();
59
+  return true;
60
+}
61
+
62
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
63
+  if (!eeprom_file.seek(pos)) return true; // return true for any error
64
+  if (eeprom_file.write(value, size) != size) return true;
65
+
66
+  crc16(crc, value, size);
67
+  pos += size;
68
+
69
+  return false;
70
+}
71
+
72
+bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
73
+  if (!eeprom_file.seek(pos)) return true; // return true for any error
74
+
75
+  if (writing) {
76
+    if (eeprom_file.read(value, size) != size) return true;
77
+    crc16(crc, value, size);
78
+  }
79
+  else {
80
+    uint8_t tmp[size];
81
+    if (eeprom_file.read(tmp, size) != size) return true;
82
+    crc16(crc, tmp, size);
83
+  }
84
+
85
+  pos += size;
86
+
87
+  return false;
88
+}
89
+
90
+size_t PersistentStore::capacity() { return HAL_ESP32_EEPROM_SIZE; }
91
+
92
+#endif // EEPROM_SETTINGS
93
+#endif // ARDUINO_ARCH_ESP32

Marlin/src/gcode/bedlevel/ubl/M49.cpp → Marlin/src/HAL/HAL_ESP32/spiffs.cpp View File

@@ -20,21 +20,25 @@
20 20
  *
21 21
  */
22 22
 
23
-/**
24
- * M49.cpp - Toggle the G26 debug flag
25
- */
23
+#ifdef ARDUINO_ARCH_ESP32
24
+
25
+#include "../../inc/MarlinConfigPre.h"
26
+
27
+#if EITHER(WEBSUPPORT, EEPROM_SETTINGS)
26 28
 
27
-#include "../../../inc/MarlinConfig.h"
29
+#include "../../core/serial.h"
28 30
 
29
-#if ENABLED(G26_MESH_VALIDATION)
31
+#include "FS.h"
32
+#include "SPIFFS.h"
30 33
 
31
-#include "../../gcode.h"
32
-#include "../../../feature/bedlevel/bedlevel.h"
34
+bool spiffs_initialized;
33 35
 
34
-void GcodeSuite::M49() {
35
-  g26_debug_flag ^= true;
36
-  SERIAL_ECHOPGM("G26 Debug: ");
37
-  serialprintPGM(g26_debug_flag ? PSTR("On\n") : PSTR("Off\n"));
36
+void spiffs_init() {
37
+  if (SPIFFS.begin())
38
+    spiffs_initialized = true;
39
+  else
40
+    SERIAL_ECHO_MSG("SPIFFS mount failed");
38 41
 }
39 42
 
40
-#endif // G26_MESH_VALIDATION
43
+#endif // WEBSUPPORT
44
+#endif // ARDUINO_ARCH_ESP32

+ 26
- 0
Marlin/src/HAL/HAL_ESP32/spiffs.h View File

@@ -0,0 +1,26 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+#pragma once
23
+
24
+extern bool spiffs_initialized;
25
+
26
+void spiffs_init();

+ 7
- 11
Marlin/src/HAL/HAL_ESP32/web.cpp View File

@@ -1,7 +1,9 @@
1 1
 /**
2 2
  * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
3
+ * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
5 7
  *
6 8
  * This program is free software: you can redistribute it and/or modify
7 9
  * it under the terms of the GNU General Public License as published by
@@ -15,6 +17,7 @@
15 17
  *
16 18
  * You should have received a copy of the GNU General Public License
17 19
  * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
18 21
  */
19 22
 
20 23
 #ifdef ARDUINO_ARCH_ESP32
@@ -23,9 +26,6 @@
23 26
 
24 27
 #if ENABLED(WEBSUPPORT)
25 28
 
26
-#include "../../core/serial.h"
27
-
28
-#include "FS.h"
29 29
 #include "SPIFFS.h"
30 30
 #include "wifi.h"
31 31
 
@@ -37,12 +37,8 @@ void onNotFound(AsyncWebServerRequest *request){
37 37
 
38 38
 void web_init() {
39 39
   server.addHandler(&events);       // attach AsyncEventSource
40
-  if (SPIFFS.begin()) {
41
-    server.serveStatic("/", SPIFFS, "/www").setDefaultFile("index.html");
42
-    server.onNotFound(onNotFound);
43
-  }
44
-  else
45
-    SERIAL_ECHO_MSG("SPIFFS Mount Failed");
40
+  server.serveStatic("/", SPIFFS, "/www").setDefaultFile("index.html");
41
+  server.onNotFound(onNotFound);
46 42
 }
47 43
 
48 44
 #endif // WEBSUPPORT

+ 5
- 2
Marlin/src/HAL/HAL_ESP32/web.h View File

@@ -1,7 +1,9 @@
1 1
 /**
2 2
  * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
3
+ * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
5 7
  *
6 8
  * This program is free software: you can redistribute it and/or modify
7 9
  * it under the terms of the GNU General Public License as published by
@@ -15,6 +17,7 @@
15 17
  *
16 18
  * You should have received a copy of the GNU General Public License
17 19
  * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
18 21
  */
19 22
 #pragma once
20 23
 

+ 5
- 2
Marlin/src/HAL/HAL_ESP32/wifi.cpp View File

@@ -1,7 +1,9 @@
1 1
 /**
2 2
  * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
3
+ * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
5 7
  *
6 8
  * This program is free software: you can redistribute it and/or modify
7 9
  * it under the terms of the GNU General Public License as published by
@@ -15,6 +17,7 @@
15 17
  *
16 18
  * You should have received a copy of the GNU General Public License
17 19
  * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
18 21
  */
19 22
 
20 23
 #ifdef ARDUINO_ARCH_ESP32

+ 5
- 2
Marlin/src/HAL/HAL_ESP32/wifi.h View File

@@ -1,7 +1,9 @@
1 1
 /**
2 2
  * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
3
+ * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
5 7
  *
6 8
  * This program is free software: you can redistribute it and/or modify
7 9
  * it under the terms of the GNU General Public License as published by
@@ -15,6 +17,7 @@
15 17
  *
16 18
  * You should have received a copy of the GNU General Public License
17 19
  * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
18 21
  */
19 22
 #pragma once
20 23
 

+ 2
- 2
Marlin/src/HAL/HAL_LINUX/SanityCheck.h View File

@@ -25,8 +25,8 @@
25 25
  */
26 26
 
27 27
 #if ENABLED(SPINDLE_LASER_ENABLE)
28
-  #if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
29
-    #error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
28
+  #if !PIN_EXISTS(SPINDLE_LASER_ENA)
29
+    #error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
30 30
   #elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
31 31
     #error "SPINDLE_DIR_PIN not defined."
32 32
   #elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)

+ 6
- 4
Marlin/src/HAL/HAL_LPC1768/HAL.cpp View File

@@ -52,11 +52,13 @@ int freeMemory() {
52 52
   return result;
53 53
 }
54 54
 
55
+// scan command line for code
56
+//   return index into pin map array if found and the pin is valid.
57
+//   return dval if not found or not a valid pin.
55 58
 int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
56
-  const uint16_t val = (uint16_t)parser.intval(code), port = val / 100, pin = val % 100;
57
-  const  int16_t ind = (port < (NUM_DIGITAL_PINS >> 5) && (pin < 32))
58
-                      ? GET_PIN_MAP_INDEX(port << 5 | pin) : -2;
59
-  return ind > -2 ? ind : dval;
59
+  const uint16_t val = (uint16_t)parser.intval(code, -1), port = val / 100, pin = val % 100;
60
+  const  int16_t ind = (port < ((NUM_DIGITAL_PINS) >> 5) && pin < 32) ? GET_PIN_MAP_INDEX((port << 5) | pin) : -2;
61
+  return ind > -1 ? ind : dval;
60 62
 }
61 63
 
62 64
 void flashFirmware(int16_t value) {

+ 2
- 2
Marlin/src/HAL/HAL_LPC1768/SanityCheck.h View File

@@ -25,8 +25,8 @@
25 25
  */
26 26
 
27 27
 #if ENABLED(SPINDLE_LASER_ENABLE)
28
-  #if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
29
-    #error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
28
+  #if !PIN_EXISTS(SPINDLE_LASER_ENA)
29
+    #error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
30 30
   #elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
31 31
     #error "SPINDLE_DIR_PIN not defined."
32 32
   #elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)

+ 6
- 0
Marlin/src/HAL/HAL_LPC1768/pinsDebug.h View File

@@ -40,6 +40,12 @@
40 40
 #define PRINT_PIN(p) do {sprintf_P(buffer, PSTR("%d.%02d"), LPC1768_PIN_PORT(p), LPC1768_PIN_PIN(p)); SERIAL_ECHO(buffer);} while (0)
41 41
 #define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
42 42
 
43
+// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities
44
+//  uses pin index
45
+#ifndef M43_NEVER_TOUCH
46
+  #define M43_NEVER_TOUCH(Q) ((Q) == 29 || (Q) == 30 || (Q) == 73)  // USB pins
47
+#endif
48
+
43 49
 // active ADC function/mode/code values for PINSEL registers
44 50
 constexpr int8_t ADC_pin_mode(pin_t pin) {
45 51
   return (LPC1768_PIN_PORT(pin) == 0 && LPC1768_PIN_PIN(pin) == 2  ? 2 :

+ 4
- 2
Marlin/src/HAL/HAL_LPC1768/watchdog.cpp View File

@@ -74,8 +74,10 @@ void watchdog_reset() {
74 74
 
75 75
 #else
76 76
 
77
-  void HAL_clear_reset_source(void) {}
78
-  uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; }
77
+void watchdog_init(void) {}
78
+void watchdog_reset(void) {}
79
+void HAL_clear_reset_source(void) {}
80
+uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; }
79 81
 
80 82
 #endif // USE_WATCHDOG
81 83
 

+ 4
- 2
Marlin/src/HAL/HAL_STM32/HAL.cpp View File

@@ -36,8 +36,10 @@
36 36
 #if ENABLED(EEPROM_EMULATED_WITH_SRAM)
37 37
   #if STM32F7xx
38 38
     #include "stm32f7xx_ll_pwr.h"
39
+  #elif STM32F4xx
40
+    #include "stm32f4xx_ll_pwr.h"
39 41
   #else
40
-    #error "EEPROM_EMULATED_WITH_SRAM is currently only supported for STM32F7xx"
42
+    #error "EEPROM_EMULATED_WITH_SRAM is currently only supported for STM32F4xx and STM32F7xx"
41 43
   #endif
42 44
 #endif // EEPROM_EMULATED_WITH_SRAM
43 45
 
@@ -118,7 +120,7 @@ void HAL_init(void) {
118 120
 
119 121
 void HAL_clear_reset_source(void) { __HAL_RCC_CLEAR_RESET_FLAGS(); }
120 122
 
121
-uint8_t HAL_get_reset_source (void) {
123
+uint8_t HAL_get_reset_source(void) {
122 124
   if (__HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) != RESET) return RST_WATCHDOG;
123 125
   if (__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST) != RESET)  return RST_SOFTWARE;
124 126
   if (__HAL_RCC_GET_FLAG(RCC_FLAG_PINRST) != RESET)  return RST_EXTERNAL;

+ 1
- 1
Marlin/src/HAL/HAL_STM32/HAL.h View File

@@ -165,7 +165,7 @@ void HAL_init(void);
165 165
 void HAL_clear_reset_source (void);
166 166
 
167 167
 /** reset reason */
168
-uint8_t HAL_get_reset_source (void);
168
+uint8_t HAL_get_reset_source(void);
169 169
 
170 170
 void _delay_ms(const int delay);
171 171
 

+ 2
- 2
Marlin/src/HAL/HAL_STM32/SanityCheck.h View File

@@ -25,8 +25,8 @@
25 25
  * Test Re-ARM specific configuration values for errors at compile-time.
26 26
  */
27 27
 #if ENABLED(SPINDLE_LASER_ENABLE)
28
-  #if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
29
-    #error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
28
+  #if !PIN_EXISTS(SPINDLE_LASER_ENA)
29
+    #error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
30 30
   #elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
31 31
     #error "SPINDLE_DIR_PIN not defined."
32 32
   #elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)

+ 2
- 2
Marlin/src/HAL/HAL_STM32F1/SanityCheck.h View File

@@ -28,8 +28,8 @@
28 28
  * Test Re-ARM specific configuration values for errors at compile-time.
29 29
  */
30 30
 #if ENABLED(SPINDLE_LASER_ENABLE)
31
-  #if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
32
-    #error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
31
+  #if !PIN_EXISTS(SPINDLE_LASER_ENA)
32
+    #error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
33 33
   #elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
34 34
     #error "SPINDLE_DIR_PIN not defined."
35 35
   #elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)

+ 45
- 47
Marlin/src/HAL/HAL_STM32F4/EEPROM_Emul/eeprom_emul.h View File

@@ -1,50 +1,48 @@
1
-/**
2
-  ******************************************************************************
3
-  * @file    EEPROM/EEPROM_Emulation/inc/eeprom.h
4
-  * @author  MCD Application Team
5
-  * @version V1.2.6
6
-  * @date    04-November-2016
7
-  * @brief   This file contains all the functions prototypes for the EEPROM
8
-  *          emulation firmware library.
9
-  ******************************************************************************
10
-  * @attention
11
-  *
12
-  * <h2><center>&copy; Copyright � 2016 STMicroelectronics International N.V.
13
-  * All rights reserved.</center></h2>
14
-  *
15
-  * Redistribution and use in source and binary forms, with or without
16
-  * modification, are permitted, provided that the following conditions are met:
17
-  *
18
-  * 1. Redistribution of source code must retain the above copyright notice,
19
-  *    this list of conditions and the following disclaimer.
20
-  * 2. Redistributions in binary form must reproduce the above copyright notice,
21
-  *    this list of conditions and the following disclaimer in the documentation
22
-  *    and/or other materials provided with the distribution.
23
-  * 3. Neither the name of STMicroelectronics nor the names of other
24
-  *    contributors to this software may be used to endorse or promote products
25
-  *    derived from this software without specific written permission.
26
-  * 4. This software, including modifications and/or derivative works of this
27
-  *    software, must execute solely and exclusively on microcontroller or
28
-  *    microprocessor devices manufactured by or for STMicroelectronics.
29
-  * 5. Redistribution and use of this software other than as permitted under
30
-  *    this license is void and will automatically terminate your rights under
31
-  *    this license.
32
-  *
33
-  * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
34
-  * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
35
-  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
36
-  * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
37
-  * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
38
-  * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
39
-  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
40
-  * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
41
-  * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
42
-  * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
43
-  * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
44
-  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
45
-  *
46
-  ******************************************************************************
47
-  */
1
+/******************************************************************************
2
+ * @file    eeprom_emul.h
3
+ * @author  MCD Application Team
4
+ * @version V1.2.6
5
+ * @date    04-November-2016
6
+ * @brief   This file contains all the functions prototypes for the EEPROM
7
+ *          emulation firmware library.
8
+ ******************************************************************************
9
+ * @attention
10
+ *
11
+ * <h2><center>&copy; Copyright � 2016 STMicroelectronics International N.V.
12
+ * All rights reserved.</center></h2>
13
+ *
14
+ * Redistribution and use in source and binary forms, with or without
15
+ * modification, are permitted, provided that the following conditions are met:
16
+ *
17
+ * 1. Redistribution of source code must retain the above copyright notice,
18
+ *    this list of conditions and the following disclaimer.
19
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
20
+ *    this list of conditions and the following disclaimer in the documentation
21
+ *    and/or other materials provided with the distribution.
22
+ * 3. Neither the name of STMicroelectronics nor the names of other
23
+ *    contributors to this software may be used to endorse or promote products
24
+ *    derived from this software without specific written permission.
25
+ * 4. This software, including modifications and/or derivative works of this
26
+ *    software, must execute solely and exclusively on microcontroller or
27
+ *    microprocessor devices manufactured by or for STMicroelectronics.
28
+ * 5. Redistribution and use of this software other than as permitted under
29
+ *    this license is void and will automatically terminate your rights under
30
+ *    this license.
31
+ *
32
+ * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
33
+ * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
34
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
35
+ * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
36
+ * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
37
+ * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
38
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
39
+ * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
40
+ * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
41
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
42
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
43
+ * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
44
+ *
45
+ ******************************************************************************/
48 46
 #pragma once
49 47
 
50 48
 // --------------------------------------------------------------------------

+ 1
- 1
Marlin/src/HAL/HAL_STM32F4/HAL.cpp View File

@@ -79,7 +79,7 @@ void sei(void) { interrupts(); }
79 79
 
80 80
 void HAL_clear_reset_source(void) { __HAL_RCC_CLEAR_RESET_FLAGS(); }
81 81
 
82
-uint8_t HAL_get_reset_source (void) {
82
+uint8_t HAL_get_reset_source(void) {
83 83
   if (__HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) != RESET) return RST_WATCHDOG;
84 84
 
85 85
   if (__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST) != RESET)  return RST_SOFTWARE;

+ 1
- 1
Marlin/src/HAL/HAL_STM32F4/HAL.h View File

@@ -170,7 +170,7 @@ extern uint16_t HAL_adc_result;
170 170
 void HAL_clear_reset_source (void);
171 171
 
172 172
 /** reset reason */
173
-uint8_t HAL_get_reset_source (void);
173
+uint8_t HAL_get_reset_source(void);
174 174
 
175 175
 void _delay_ms(const int delay);
176 176
 

+ 2
- 2
Marlin/src/HAL/HAL_STM32F4/SanityCheck.h View File

@@ -24,8 +24,8 @@
24 24
  * Test Re-ARM specific configuration values for errors at compile-time.
25 25
  */
26 26
 #if ENABLED(SPINDLE_LASER_ENABLE)
27
-  #if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
28
-    #error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
27
+  #if !PIN_EXISTS(SPINDLE_LASER_ENA)
28
+    #error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
29 29
   #elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
30 30
     #error "SPINDLE_DIR_PIN not defined."
31 31
   #elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)

+ 45
- 47
Marlin/src/HAL/HAL_STM32F7/EEPROM_Emul/eeprom_emul.h View File

@@ -1,50 +1,48 @@
1
-/**
2
-  ******************************************************************************
3
-  * @file    EEPROM/EEPROM_Emulation/inc/eeprom.h
4
-  * @author  MCD Application Team
5
-  * @version V1.2.6
6
-  * @date    04-November-2016
7
-  * @brief   This file contains all the functions prototypes for the EEPROM
8
-  *          emulation firmware library.
9
-  ******************************************************************************
10
-  * @attention
11
-  *
12
-  * <h2><center>&copy; Copyright © 2016 STMicroelectronics International N.V.
13
-  * All rights reserved.</center></h2>
14
-  *
15
-  * Redistribution and use in source and binary forms, with or without
16
-  * modification, are permitted, provided that the following conditions are met:
17
-  *
18
-  * 1. Redistribution of source code must retain the above copyright notice,
19
-  *    this list of conditions and the following disclaimer.
20
-  * 2. Redistributions in binary form must reproduce the above copyright notice,
21
-  *    this list of conditions and the following disclaimer in the documentation
22
-  *    and/or other materials provided with the distribution.
23
-  * 3. Neither the name of STMicroelectronics nor the names of other
24
-  *    contributors to this software may be used to endorse or promote products
25
-  *    derived from this software without specific written permission.
26
-  * 4. This software, including modifications and/or derivative works of this
27
-  *    software, must execute solely and exclusively on microcontroller or
28
-  *    microprocessor devices manufactured by or for STMicroelectronics.
29
-  * 5. Redistribution and use of this software other than as permitted under
30
-  *    this license is void and will automatically terminate your rights under
31
-  *    this license.
32
-  *
33
-  * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
34
-  * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
35
-  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
36
-  * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
37
-  * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
38
-  * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
39
-  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
40
-  * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
41
-  * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
42
-  * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
43
-  * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
44
-  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
45
-  *
46
-  ******************************************************************************
47
-  */
1
+/******************************************************************************
2
+ * @file    eeprom_emul.h
3
+ * @author  MCD Application Team
4
+ * @version V1.2.6
5
+ * @date    04-November-2016
6
+ * @brief   This file contains all the functions prototypes for the EEPROM
7
+ *          emulation firmware library.
8
+ ******************************************************************************
9
+ * @attention
10
+ *
11
+ * <h2><center>&copy; Copyright © 2016 STMicroelectronics International N.V.
12
+ * All rights reserved.</center></h2>
13
+ *
14
+ * Redistribution and use in source and binary forms, with or without
15
+ * modification, are permitted, provided that the following conditions are met:
16
+ *
17
+ * 1. Redistribution of source code must retain the above copyright notice,
18
+ *    this list of conditions and the following disclaimer.
19
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
20
+ *    this list of conditions and the following disclaimer in the documentation
21
+ *    and/or other materials provided with the distribution.
22
+ * 3. Neither the name of STMicroelectronics nor the names of other
23
+ *    contributors to this software may be used to endorse or promote products
24
+ *    derived from this software without specific written permission.
25
+ * 4. This software, including modifications and/or derivative works of this
26
+ *    software, must execute solely and exclusively on microcontroller or
27
+ *    microprocessor devices manufactured by or for STMicroelectronics.
28
+ * 5. Redistribution and use of this software other than as permitted under
29
+ *    this license is void and will automatically terminate your rights under
30
+ *    this license.
31
+ *
32
+ * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
33
+ * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
34
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
35
+ * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
36
+ * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
37
+ * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
38
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
39
+ * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
40
+ * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
41
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
42
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
43
+ * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
44
+ *
45
+ *****************************************************************************/
48 46
 #pragma once
49 47
 
50 48
 // --------------------------------------------------------------------------

+ 1
- 1
Marlin/src/HAL/HAL_STM32F7/HAL.cpp View File

@@ -79,7 +79,7 @@ void sei(void) { interrupts(); }
79 79
 
80 80
 void HAL_clear_reset_source(void) { __HAL_RCC_CLEAR_RESET_FLAGS(); }
81 81
 
82
-uint8_t HAL_get_reset_source (void) {
82
+uint8_t HAL_get_reset_source(void) {
83 83
   if (__HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) != RESET)
84 84
     return RST_WATCHDOG;
85 85
 

+ 1
- 1
Marlin/src/HAL/HAL_STM32F7/HAL.h View File

@@ -157,7 +157,7 @@ extern uint16_t HAL_adc_result;
157 157
 void HAL_clear_reset_source (void);
158 158
 
159 159
 /** reset reason */
160
-uint8_t HAL_get_reset_source (void);
160
+uint8_t HAL_get_reset_source(void);
161 161
 
162 162
 void _delay_ms(const int delay);
163 163
 

+ 2
- 2
Marlin/src/HAL/HAL_STM32F7/SanityCheck.h View File

@@ -24,8 +24,8 @@
24 24
  * Test Re-ARM specific configuration values for errors at compile-time.
25 25
  */
26 26
 #if ENABLED(SPINDLE_LASER_ENABLE)
27
-  #if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
28
-    #error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
27
+  #if !PIN_EXISTS(SPINDLE_LASER_ENA)
28
+    #error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENA_PIN."
29 29
   #elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
30 30
     #error "SPINDLE_DIR_PIN not defined."
31 31
   #elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)

+ 13
- 13
Marlin/src/Marlin.cpp View File

@@ -457,7 +457,7 @@ void manage_inactivity(const bool ignore_stepper_queue/*=false*/) {
457 457
   if (stepper_inactive_time) {
458 458
     static bool already_shutdown_steppers; // = false
459 459
     if (planner.has_blocks_queued())
460
-      gcode.previous_move_ms = ms; // reset_stepper_timeout to keep steppers powered
460
+      gcode.reset_stepper_timeout();
461 461
     else if (MOVE_AWAY_TEST && !ignore_stepper_queue && ELAPSED(ms, gcode.previous_move_ms + stepper_inactive_time)) {
462 462
       if (!already_shutdown_steppers) {
463 463
         already_shutdown_steppers = true;  // L6470 SPI will consume 99% of free time without this
@@ -473,14 +473,11 @@ void manage_inactivity(const bool ignore_stepper_queue/*=false*/) {
473 473
         #if ENABLED(DISABLE_INACTIVE_E)
474 474
           disable_e_steppers();
475 475
         #endif
476
-        #if HAS_LCD_MENU
477
-          ui.status_screen();
478
-          #if ENABLED(AUTO_BED_LEVELING_UBL)
479
-            if (ubl.lcd_map_control) {
480
-              ubl.lcd_map_control = false;
481
-              ui.defer_status_screen(false);
482
-            }
483
-          #endif
476
+        #if HAS_LCD_MENU && ENABLED(AUTO_BED_LEVELING_UBL)
477
+          if (ubl.lcd_map_control) {
478
+            ubl.lcd_map_control = false;
479
+            ui.defer_status_screen(false);
480
+          }
484 481
         #endif
485 482
       }
486 483
     }
@@ -617,7 +614,7 @@ void manage_inactivity(const bool ignore_stepper_queue/*=false*/) {
617 614
         }
618 615
       #endif // !SWITCHING_EXTRUDER
619 616
 
620
-      gcode.previous_move_ms = ms; // reset_stepper_timeout to keep steppers powered
617
+      gcode.reset_stepper_timeout();
621 618
     }
622 619
   #endif // EXTRUDER_RUNOUT_PREVENT
623 620
 
@@ -723,7 +720,7 @@ void idle(
723 720
   #endif
724 721
 
725 722
   #if ENABLED(PRUSA_MMU2)
726
-    mmu2.mmuLoop();
723
+    mmu2.mmu_loop();
727 724
   #endif
728 725
 }
729 726
 
@@ -975,7 +972,7 @@ void setup() {
975 972
   #endif
976 973
 
977 974
   #if ENABLED(SPINDLE_LASER_ENABLE)
978
-    OUT_WRITE(SPINDLE_LASER_ENABLE_PIN, !SPINDLE_LASER_ENABLE_INVERT);  // init spindle to off
975
+    OUT_WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ENABLE_INVERT);  // init spindle to off
979 976
     #if SPINDLE_DIR_CHANGE
980 977
       OUT_WRITE(SPINDLE_DIR_PIN, SPINDLE_INVERT_DIR ? 255 : 0);  // init rotation to clockwise (M3)
981 978
     #endif
@@ -1045,7 +1042,7 @@ void setup() {
1045 1042
   ui.init();
1046 1043
   ui.reset_status();
1047 1044
 
1048
-  #if ENABLED(SHOW_BOOTSCREEN)
1045
+  #if HAS_SPI_LCD && ENABLED(SHOW_BOOTSCREEN)
1049 1046
     ui.show_bootscreen();
1050 1047
   #endif
1051 1048
 
@@ -1143,6 +1140,9 @@ void loop() {
1143 1140
         #if ENABLED(POWER_LOSS_RECOVERY)
1144 1141
           card.removeJobRecoveryFile();
1145 1142
         #endif
1143
+        #ifdef EVENT_GCODE_SD_STOP
1144
+          enqueue_and_echo_commands_P(PSTR(EVENT_GCODE_SD_STOP));
1145
+        #endif
1146 1146
       }
1147 1147
     #endif // SDSUPPORT
1148 1148
 

+ 4
- 1
Marlin/src/core/boards.h View File

@@ -189,10 +189,11 @@
189 189
 #define BOARD_COHESION3D_REMIX    1755  // Cohesion3D ReMix
190 190
 #define BOARD_COHESION3D_MINI     1756  // Cohesion3D Mini
191 191
 #define BOARD_SMOOTHIEBOARD       1757  // Smoothieboard
192
-#define BOARD_AZTEEG_X5_MINI_WIFI 1758  // Azteeg X5 Mini (Power outputs: Hotend0, Bed, Fan)
192
+#define BOARD_AZTEEG_X5_MINI_WIFI 1758  // Azteeg X5 Mini Wifi (Power outputs: Hotend0, Bed, Fan)
193 193
 #define BOARD_BIQU_SKR_V1_1       1759  // BIQU SKR_V1.1 (Power outputs: Hotend0,Hotend1, Fan, Bed)
194 194
 #define BOARD_BIQU_B300_V1_0      1760  // BIQU B300_V1.0 (Power outputs: Hotend0, Fan, Bed, SPI Driver)
195 195
 #define BOARD_BIGTREE_SKR_V1_3    1761  // BIGTREE SKR_V1.3 (Power outputs: Hotend0, Hotend1, Fan, Bed)
196
+#define BOARD_AZTEEG_X5_MINI      1762  // Azteeg X5 Mini (Power outputs: Hotend0, Bed, Fan)
196 197
 
197 198
 //
198 199
 // SAM3X8E ARM Cortex M3
@@ -253,6 +254,8 @@
253 254
 #define BOARD_STM32F4          1804   // STM32 STM32GENERIC based STM32F4 controller
254 255
 #define BOARD_ARMED            1807   // Arm'ed STM32F4 based controller
255 256
 #define BOARD_RUMBA32          1809   // RUMBA32 STM32F4 based controller
257
+#define BOARD_BLACK_STM32F407VE 1810  // BLACK_STM32F407VE
258
+#define BOARD_BLACK_STM32F407ZE 1811  // BLACK_STM32F407ZE
256 259
 #define BOARD_STEVAL           1866   // STEVAL-3DP001V1 3D PRINTER BOARD
257 260
 
258 261
 //

+ 2
- 0
Marlin/src/core/debug_out.h View File

@@ -47,6 +47,7 @@
47 47
 #undef DEBUG_DELAY
48 48
 
49 49
 #if DEBUG_OUT
50
+  #define DEBUG_PRINT_P(P)        serialprintPGM(P)
50 51
   #define DEBUG_ECHO_START        SERIAL_ECHO_START
51 52
   #define DEBUG_ERROR_START       SERIAL_ERROR_START
52 53
   #define DEBUG_CHAR              SERIAL_CHAR
@@ -66,6 +67,7 @@
66 67
   #define DEBUG_XYZ               SERIAL_XYZ
67 68
   #define DEBUG_DELAY(ms)         serial_delay(ms)
68 69
 #else
70
+  #define DEBUG_PRINT_P(P)        NOOP
69 71
   #define DEBUG_ECHO_START()      NOOP
70 72
   #define DEBUG_ERROR_START()     NOOP
71 73
   #define DEBUG_CHAR(...)         NOOP

+ 38
- 13
Marlin/src/core/drivers.h View File

@@ -65,20 +65,45 @@
65 65
 
66 66
 #define AXIS_DRIVER_TYPE(A,T) AXIS_DRIVER_TYPE_##A(T)
67 67
 
68
-#define HAS_DRIVER(T)  (AXIS_DRIVER_TYPE_X(T)  || AXIS_DRIVER_TYPE_X2(T) || \
69
-                        AXIS_DRIVER_TYPE_Y(T)  || AXIS_DRIVER_TYPE_Y2(T) || \
70
-                        AXIS_DRIVER_TYPE_Z(T)  || AXIS_DRIVER_TYPE_Z2(T) || AXIS_DRIVER_TYPE_Z3(T) || \
71
-                        AXIS_DRIVER_TYPE_E0(T) || AXIS_DRIVER_TYPE_E1(T) || \
72
-                        AXIS_DRIVER_TYPE_E2(T) || AXIS_DRIVER_TYPE_E3(T) || \
73
-                        AXIS_DRIVER_TYPE_E4(T) || AXIS_DRIVER_TYPE_E5(T) )
68
+#define HAS_DRIVER(T) (    AXIS_DRIVER_TYPE_X(T)  || AXIS_DRIVER_TYPE_X2(T) \
69
+                        || AXIS_DRIVER_TYPE_Y(T)  || AXIS_DRIVER_TYPE_Y2(T) \
70
+                        || AXIS_DRIVER_TYPE_Z(T)  || AXIS_DRIVER_TYPE_Z2(T) || AXIS_DRIVER_TYPE_Z3(T) \
71
+                        || AXIS_DRIVER_TYPE_E0(T) || AXIS_DRIVER_TYPE_E1(T) \
72
+                        || AXIS_DRIVER_TYPE_E2(T) || AXIS_DRIVER_TYPE_E3(T) \
73
+                        || AXIS_DRIVER_TYPE_E4(T) || AXIS_DRIVER_TYPE_E5(T) )
74 74
 
75 75
 // Test for supported TMC drivers that require advanced configuration
76 76
 // Does not match standalone configurations
77
-#define HAS_TRINAMIC ( HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC2160) || HAS_DRIVER(TMC2208) || HAS_DRIVER(TMC2660) || HAS_DRIVER(TMC5130) || HAS_DRIVER(TMC5160) )
77
+#define HAS_TRINAMIC (    HAS_DRIVER(TMC2130) \
78
+                       || HAS_DRIVER(TMC2160) \
79
+                       || HAS_DRIVER(TMC2208) \
80
+                       || HAS_DRIVER(TMC2660) \
81
+                       || HAS_DRIVER(TMC5130) \
82
+                       || HAS_DRIVER(TMC5160) )
78 83
 
79
-#define AXIS_IS_TMC(A) ( AXIS_DRIVER_TYPE_##A(TMC2130) || \
80
-                         AXIS_DRIVER_TYPE_##A(TMC2160) || \
81
-                         AXIS_DRIVER_TYPE_##A(TMC2208) || \
82
-                         AXIS_DRIVER_TYPE_##A(TMC2660) || \
83
-                         AXIS_DRIVER_TYPE_##A(TMC5130) || \
84
-                         AXIS_DRIVER_TYPE_##A(TMC5160))
84
+#define AXIS_IS_TMC(A)   (    AXIS_DRIVER_TYPE(A,TMC2130) \
85
+                           || AXIS_DRIVER_TYPE(A,TMC2160) \
86
+                           || AXIS_DRIVER_TYPE(A,TMC2208) \
87
+                           || AXIS_DRIVER_TYPE(A,TMC2660) \
88
+                           || AXIS_DRIVER_TYPE(A,TMC5130) \
89
+                           || AXIS_DRIVER_TYPE(A,TMC5160) )
90
+
91
+// Test for a driver that uses SPI - this allows checking whether a _CS_ pin
92
+// is considered sensitive
93
+#define AXIS_HAS_SPI(A)  (    AXIS_DRIVER_TYPE(A,TMC2130) \
94
+                           || AXIS_DRIVER_TYPE(A,TMC2160) \
95
+                           || AXIS_DRIVER_TYPE(A,TMC2660) \
96
+                           || AXIS_DRIVER_TYPE(A,TMC5130) \
97
+                           || AXIS_DRIVER_TYPE(A,TMC5160) )
98
+
99
+#define AXIS_HAS_STALLGUARD(A)   (    AXIS_DRIVER_TYPE(A,TMC2130) \
100
+                                   || AXIS_DRIVER_TYPE(A,TMC2160) \
101
+                                   || AXIS_DRIVER_TYPE(A,TMC2660) \
102
+                                   || AXIS_DRIVER_TYPE(A,TMC5130) \
103
+                                   || AXIS_DRIVER_TYPE(A,TMC5160) )
104
+
105
+#define AXIS_HAS_STEALTHCHOP(A)  (    AXIS_DRIVER_TYPE(A,TMC2130) \
106
+                                   || AXIS_DRIVER_TYPE(A,TMC2160) \
107
+                                   || AXIS_DRIVER_TYPE(A,TMC2208) \
108
+                                   || AXIS_DRIVER_TYPE(A,TMC5130) \
109
+                                   || AXIS_DRIVER_TYPE(A,TMC5160) )

+ 6
- 0
Marlin/src/core/enum.h View File

@@ -39,6 +39,12 @@ enum AxisEnum : unsigned char {
39 39
   X_HEAD    = 4,
40 40
   Y_HEAD    = 5,
41 41
   Z_HEAD    = 6,
42
+  E0_AXIS   = 3,
43
+  E1_AXIS   = 4,
44
+  E2_AXIS   = 5,
45
+  E3_AXIS   = 6,
46
+  E4_AXIS   = 7,
47
+  E5_AXIS   = 8,
42 48
   ALL_AXES  = 0xFE,
43 49
   NO_AXIS   = 0xFF
44 50
 };

+ 18
- 17
Marlin/src/core/serial.cpp View File

@@ -22,6 +22,7 @@
22 22
 
23 23
 #include "serial.h"
24 24
 #include "language.h"
25
+#include "enum.h"
25 26
 
26 27
 uint8_t marlin_debug_flags = MARLIN_DEBUG_NONE;
27 28
 
@@ -49,8 +50,14 @@ void serial_echopair_PGM(PGM_P const s_P, unsigned long v) { serialprintPGM(s_P)
49 50
 
50 51
 void serial_spaces(uint8_t count) { count *= (PROPORTIONAL_FONT_RATIO); while (count--) SERIAL_CHAR(' '); }
51 52
 
53
+void serial_ternary(const bool onoff, PGM_P const pre, PGM_P const on, PGM_P const off, PGM_P const post/*=NULL*/) {
54
+  if (pre) serialprintPGM(pre);
55
+  serialprintPGM(onoff ? on : off);
56
+  if (post) serialprintPGM(post);
57
+}
52 58
 void serialprint_onoff(const bool onoff) { serialprintPGM(onoff ? PSTR(MSG_ON) : PSTR(MSG_OFF)); }
53 59
 void serialprintln_onoff(const bool onoff) { serialprint_onoff(onoff); SERIAL_EOL(); }
60
+void serialprint_truefalse(const bool tf) { serialprintPGM(tf ? PSTR("true") : PSTR("false")); }
54 61
 
55 62
 void print_bin(const uint16_t val) {
56 63
   uint16_t mask = 0x8000;
@@ -61,21 +68,15 @@ void print_bin(const uint16_t val) {
61 68
   }
62 69
 }
63 70
 
64
-#if ENABLED(DEBUG_LEVELING_FEATURE)
65
-
66
-  #include "enum.h"
67
-
68
-  void print_xyz(PGM_P const prefix, PGM_P const suffix, const float x, const float y, const float z) {
69
-    serialprintPGM(prefix);
70
-    SERIAL_CHAR('(');
71
-    SERIAL_ECHO(x);
72
-    SERIAL_ECHOPAIR(", ", y, ", ", z);
73
-    SERIAL_CHAR(')');
74
-    if (suffix) serialprintPGM(suffix); else SERIAL_EOL();
75
-  }
76
-
77
-  void print_xyz(PGM_P const prefix, PGM_P const suffix, const float xyz[]) {
78
-    print_xyz(prefix, suffix, xyz[X_AXIS], xyz[Y_AXIS], xyz[Z_AXIS]);
79
-  }
71
+void print_xyz(PGM_P const prefix, PGM_P const suffix, const float x, const float y, const float z) {
72
+  serialprintPGM(prefix);
73
+  SERIAL_CHAR('(');
74
+  SERIAL_ECHO(x);
75
+  SERIAL_ECHOPAIR(", ", y, ", ", z);
76
+  SERIAL_CHAR(')');
77
+  if (suffix) serialprintPGM(suffix); else SERIAL_EOL();
78
+}
80 79
 
81
-#endif
80
+void print_xyz(PGM_P const prefix, PGM_P const suffix, const float xyz[]) {
81
+  print_xyz(prefix, suffix, xyz[X_AXIS], xyz[Y_AXIS], xyz[Z_AXIS]);
82
+}

+ 6
- 9
Marlin/src/core/serial.h View File

@@ -174,18 +174,15 @@ inline void serial_echopair_PGM(PGM_P const s_P, void *v)   { serial_echopair_PG
174 174
 void serialprintPGM(PGM_P str);
175 175
 void serial_echo_start();
176 176
 void serial_error_start();
177
+void serial_ternary(const bool onoff, PGM_P const pre, PGM_P const on, PGM_P const off, PGM_P const post=NULL);
177 178
 void serialprint_onoff(const bool onoff);
178 179
 void serialprintln_onoff(const bool onoff);
180
+void serialprint_truefalse(const bool tf);
179 181
 void serial_spaces(uint8_t count);
180 182
 
181 183
 void print_bin(const uint16_t val);
182 184
 
183
-#if ENABLED(DEBUG_LEVELING_FEATURE)
184
-  void print_xyz(PGM_P const prefix, PGM_P const suffix, const float x, const float y, const float z);
185
-  void print_xyz(PGM_P const prefix, PGM_P const suffix, const float xyz[]);
186
-  #define SERIAL_POS(SUFFIX,VAR) do { print_xyz(PSTR("  " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n"), VAR); } while(0)
187
-  #define SERIAL_XYZ(PREFIX,...) do { print_xyz(PSTR(PREFIX), NULL, __VA_ARGS__); } while(0)
188
-#else
189
-  #define SERIAL_POS(...) NOOP
190
-  #define SERIAL_XYZ(...) NOOP
191
-#endif
185
+void print_xyz(PGM_P const prefix, PGM_P const suffix, const float x, const float y, const float z);
186
+void print_xyz(PGM_P const prefix, PGM_P const suffix, const float xyz[]);
187
+#define SERIAL_POS(SUFFIX,VAR) do { print_xyz(PSTR("  " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n"), VAR); } while(0)
188
+#define SERIAL_XYZ(PREFIX,...) do { print_xyz(PSTR(PREFIX), NULL, __VA_ARGS__); } while(0)

+ 18
- 5
Marlin/src/core/utility.cpp View File

@@ -58,11 +58,11 @@ void safe_delay(millis_t ms) {
58 58
   #define MINUSOR(n, alt) (n >= 0 ? (alt) : (n = -n, '-'))
59 59
 
60 60
   // Convert a full-range unsigned 8bit int to a percentage
61
-  char* ui8tostr_percent(const uint8_t i) {
62
-    const uint8_t percent = ui8_to_percent(i);
63
-    conv[3] = RJDIGIT(percent, 100);
64
-    conv[4] = RJDIGIT(percent, 10);
65
-    conv[5] = DIGIMOD(percent, 1);
61
+  char* ui8tostr4pct(const uint8_t i) {
62
+    const uint8_t n = ui8_to_percent(i);
63
+    conv[3] = RJDIGIT(n, 100);
64
+    conv[4] = RJDIGIT(n, 10);
65
+    conv[5] = DIGIMOD(n, 1);
66 66
     conv[6] = '%';
67 67
     return &conv[3];
68 68
   }
@@ -214,6 +214,19 @@ void safe_delay(millis_t ms) {
214 214
     return &conv[1];
215 215
   }
216 216
 
217
+  // Convert signed float to string (5 digit) with -1.2345 / _0.0000 / +1.2345 format
218
+  char* ftostr54sign(const float &f, char plus/*=' '*/) {
219
+    long i = (f * 100000 + (f < 0 ? -5: 5)) / 10;
220
+    conv[0] = i ? MINUSOR(i, plus) : ' ';
221
+    conv[1] = DIGIMOD(i, 10000);
222
+    conv[2] = '.';
223
+    conv[3] = DIGIMOD(i, 1000);
224
+    conv[4] = DIGIMOD(i, 100);
225
+    conv[5] = DIGIMOD(i, 10);
226
+    conv[6] = DIGIMOD(i, 1);
227
+    return &conv[0];
228
+  }
229
+
217 230
   // Convert unsigned float to rj string with 12345 format
218 231
   char* ftostr5rj(const float &f) {
219 232
     const long i = ((f < 0 ? -f : f) * 10 + 5) / 10;

+ 4
- 1
Marlin/src/core/utility.h View File

@@ -56,7 +56,7 @@ inline void serial_delay(const millis_t ms) {
56 56
 #if ANY(ULTRA_LCD, DEBUG_LEVELING_FEATURE, EXTENSIBLE_UI)
57 57
 
58 58
   // Convert a full-range unsigned 8bit int to a percentage
59
-  char* ui8tostr_percent(const uint8_t i);
59
+  char* ui8tostr4pct(const uint8_t i);
60 60
 
61 61
   // Convert uint8_t to string with 123 format
62 62
   char* ui8tostr3(const uint8_t x);
@@ -91,6 +91,9 @@ inline void serial_delay(const millis_t ms) {
91 91
   // Convert signed float to string (6 digit) with -1.234 / _0.000 / +1.234 format
92 92
   char* ftostr43sign(const float &x, char plus=' ');
93 93
 
94
+  // Convert signed float to string (5 digit) with -1.2345 / _0.0000 / +1.2345 format
95
+  char* ftostr54sign(const float &x, char plus=' ');
96
+
94 97
   // Convert unsigned float to rj string with 12345 format
95 98
   char* ftostr5rj(const float &x);
96 99
 

+ 6
- 6
Marlin/src/feature/I2CPositionEncoder.cpp View File

@@ -38,6 +38,8 @@
38 38
 #include "../module/stepper.h"
39 39
 #include "../gcode/parser.h"
40 40
 
41
+#include "../feature/babystep.h"
42
+
41 43
 #include <Wire.h>
42 44
 
43 45
 void I2CPositionEncoder::init(const uint8_t address, const AxisEnum axis) {
@@ -169,7 +171,7 @@ void I2CPositionEncoder::update() {
169 171
             const int32_t errorP = int32_t(sumP * (1.0f / (I2CPE_ERR_PRST_ARRAY_SIZE)));
170 172
             SERIAL_ECHO(axis_codes[encoderAxis]);
171 173
             SERIAL_ECHOLNPAIR(" - err detected: ", errorP * planner.steps_to_mm[encoderAxis], "mm; correcting!");
172
-            thermalManager.babystepsTodo[encoderAxis] = -LROUND(errorP);
174
+            babystep.add_steps(encoderAxis, -LROUND(errorP));
173 175
             errPrstIdx = 0;
174 176
           }
175 177
         }
@@ -180,7 +182,7 @@ void I2CPositionEncoder::update() {
180 182
       if (ABS(error) > threshold * planner.settings.axis_steps_per_mm[encoderAxis]) {
181 183
         //SERIAL_ECHOLN(error);
182 184
         //SERIAL_ECHOLN(position);
183
-        thermalManager.babystepsTodo[encoderAxis] = -LROUND(error / 2);
185
+        babystep.add_steps(encoderAxis, -LROUND(error / 2));
184 186
       }
185 187
     #endif
186 188
 
@@ -227,13 +229,11 @@ bool I2CPositionEncoder::passes_test(const bool report) {
227 229
   if (report) {
228 230
     if (H != I2CPE_MAG_SIG_GOOD) SERIAL_ECHOPGM("Warning. ");
229 231
     SERIAL_ECHO(axis_codes[encoderAxis]);
230
-    SERIAL_ECHOPGM(" axis ");
231
-    serialprintPGM(H == I2CPE_MAG_SIG_BAD ? PSTR("magnetic strip ") : PSTR("encoder "));
232
+    serial_ternary(H == I2CPE_MAG_SIG_BAD, PSTR(" axis "), PSTR("magnetic strip "), PSTR("encoder "));
232 233
     switch (H) {
233 234
       case I2CPE_MAG_SIG_GOOD:
234 235
       case I2CPE_MAG_SIG_MID:
235
-        SERIAL_ECHOLNPGM("passes test; field strength ");
236
-        serialprintPGM(H == I2CPE_MAG_SIG_GOOD ? PSTR("good.\n") : PSTR("fair.\n"));
236
+        serial_ternary(H == I2CPE_MAG_SIG_GOOD, PSTR("passes test; field strength "), PSTR("good"), PSTR("fair"), PSTR(".\n"));
237 237
         break;
238 238
       default:
239 239
         SERIAL_ECHOLNPGM("not detected!");

+ 2
- 3
Marlin/src/feature/I2CPositionEncoder.h View File

@@ -275,9 +275,8 @@ class I2CPositionEncodersMgr {
275 275
     static void enable_ec(const int8_t idx, const bool enabled, const AxisEnum axis) {
276 276
       CHECK_IDX();
277 277
       encoders[idx].set_ec_enabled(enabled);
278
-      SERIAL_ECHOPAIR("Error correction on ", axis_codes[axis], " axis is ");
279
-      serialprintPGM(encoders[idx].get_ec_enabled() ? PSTR("en") : PSTR("dis"));
280
-      SERIAL_ECHOLNPGM("abled.");
278
+      SERIAL_ECHOPAIR("Error correction on ", axis_codes[axis]);
279
+      serial_ternary(encoders[idx].get_ec_enabled(), PSTR(" axis is "), PSTR("en"), PSTR("dis"), PSTR("abled.\n"));
281 280
     }
282 281
 
283 282
     static void set_ec_threshold(const int8_t idx, const float newThreshold, const AxisEnum axis) {

+ 135
- 0
Marlin/src/feature/babystep.cpp View File

@@ -0,0 +1,135 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+#include "../inc/MarlinConfig.h"
24
+
25
+#if ENABLED(BABYSTEPPING)
26
+
27
+#include "babystep.h"
28
+#include "../Marlin.h"
29
+#include "../module/planner.h"
30
+#include "../module/stepper.h"
31
+
32
+#if ENABLED(BABYSTEP_ALWAYS_AVAILABLE)
33
+  #include "../gcode/gcode.h"
34
+#endif
35
+
36
+Babystep babystep;
37
+
38
+volatile int16_t Babystep::todo[BS_TODO_AXIS(Z_AXIS) + 1];
39
+
40
+#if HAS_LCD_MENU
41
+  int16_t Babystep::accum;
42
+  #if ENABLED(BABYSTEP_DISPLAY_TOTAL)
43
+    int16_t Babystep::axis_total[BS_TOTAL_AXIS(Z_AXIS) + 1];
44
+  #endif
45
+#endif
46
+
47
+void Babystep::step_axis(const AxisEnum axis) {
48
+  const int16_t curTodo = todo[BS_TODO_AXIS(axis)]; // get rid of volatile for performance
49
+  if (curTodo) {
50
+    stepper.babystep((AxisEnum)axis, curTodo > 0);
51
+    if (curTodo > 0) todo[BS_TODO_AXIS(axis)]--; else todo[BS_TODO_AXIS(axis)]++;
52
+  }
53
+}
54
+
55
+void Babystep::task() {
56
+  #if EITHER(BABYSTEP_XY, I2C_POSITION_ENCODERS)
57
+    LOOP_XYZ(axis) step_axis((AxisEnum)axis);
58
+  #else
59
+    step_axis(Z_AXIS);
60
+  #endif
61
+}
62
+
63
+void Babystep::add_mm(const AxisEnum axis, const float &mm) {
64
+  add_steps(axis, mm * planner.settings.axis_steps_per_mm[axis]);
65
+}
66
+
67
+void Babystep::add_steps(const AxisEnum axis, const int32_t distance) {
68
+
69
+  #if ENABLED(BABYSTEP_WITHOUT_HOMING)
70
+    #define CAN_BABYSTEP(AXIS) true
71
+  #else
72
+    extern uint8_t axis_known_position;
73
+    #define CAN_BABYSTEP(AXIS) TEST(axis_known_position, AXIS)
74
+  #endif
75
+
76
+  if (!CAN_BABYSTEP(axis)) return;
77
+
78
+  #if HAS_LCD_MENU
79
+    accum += distance; // Count up babysteps for the UI
80
+    #if ENABLED(BABYSTEP_DISPLAY_TOTAL)
81
+      axis_total[BS_TOTAL_AXIS(axis)] += distance;
82
+    #endif
83
+  #endif
84
+
85
+  #if ENABLED(BABYSTEP_ALWAYS_AVAILABLE)
86
+    #define BSA_ENABLE(AXIS) do{ switch (AXIS) { case X_AXIS: enable_X(); break; case Y_AXIS: enable_Y(); break; case Z_AXIS: enable_Z(); } }while(0)
87
+  #else
88
+    #define BSA_ENABLE(AXIS) NOOP
89
+  #endif
90
+
91
+  #if IS_CORE
92
+    #if ENABLED(BABYSTEP_XY)
93
+      switch (axis) {
94
+        case CORE_AXIS_1: // X on CoreXY and CoreXZ, Y on CoreYZ
95
+          BSA_ENABLE(CORE_AXIS_1);
96
+          BSA_ENABLE(CORE_AXIS_2);
97
+          todo[CORE_AXIS_1] += distance * 2;
98
+          todo[CORE_AXIS_2] += distance * 2;
99
+          break;
100
+        case CORE_AXIS_2: // Y on CoreXY, Z on CoreXZ and CoreYZ
101
+          BSA_ENABLE(CORE_AXIS_1);
102
+          BSA_ENABLE(CORE_AXIS_2);
103
+          todo[CORE_AXIS_1] += CORESIGN(distance * 2);
104
+          todo[CORE_AXIS_2] -= CORESIGN(distance * 2);
105
+          break;
106
+        case NORMAL_AXIS: // Z on CoreXY, Y on CoreXZ, X on CoreYZ
107
+        default:
108
+          BSA_ENABLE(NORMAL_AXIS);
109
+          todo[NORMAL_AXIS] += distance;
110
+          break;
111
+      }
112
+    #elif CORE_IS_XZ || CORE_IS_YZ
113
+      // Only Z stepping needs to be handled here
114
+      BSA_ENABLE(CORE_AXIS_1);
115
+      BSA_ENABLE(CORE_AXIS_2);
116
+      todo[CORE_AXIS_1] += CORESIGN(distance * 2);
117
+      todo[CORE_AXIS_2] -= CORESIGN(distance * 2);
118
+    #else
119
+      BSA_ENABLE(Z_AXIS);
120
+      todo[Z_AXIS] += distance;
121
+    #endif
122
+  #else
123
+    #if ENABLED(BABYSTEP_XY)
124
+      BSA_ENABLE(axis);
125
+    #else
126
+      BSA_ENABLE(Z_AXIS);
127
+    #endif
128
+    todo[BS_TODO_AXIS(axis)] += distance;
129
+  #endif
130
+  #if ENABLED(BABYSTEP_ALWAYS_AVAILABLE)
131
+    gcode.reset_stepper_timeout();
132
+  #endif
133
+}
134
+
135
+#endif // BABYSTEPPING

+ 63
- 0
Marlin/src/feature/babystep.h View File

@@ -0,0 +1,63 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+#pragma once
23
+
24
+#include "../inc/MarlinConfigPre.h"
25
+#include "../core/enum.h"
26
+
27
+#if IS_CORE || EITHER(BABYSTEP_XY, I2C_POSITION_ENCODERS)
28
+  #define BS_TODO_AXIS(A) A
29
+#else
30
+  #define BS_TODO_AXIS(A) 0
31
+#endif
32
+
33
+#if HAS_LCD_MENU && ENABLED(BABYSTEP_DISPLAY_TOTAL)
34
+  #if ENABLED(BABYSTEP_XY)
35
+    #define BS_TOTAL_AXIS(A) A
36
+  #else
37
+    #define BS_TOTAL_AXIS(A) 0
38
+  #endif
39
+#endif
40
+
41
+class Babystep {
42
+public:
43
+  static volatile int16_t todo[BS_TODO_AXIS(Z_AXIS) + 1];
44
+  #if HAS_LCD_MENU
45
+    static int16_t accum;                                     // Total babysteps in current edit
46
+    #if ENABLED(BABYSTEP_DISPLAY_TOTAL)
47
+      static int16_t axis_total[BS_TOTAL_AXIS(Z_AXIS) + 1];   // Total babysteps since G28
48
+      static inline void reset_total(const AxisEnum axis) {
49
+        #if ENABLED(BABYSTEP_XY)
50
+          if (axis == Z_AXIS)
51
+        #endif
52
+            axis_total[BS_TOTAL_AXIS(axis)] = 0;
53
+      }
54
+    #endif
55
+  #endif
56
+  static void add_steps(const AxisEnum axis, const int32_t distance);
57
+  static void add_mm(const AxisEnum axis, const float &mm);
58
+  static void task();
59
+private:
60
+  static void step_axis(const AxisEnum axis);
61
+};
62
+
63
+extern Babystep babystep;

+ 0
- 4
Marlin/src/feature/bedlevel/bedlevel.cpp View File

@@ -42,10 +42,6 @@
42 42
 #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE)
43 43
 #include "../../core/debug_out.h"
44 44
 
45
-#if ENABLED(G26_MESH_VALIDATION)
46
-  bool g26_debug_flag; // = false
47
-#endif
48
-
49 45
 bool leveling_is_valid() {
50 46
   return
51 47
     #if ENABLED(MESH_BED_LEVELING)

+ 0
- 6
Marlin/src/feature/bedlevel/bedlevel.h View File

@@ -28,12 +28,6 @@ typedef struct {
28 28
   float distance; // When populated, the distance from the search location
29 29
 } mesh_index_pair;
30 30
 
31
-#if ENABLED(G26_MESH_VALIDATION)
32
-  extern bool g26_debug_flag;
33
-#else
34
-  constexpr bool g26_debug_flag = false;
35
-#endif
36
-
37 31
 #if ENABLED(PROBE_MANUALLY)
38 32
   extern bool g29_in_progress;
39 33
 #else

+ 2
- 2
Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp View File

@@ -49,8 +49,8 @@
49 49
     ZERO(z_values);
50 50
     #if ENABLED(EXTENSIBLE_UI)
51 51
       for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++)
52
-        for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) 
53
-            ExtUI::onMeshUpdate(x, y, 0);
52
+        for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++)
53
+          ExtUI::onMeshUpdate(x, y, 0);
54 54
     #endif
55 55
   }
56 56
 

+ 4
- 48
Marlin/src/feature/bedlevel/ubl/ubl.cpp View File

@@ -35,7 +35,7 @@
35 35
   #if ENABLED(EXTENSIBLE_UI)
36 36
     #include "../../../lcd/extensible_ui/ui_api.h"
37 37
   #endif
38
-  
38
+
39 39
   #include "math.h"
40 40
 
41 41
   void unified_bed_leveling::echo_name() {
@@ -58,54 +58,10 @@
58 58
 
59 59
   void unified_bed_leveling::report_state() {
60 60
     echo_name();
61
-    SERIAL_ECHOPGM(" System v" UBL_VERSION " ");
62
-    if (!planner.leveling_active) SERIAL_ECHOPGM("in");
63
-    SERIAL_ECHOLNPGM("active.");
61
+    serial_ternary(planner.leveling_active, PSTR(" System v" UBL_VERSION " "), PSTR(""), PSTR("in"), PSTR("active\n"));
64 62
     serial_delay(50);
65 63
   }
66 64
 
67
-  #if ENABLED(UBL_DEVEL_DEBUGGING)
68
-
69
-    static void debug_echo_axis(const AxisEnum axis) {
70
-      if (current_position[axis] == destination[axis])
71
-        SERIAL_ECHOPGM("-------------");
72
-      else
73
-        SERIAL_ECHO_F(destination[X_AXIS], 6);
74
-    }
75
-
76
-    void debug_current_and_destination(PGM_P title) {
77
-
78
-      // if the title message starts with a '!' it is so important, we are going to
79
-      // ignore the status of the g26_debug_flag
80
-      if (*title != '!' && !g26_debug_flag) return;
81
-
82
-      const float de = destination[E_AXIS] - current_position[E_AXIS];
83
-
84
-      if (de == 0.0) return; // Printing moves only
85
-
86
-      const float dx = destination[X_AXIS] - current_position[X_AXIS],
87
-                  dy = destination[Y_AXIS] - current_position[Y_AXIS],
88
-                  xy_dist = HYPOT(dx, dy);
89
-
90
-      if (xy_dist == 0.0) return;
91
-
92
-      const float fpmm = de / xy_dist;
93
-      SERIAL_ECHOPAIR_F("   fpmm=", fpmm, 6);
94
-      SERIAL_ECHOPAIR_F("    current=( ", current_position[X_AXIS], 6);
95
-      SERIAL_ECHOPAIR_F(", ", current_position[Y_AXIS], 6);
96
-      SERIAL_ECHOPAIR_F(", ", current_position[Z_AXIS], 6);
97
-      SERIAL_ECHOPAIR_F(", ", current_position[E_AXIS], 6);
98
-      SERIAL_ECHOPGM(" )   destination=( "); debug_echo_axis(X_AXIS);
99
-      SERIAL_ECHOPGM(", "); debug_echo_axis(Y_AXIS);
100
-      SERIAL_ECHOPGM(", "); debug_echo_axis(Z_AXIS);
101
-      SERIAL_ECHOPGM(", "); debug_echo_axis(E_AXIS);
102
-      SERIAL_ECHOPGM(" )   ");
103
-      serialprintPGM(title);
104
-      SERIAL_EOL();
105
-    }
106
-
107
-  #endif // UBL_DEVEL_DEBUGGING
108
-
109 65
   int8_t unified_bed_leveling::storage_slot;
110 66
 
111 67
   float unified_bed_leveling::z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y];
@@ -135,8 +91,8 @@
135 91
     ZERO(z_values);
136 92
     #if ENABLED(EXTENSIBLE_UI)
137 93
       for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++)
138
-        for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) 
139
-            ExtUI::onMeshUpdate(x, y, 0);
94
+        for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++)
95
+          ExtUI::onMeshUpdate(x, y, 0);
140 96
     #endif
141 97
     if (was_enabled) report_current_position();
142 98
   }

+ 0
- 8
Marlin/src/feature/bedlevel/ubl/ubl.h View File

@@ -39,14 +39,6 @@
39 39
 #define USE_NOZZLE_AS_REFERENCE 0
40 40
 #define USE_PROBE_AS_REFERENCE 1
41 41
 
42
-// ubl_motion.cpp
43
-
44
-#if ENABLED(UBL_DEVEL_DEBUGGING)
45
-  void debug_current_and_destination(PGM_P const title);
46
-#else
47
-  FORCE_INLINE void debug_current_and_destination(PGM_P const title) { UNUSED(title); }
48
-#endif
49
-
50 42
 // ubl_G29.cpp
51 43
 
52 44
 enum MeshPointType : char { INVALID, REAL, SET_IN_BITMAP };

+ 2
- 6
Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp View File

@@ -24,8 +24,6 @@
24 24
 
25 25
 #if ENABLED(AUTO_BED_LEVELING_UBL)
26 26
 
27
-  //#define UBL_DEVEL_DEBUGGING
28
-
29 27
   #include "ubl.h"
30 28
 
31 29
   #include "../../../Marlin.h"
@@ -765,14 +763,12 @@
765 763
 
766 764
         if (location.x_index >= 0) {    // mesh point found and is reachable by probe
767 765
           const float rawx = mesh_index_to_xpos(location.x_index),
768
-                      rawy = mesh_index_to_ypos(location.y_index);
769
-
770
-          const float measured_z = probe_pt(rawx, rawy, stow_probe ? PROBE_PT_STOW : PROBE_PT_RAISE, g29_verbose_level); // TODO: Needs error handling
766
+                      rawy = mesh_index_to_ypos(location.y_index),
767
+                      measured_z = probe_pt(rawx, rawy, stow_probe ? PROBE_PT_STOW : PROBE_PT_RAISE, g29_verbose_level); // TODO: Needs error handling
771 768
           z_values[location.x_index][location.y_index] = measured_z;
772 769
           #if ENABLED(EXTENSIBLE_UI)
773 770
             ExtUI::onMeshUpdate(location.x_index, location.y_index, measured_z);
774 771
           #endif
775
-          
776 772
         }
777 773
         SERIAL_FLUSH(); // Prevent host M105 buffer overrun.
778 774
       } while (location.x_index >= 0 && --count);

+ 0
- 26
Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp View File

@@ -64,17 +64,6 @@
64 64
               cell_dest_xi  = get_cell_index_x(end[X_AXIS]),
65 65
               cell_dest_yi  = get_cell_index_y(end[Y_AXIS]);
66 66
 
67
-    if (g26_debug_flag) {
68
-      SERIAL_ECHOLNPAIR(
69
-        " ubl.line_to_destination_cartesian(xe=", destination[X_AXIS],
70
-        ", ye=", destination[Y_AXIS],
71
-        ", ze=", destination[Z_AXIS],
72
-        ", ee=", destination[E_AXIS],
73
-        ")"
74
-      );
75
-      debug_current_and_destination(PSTR("Start of ubl.line_to_destination_cartesian()"));
76
-    }
77
-
78 67
     // A move within the same cell needs no splitting
79 68
     if (cell_start_xi == cell_dest_xi && cell_start_yi == cell_dest_yi) {
80 69
 
@@ -93,9 +82,6 @@
93 82
         planner.buffer_segment(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + z_raise, end[E_AXIS], feed_rate, extruder);
94 83
         set_current_from_destination();
95 84
 
96
-        if (g26_debug_flag)
97
-          debug_current_and_destination(PSTR("out of bounds in ubl.line_to_destination_cartesian()"));
98
-
99 85
         return;
100 86
       }
101 87
 
@@ -119,9 +105,6 @@
119 105
       // Replace NAN corrections with 0.0 to prevent NAN propagation.
120 106
       planner.buffer_segment(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + (isnan(z0) ? 0.0 : z0), end[E_AXIS], feed_rate, extruder);
121 107
 
122
-      if (g26_debug_flag)
123
-        debug_current_and_destination(PSTR("FINAL_MOVE in ubl.line_to_destination_cartesian()"));
124
-
125 108
       set_current_from_destination();
126 109
       return;
127 110
     }
@@ -215,9 +198,6 @@
215 198
         } //else printf("FIRST MOVE PRUNED  ");
216 199
       }
217 200
 
218
-      if (g26_debug_flag)
219
-        debug_current_and_destination(PSTR("vertical move done in ubl.line_to_destination_cartesian()"));
220
-
221 201
       // At the final destination? Usually not, but when on a Y Mesh Line it's completed.
222 202
       if (current_position[X_AXIS] != end[X_AXIS] || current_position[Y_AXIS] != end[Y_AXIS])
223 203
         goto FINAL_MOVE;
@@ -267,9 +247,6 @@
267 247
         } //else printf("FIRST MOVE PRUNED  ");
268 248
       }
269 249
 
270
-      if (g26_debug_flag)
271
-        debug_current_and_destination(PSTR("horizontal move done in ubl.line_to_destination_cartesian()"));
272
-
273 250
       if (current_position[X_AXIS] != end[X_AXIS] || current_position[Y_AXIS] != end[Y_AXIS])
274 251
         goto FINAL_MOVE;
275 252
 
@@ -353,9 +330,6 @@
353 330
       if (xi_cnt < 0 || yi_cnt < 0) break; // Too far! Exit the loop and go to FINAL_MOVE
354 331
     }
355 332
 
356
-    if (g26_debug_flag)
357
-      debug_current_and_destination(PSTR("generic move done in ubl.line_to_destination_cartesian()"));
358
-
359 333
     if (current_position[X_AXIS] != end[X_AXIS] || current_position[Y_AXIS] != end[Y_AXIS])
360 334
       goto FINAL_MOVE;
361 335
 

+ 3
- 0
Marlin/src/feature/digipot/digipot_mcp4451.cpp View File

@@ -35,6 +35,9 @@
35 35
 #if MB(5DPRINT)
36 36
   #define DIGIPOT_I2C_FACTOR 117.96
37 37
   #define DIGIPOT_I2C_MAX_CURRENT 1.736
38
+#elif MB(AZTEEG_X5_MINI) || MB(AZTEEG_X5_MINI_WIFI)
39
+  #define DIGIPOT_I2C_FACTOR 113.5
40
+  #define DIGIPOT_I2C_MAX_CURRENT 2.0
38 41
 #else
39 42
   #define DIGIPOT_I2C_FACTOR 106.7
40 43
   #define DIGIPOT_I2C_MAX_CURRENT 2.5

+ 1
- 1
Marlin/src/feature/host_actions.cpp View File

@@ -1,6 +1,6 @@
1 1
 /**
2 2
  * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
3
+ * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4 4
  *
5 5
  * Based on Sprinter and grbl.
6 6
  * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm

+ 1
- 1
Marlin/src/feature/host_actions.h View File

@@ -1,6 +1,6 @@
1 1
 /**
2 2
  * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
3
+ * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4 4
  *
5 5
  * Based on Sprinter and grbl.
6 6
  * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm

+ 20
- 11
Marlin/src/feature/leds/leds.h View File

@@ -120,19 +120,28 @@ typedef struct LEDColor {
120 120
   #else
121 121
     #define MakeLEDColor(R,G,B,W,I) LEDColor(R, G, B, W)
122 122
   #endif
123
-  #define LEDColorWhite() LEDColor(0, 0, 0, 255)
124 123
 #else
125
-  #define MakeLEDColor(R,G,B,W,I) LEDColor(R, G, B)
126
-  #define LEDColorWhite() LEDColor(255, 255, 255)
124
+  #define MakeLEDColor(R,G,B,W,I)   LEDColor(R, G, B)
125
+#endif
126
+
127
+#define LEDColorOff()             LEDColor(  0,   0,   0)
128
+#define LEDColorRed()             LEDColor(255,   0,   0)
129
+#if ENABLED(LED_COLORS_REDUCE_GREEN)
130
+  #define LEDColorOrange()        LEDColor(255,  25,   0)
131
+  #define LEDColorYellow()        LEDColor(255,  75,   0)
132
+#else
133
+  #define LEDColorOrange()        LEDColor(255,  80,   0)
134
+  #define LEDColorYellow()        LEDColor(255, 255,   0)
135
+#endif
136
+#define LEDColorGreen()           LEDColor(  0, 255,   0)
137
+#define LEDColorBlue()            LEDColor(  0,   0, 255)
138
+#define LEDColorIndigo()          LEDColor(  0, 255, 255)
139
+#define LEDColorViolet()          LEDColor(255,   0, 255)
140
+#if HAS_WHITE_LED
141
+  #define LEDColorWhite()         LEDColor(  0,   0,   0, 255)
142
+#else
143
+  #define LEDColorWhite()         LEDColor(255, 255, 255)
127 144
 #endif
128
-#define LEDColorOff()     LEDColor(  0,   0,   0)
129
-#define LEDColorRed()     LEDColor(255,   0,   0)
130
-#define LEDColorOrange()  LEDColor(255,  80,   0)
131
-#define LEDColorYellow()  LEDColor(255, 255,   0)
132
-#define LEDColorGreen()   LEDColor(  0, 255,   0)
133
-#define LEDColorBlue()    LEDColor(  0,   0, 255)
134
-#define LEDColorIndigo()  LEDColor(  0, 255, 255)
135
-#define LEDColorViolet()  LEDColor(255,   0, 255)
136 145
 
137 146
 class LEDLights {
138 147
 public:

+ 40
- 44
Marlin/src/feature/power_loss_recovery.cpp View File

@@ -50,6 +50,9 @@ job_recovery_info_t PrintJobRecovery::info;
50 50
   #include "fwretract.h"
51 51
 #endif
52 52
 
53
+#define DEBUG_OUT ENABLED(DEBUG_POWER_LOSS_RECOVERY)
54
+#include "../core/debug_out.h"
55
+
53 56
 PrintJobRecovery recovery;
54 57
 
55 58
 /**
@@ -110,9 +113,7 @@ void PrintJobRecovery::load() {
110 113
     (void)file.read(&info, sizeof(info));
111 114
     close();
112 115
   }
113
-  #if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
114
-    debug(PSTR("Load"));
115
-  #endif
116
+  debug(PSTR("Load"));
116 117
 }
117 118
 
118 119
 /**
@@ -125,6 +126,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const bool save_queue/*=
125 126
     millis_t ms = millis();
126 127
   #endif
127 128
 
129
+  // Did Z change since the last call?
128 130
   if (force
129 131
     #if DISABLED(SAVE_EACH_CMD_MODE)      // Always save state when enabled
130 132
       #if PIN_EXISTS(POWER_LOSS)          // Save if power loss pin is triggered
@@ -133,8 +135,8 @@ void PrintJobRecovery::save(const bool force/*=false*/, const bool save_queue/*=
133 135
       #if SAVE_INFO_INTERVAL_MS > 0       // Save if interval is elapsed
134 136
         || ELAPSED(ms, next_save_ms)
135 137
       #endif
136
-      // Save every time Z is higher than the last call
137
-      || current_position[Z_AXIS] > info.current_position[Z_AXIS]
138
+        // Save every time Z is higher than the last call
139
+        || current_position[Z_AXIS] > info.current_position[Z_AXIS]
138 140
     #endif
139 141
   ) {
140 142
 
@@ -215,20 +217,14 @@ void PrintJobRecovery::save(const bool force/*=false*/, const bool save_queue/*=
215 217
  */
216 218
 void PrintJobRecovery::write() {
217 219
 
218
-  #if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
219
-    debug(PSTR("Write"));
220
-  #endif
220
+  debug(PSTR("Write"));
221 221
 
222 222
   open(false);
223 223
   file.seekSet(0);
224 224
   const int16_t ret = file.write(&info, sizeof(info));
225 225
   close();
226 226
 
227
-  #if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
228
-    if (ret == -1) SERIAL_ECHOLNPGM("Power-loss file write failed.");
229
-  #else
230
-    UNUSED(ret);
231
-  #endif
227
+  if (ret == -1) DEBUG_ECHOLNPGM("Power-loss file write failed.");
232 228
 }
233 229
 
234 230
 /**
@@ -366,65 +362,65 @@ void PrintJobRecovery::resume() {
366 362
 #if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
367 363
 
368 364
   void PrintJobRecovery::debug(PGM_P const prefix) {
369
-    serialprintPGM(prefix);
370
-    SERIAL_ECHOLNPAIR(" Job Recovery Info...\nvalid_head:", int(info.valid_head), " valid_foot:", int(info.valid_foot));
365
+    DEBUG_PRINT_P(prefix);
366
+    DEBUG_ECHOLNPAIR(" Job Recovery Info...\nvalid_head:", int(info.valid_head), " valid_foot:", int(info.valid_foot));
371 367
     if (info.valid_head) {
372 368
       if (info.valid_head == info.valid_foot) {
373
-        SERIAL_ECHOPGM("current_position: ");
369
+        DEBUG_ECHOPGM("current_position: ");
374 370
         LOOP_XYZE(i) {
375
-          SERIAL_ECHO(info.current_position[i]);
376
-          if (i < E_AXIS) SERIAL_CHAR(',');
371
+          if (i) DEBUG_CHAR(',');
372
+          DEBUG_ECHO(info.current_position[i]);
377 373
         }
378
-        SERIAL_EOL();
379
-        SERIAL_ECHOLNPAIR("feedrate: ", info.feedrate);
374
+        DEBUG_EOL();
375
+        DEBUG_ECHOLNPAIR("feedrate: ", info.feedrate);
380 376
 
381 377
         #if HOTENDS > 1
382
-          SERIAL_ECHOLNPAIR("active_hotend: ", int(info.active_hotend));
378
+          DEBUG_ECHOLNPAIR("active_hotend: ", int(info.active_hotend));
383 379
         #endif
384 380
 
385
-        SERIAL_ECHOPGM("target_temperature: ");
381
+        DEBUG_ECHOPGM("target_temperature: ");
386 382
         HOTEND_LOOP() {
387
-          SERIAL_ECHO(info.target_temperature[e]);
388
-          if (e < HOTENDS - 1) SERIAL_CHAR(',');
383
+          DEBUG_ECHO(info.target_temperature[e]);
384
+          if (e < HOTENDS - 1) DEBUG_CHAR(',');
389 385
         }
390
-        SERIAL_EOL();
386
+        DEBUG_EOL();
391 387
 
392 388
         #if HAS_HEATED_BED
393
-          SERIAL_ECHOLNPAIR("target_temperature_bed: ", info.target_temperature_bed);
389
+          DEBUG_ECHOLNPAIR("target_temperature_bed: ", info.target_temperature_bed);
394 390
         #endif
395 391
 
396 392
         #if FAN_COUNT
397
-          SERIAL_ECHOPGM("fan_speed: ");
393
+          DEBUG_ECHOPGM("fan_speed: ");
398 394
           FANS_LOOP(i) {
399
-            SERIAL_ECHO(int(info.fan_speed[i]));
400
-            if (i < FAN_COUNT - 1) SERIAL_CHAR(',');
395
+            DEBUG_ECHO(int(info.fan_speed[i]));
396
+            if (i < FAN_COUNT - 1) DEBUG_CHAR(',');
401 397
           }
402
-          SERIAL_EOL();
398
+          DEBUG_EOL();
403 399
         #endif
404 400
 
405 401
         #if HAS_LEVELING
406
-          SERIAL_ECHOLNPAIR("leveling: ", int(info.leveling), "\n fade: ", int(info.fade));
402
+          DEBUG_ECHOLNPAIR("leveling: ", int(info.leveling), "\n fade: ", int(info.fade));
407 403
         #endif
408 404
         #if ENABLED(FWRETRACT)
409
-          SERIAL_ECHOPGM("retract: ");
405
+          DEBUG_ECHOPGM("retract: ");
410 406
           for (int8_t e = 0; e < EXTRUDERS; e++) {
411
-            SERIAL_ECHO(info.retract[e]);
412
-            if (e < EXTRUDERS - 1) SERIAL_CHAR(',');
407
+            DEBUG_ECHO(info.retract[e]);
408
+            if (e < EXTRUDERS - 1) DEBUG_CHAR(',');
413 409
           }
414
-          SERIAL_EOL();
415
-          SERIAL_ECHOLNPAIR("retract_hop: ", info.retract_hop);
410
+          DEBUG_EOL();
411
+          DEBUG_ECHOLNPAIR("retract_hop: ", info.retract_hop);
416 412
         #endif
417
-        SERIAL_ECHOLNPAIR("cmd_queue_index_r: ", int(info.cmd_queue_index_r));
418
-        SERIAL_ECHOLNPAIR("commands_in_queue: ", int(info.commands_in_queue));
419
-        for (uint8_t i = 0; i < info.commands_in_queue; i++) SERIAL_ECHOLNPAIR("> ", info.command_queue[i]);
420
-        SERIAL_ECHOLNPAIR("sd_filename: ", info.sd_filename);
421
-        SERIAL_ECHOLNPAIR("sdpos: ", info.sdpos);
422
-        SERIAL_ECHOLNPAIR("print_job_elapsed: ", info.print_job_elapsed);
413
+        DEBUG_ECHOLNPAIR("cmd_queue_index_r: ", int(info.cmd_queue_index_r));
414
+        DEBUG_ECHOLNPAIR("commands_in_queue: ", int(info.commands_in_queue));
415
+        for (uint8_t i = 0; i < info.commands_in_queue; i++) DEBUG_ECHOLNPAIR("> ", info.command_queue[i]);
416
+        DEBUG_ECHOLNPAIR("sd_filename: ", info.sd_filename);
417
+        DEBUG_ECHOLNPAIR("sdpos: ", info.sdpos);
418
+        DEBUG_ECHOLNPAIR("print_job_elapsed: ", info.print_job_elapsed);
423 419
       }
424 420
       else
425
-        SERIAL_ECHOLNPGM("INVALID DATA");
421
+        DEBUG_ECHOLNPGM("INVALID DATA");
426 422
     }
427
-    SERIAL_ECHOLNPGM("---");
423
+    DEBUG_ECHOLNPGM("---");
428 424
   }
429 425
 
430 426
 #endif // DEBUG_POWER_LOSS_RECOVERY

+ 5
- 3
Marlin/src/feature/power_loss_recovery.h View File

@@ -125,9 +125,11 @@ class PrintJobRecovery {
125 125
 
126 126
   static inline bool valid() { return info.valid_head && info.valid_head == info.valid_foot; }
127 127
 
128
-    #if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
129
-      static void debug(PGM_P const prefix);
130
-    #endif
128
+  #if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
129
+    static void debug(PGM_P const prefix);
130
+  #else
131
+    static inline void debug(PGM_P const prefix) { UNUSED(prefix); }
132
+  #endif
131 133
 
132 134
   private:
133 135
     static void write();

+ 40
- 40
Marlin/src/feature/prusa_MMU2/mmu2.cpp View File

@@ -90,7 +90,7 @@ bool MMU2::enabled, MMU2::ready, MMU2::mmu_print_saved;
90 90
 uint8_t MMU2::cmd, MMU2::cmd_arg, MMU2::last_cmd, MMU2::extruder;
91 91
 int8_t MMU2::state = 0;
92 92
 volatile int8_t MMU2::finda = 1;
93
-volatile bool MMU2::findaRunoutValid;
93
+volatile bool MMU2::finda_runout_valid;
94 94
 int16_t MMU2::version = -1, MMU2::buildnr = -1;
95 95
 millis_t MMU2::last_request, MMU2::next_P0_request;
96 96
 char MMU2::rx_buffer[16], MMU2::tx_buffer[16];
@@ -103,7 +103,7 @@ char MMU2::rx_buffer[16], MMU2::tx_buffer[16];
103 103
   };
104 104
 
105 105
   static constexpr E_Step ramming_sequence[] PROGMEM = { MMU2_RAMMING_SEQUENCE };
106
-  static constexpr E_Step loadToNozzle_sequence[] PROGMEM = { MMU2_LOAD_TO_NOZZLE_SEQUENCE };
106
+  static constexpr E_Step load_to_nozzle_sequence[] PROGMEM = { MMU2_LOAD_TO_NOZZLE_SEQUENCE };
107 107
 
108 108
 #endif // MMU2_MENUS
109 109
 
@@ -142,11 +142,11 @@ void MMU2::reset() {
142 142
   #endif
143 143
 }
144 144
 
145
-uint8_t MMU2::getCurrentTool() {
145
+uint8_t MMU2::get_current_tool() {
146 146
   return extruder == MMU2_NO_TOOL ? -1 : extruder;
147 147
 }
148 148
 
149
-void MMU2::mmuLoop() {
149
+void MMU2::mmu_loop() {
150 150
 
151 151
   switch (state) {
152 152
 
@@ -185,7 +185,7 @@ void MMU2::mmuLoop() {
185 185
 
186 186
         DEBUG_ECHOLNPAIR("MMU => ", buildnr);
187 187
 
188
-        checkVersion();
188
+        check_version();
189 189
 
190 190
         #if ENABLED(MMU2_MODE_12V)
191 191
           DEBUG_ECHOLNPGM("MMU <= 'M1'");
@@ -207,7 +207,7 @@ void MMU2::mmuLoop() {
207 207
       if (rx_ok()) {
208 208
         DEBUG_ECHOLNPGM("MMU => ok");
209 209
 
210
-        checkVersion();
210
+        check_version();
211 211
 
212 212
         DEBUG_ECHOLNPGM("MMU <= 'P0'");
213 213
 
@@ -294,13 +294,13 @@ void MMU2::mmuLoop() {
294 294
         sscanf(rx_buffer, "%hhuok\n", &finda);
295 295
 
296 296
         // This is super annoying. Only activate if necessary
297
-        // if (findaRunoutValid) DEBUG_ECHOLNPAIR_F("MMU <= 'P0'\nMMU => ", finda, 6);
297
+        // if (finda_runout_valid) DEBUG_ECHOLNPAIR_F("MMU <= 'P0'\nMMU => ", finda, 6);
298 298
 
299 299
         state = 1;
300 300
 
301 301
         if (cmd == 0) ready = true;
302 302
 
303
-        if (!finda && findaRunoutValid) filamentRunout();
303
+        if (!finda && finda_runout_valid) filament_runout();
304 304
       }
305 305
       else if (ELAPSED(millis(), last_request + MMU_P0_TIMEOUT)) // Resend request after timeout (30s)
306 306
         state = 1;
@@ -434,7 +434,7 @@ bool MMU2::rx_ok() {
434 434
 /**
435 435
  * Check if MMU has compatible firmware
436 436
  */
437
-void MMU2::checkVersion() {
437
+void MMU2::check_version() {
438 438
   if (buildnr < MMU_REQUIRED_FW_BUILDNR) {
439 439
     SERIAL_ERROR_START();
440 440
     SERIAL_ECHOPGM("MMU2 firmware version invalid. Required version >= ");
@@ -447,7 +447,7 @@ void MMU2::checkVersion() {
447 447
 /**
448 448
  * Handle tool change
449 449
  */
450
-void MMU2::toolChange(uint8_t index) {
450
+void MMU2::tool_change(uint8_t index) {
451 451
 
452 452
   if (!enabled) return;
453 453
 
@@ -461,7 +461,7 @@ void MMU2::toolChange(uint8_t index) {
461 461
 
462 462
     command(MMU_CMD_T0 + index);
463 463
 
464
-    manageResponse(true, true);
464
+    manage_response(true, true);
465 465
     KEEPALIVE_STATE(IN_HANDLER);
466 466
 
467 467
     command(MMU_CMD_C0);
@@ -490,7 +490,7 @@ void MMU2::toolChange(uint8_t index) {
490 490
  * Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated.
491 491
  *
492 492
  */
493
-void MMU2::toolChange(const char* special) {
493
+void MMU2::tool_change(const char* special) {
494 494
 
495 495
   if (!enabled) return;
496 496
 
@@ -501,19 +501,19 @@ void MMU2::toolChange(const char* special) {
501 501
 
502 502
     switch (*special) {
503 503
       case '?': {
504
-        uint8_t index = mmu2_chooseFilament();
504
+        uint8_t index = mmu2_choose_filament();
505 505
         while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100);
506
-        loadFilamentToNozzle(index);
506
+        load_filament_to_nozzle(index);
507 507
       } break;
508 508
 
509 509
       case 'x': {
510 510
         planner.synchronize();
511
-        uint8_t index = mmu2_chooseFilament();
511
+        uint8_t index = mmu2_choose_filament();
512 512
         disable_E0();
513 513
         command(MMU_CMD_T0 + index);
514
-        manageResponse(true, true);
514
+        manage_response(true, true);
515 515
         command(MMU_CMD_C0);
516
-        mmuLoop();
516
+        mmu_loop();
517 517
 
518 518
         enable_E0();
519 519
         extruder = index;
@@ -522,7 +522,7 @@ void MMU2::toolChange(const char* special) {
522 522
 
523 523
       case 'c': {
524 524
         while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100);
525
-        executeExtruderSequence((const E_Step *)loadToNozzle_sequence, COUNT(loadToNozzle_sequence));
525
+        execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence));
526 526
       } break;
527 527
     }
528 528
 
@@ -547,7 +547,7 @@ void MMU2::command(const uint8_t mmu_cmd) {
547 547
 /**
548 548
  * Wait for response from MMU
549 549
  */
550
-bool MMU2::getResponse(void) {
550
+bool MMU2::get_response(void) {
551 551
   while (cmd != MMU_CMD_NONE) idle();
552 552
 
553 553
   while (!ready) {
@@ -565,7 +565,7 @@ bool MMU2::getResponse(void) {
565 565
 /**
566 566
  * Wait for response and deal with timeout if nexcessary
567 567
  */
568
-void MMU2::manageResponse(bool move_axes, bool turn_off_nozzle) {
568
+void MMU2::manage_response(bool move_axes, bool turn_off_nozzle) {
569 569
 
570 570
   bool response = false;
571 571
   mmu_print_saved = false;
@@ -575,7 +575,7 @@ void MMU2::manageResponse(bool move_axes, bool turn_off_nozzle) {
575 575
 
576 576
   while (!response) {
577 577
 
578
-    response = getResponse(); //wait for "ok" from mmu
578
+    response = get_response(); //wait for "ok" from mmu
579 579
 
580 580
     if (!response) { //no "ok" was received in reserved time frame, user will fix the issue on mmu unit
581 581
       if (!mmu_print_saved) { //first occurence, we are saving current position, park print head in certain position and disable nozzle heater
@@ -636,7 +636,7 @@ void MMU2::manageResponse(bool move_axes, bool turn_off_nozzle) {
636 636
   }
637 637
 }
638 638
 
639
-void MMU2::setFilamentType(uint8_t index, uint8_t filamentType) {
639
+void MMU2::set_filament_type(uint8_t index, uint8_t filamentType) {
640 640
   if (!enabled) return;
641 641
 
642 642
   KEEPALIVE_STATE(IN_HANDLER);
@@ -644,12 +644,12 @@ void MMU2::setFilamentType(uint8_t index, uint8_t filamentType) {
644 644
   cmd_arg = filamentType;
645 645
   command(MMU_CMD_F0 + index);
646 646
 
647
-  manageResponse(true, true);
647
+  manage_response(true, true);
648 648
 
649 649
   KEEPALIVE_STATE(NOT_BUSY);
650 650
 }
651 651
 
652
-void MMU2::filamentRunout() {
652
+void MMU2::filament_runout() {
653 653
   enqueue_and_echo_commands_P(PSTR(MMU2_FILAMENT_RUNOUT_SCRIPT));
654 654
   planner.synchronize();
655 655
 }
@@ -657,10 +657,10 @@ void MMU2::filamentRunout() {
657 657
 #if HAS_LCD_MENU && ENABLED(MMU2_MENUS)
658 658
 
659 659
   // Load filament into MMU2
660
-  void MMU2::loadFilament(uint8_t index) {
660
+  void MMU2::load_filament(uint8_t index) {
661 661
     if (!enabled) return;
662 662
     command(MMU_CMD_L0 + index);
663
-    manageResponse(false, false);
663
+    manage_response(false, false);
664 664
     BUZZ(200, 404);
665 665
   }
666 666
 
@@ -669,7 +669,7 @@ void MMU2::filamentRunout() {
669 669
    * Switch material and load to nozzle
670 670
    *
671 671
    */
672
-  bool MMU2::loadFilamentToNozzle(uint8_t index) {
672
+  bool MMU2::load_filament_to_nozzle(uint8_t index) {
673 673
 
674 674
     if (!enabled) return false;
675 675
 
@@ -682,14 +682,14 @@ void MMU2::filamentRunout() {
682 682
       KEEPALIVE_STATE(IN_HANDLER);
683 683
 
684 684
       command(MMU_CMD_T0 + index);
685
-      manageResponse(true, true);
685
+      manage_response(true, true);
686 686
       command(MMU_CMD_C0);
687
-      mmuLoop();
687
+      mmu_loop();
688 688
 
689 689
       extruder = index;
690 690
       active_extruder = 0;
691 691
 
692
-      loadToNozzle();
692
+      load_to_nozzle();
693 693
 
694 694
       BUZZ(200, 404);
695 695
 
@@ -706,12 +706,12 @@ void MMU2::filamentRunout() {
706 706
    * It is not used after T0 .. T4 command (select filament), in such case, gcode is responsible for loading
707 707
    * filament to nozzle.
708 708
    */
709
-  void MMU2::loadToNozzle() {
709
+  void MMU2::load_to_nozzle() {
710 710
     if (!enabled) return;
711
-    executeExtruderSequence((const E_Step *)loadToNozzle_sequence, COUNT(loadToNozzle_sequence));
711
+    execute_extruder_sequence((const E_Step *)load_to_nozzle_sequence, COUNT(load_to_nozzle_sequence));
712 712
   }
713 713
 
714
-  bool MMU2::ejectFilament(uint8_t index, bool recover) {
714
+  bool MMU2::eject_filament(uint8_t index, bool recover) {
715 715
 
716 716
     if (!enabled) return false;
717 717
 
@@ -731,7 +731,7 @@ void MMU2::filamentRunout() {
731 731
     planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2500 / 60, active_extruder);
732 732
     planner.synchronize();
733 733
     command(MMU_CMD_E0 + index);
734
-    manageResponse(false, false);
734
+    manage_response(false, false);
735 735
 
736 736
     if (recover)  {
737 737
       LCD_MESSAGEPGM(MSG_MMU2_EJECT_RECOVER);
@@ -745,7 +745,7 @@ void MMU2::filamentRunout() {
745 745
       BUZZ(200, 404);
746 746
 
747 747
       command(MMU_CMD_R0);
748
-      manageResponse(false, false);
748
+      manage_response(false, false);
749 749
     }
750 750
 
751 751
     ui.reset_status();
@@ -783,10 +783,10 @@ void MMU2::filamentRunout() {
783 783
 
784 784
     KEEPALIVE_STATE(IN_HANDLER);
785 785
 
786
-    filamentRamming();
786
+    filament_ramming();
787 787
 
788 788
     command(MMU_CMD_U0);
789
-    manageResponse(false, true);
789
+    manage_response(false, true);
790 790
 
791 791
     BUZZ(200, 404);
792 792
 
@@ -803,11 +803,11 @@ void MMU2::filamentRunout() {
803 803
   /**
804 804
    * Unload sequence to optimize shape of the tip of the unloaded filament
805 805
    */
806
-  void MMU2::filamentRamming() {
807
-    executeExtruderSequence((const E_Step *)ramming_sequence, sizeof(ramming_sequence) / sizeof(E_Step));
806
+  void MMU2::filament_ramming() {
807
+    execute_extruder_sequence((const E_Step *)ramming_sequence, sizeof(ramming_sequence) / sizeof(E_Step));
808 808
   }
809 809
 
810
-  void MMU2::executeExtruderSequence(const E_Step * sequence, int steps) {
810
+  void MMU2::execute_extruder_sequence(const E_Step * sequence, int steps) {
811 811
 
812 812
     planner.synchronize();
813 813
     enable_E0();

+ 18
- 18
Marlin/src/feature/prusa_MMU2/mmu2.h View File

@@ -36,18 +36,18 @@ public:
36 36
 
37 37
   static void init();
38 38
   static void reset();
39
-  static void mmuLoop();
40
-  static void toolChange(uint8_t index);
41
-  static void toolChange(const char* special);
42
-  static uint8_t getCurrentTool();
43
-  static void setFilamentType(uint8_t index, uint8_t type);
39
+  static void mmu_loop();
40
+  static void tool_change(uint8_t index);
41
+  static void tool_change(const char* special);
42
+  static uint8_t get_current_tool();
43
+  static void set_filament_type(uint8_t index, uint8_t type);
44 44
 
45 45
   #if HAS_LCD_MENU && ENABLED(MMU2_MENUS)
46 46
     static bool unload();
47
-    static void loadFilament(uint8_t);
48
-    static void loadAll();
49
-    static bool loadFilamentToNozzle(uint8_t index);
50
-    static bool ejectFilament(uint8_t index, bool recover);
47
+    static void load_filament(uint8_t);
48
+    static void load_all();
49
+    static bool load_filament_to_nozzle(uint8_t index);
50
+    static bool eject_filament(uint8_t index, bool recover);
51 51
   #endif
52 52
 
53 53
 private:
@@ -59,31 +59,31 @@ private:
59 59
 
60 60
   static bool rx_ok();
61 61
   static bool rx_start();
62
-  static void checkVersion();
62
+  static void check_version();
63 63
 
64 64
   static void command(const uint8_t cmd);
65
-  static bool getResponse(void);
66
-  static void manageResponse(bool move_axes, bool turn_off_nozzle);
65
+  static bool get_response(void);
66
+  static void manage_response(bool move_axes, bool turn_off_nozzle);
67 67
 
68 68
   #if HAS_LCD_MENU && ENABLED(MMU2_MENUS)
69
-    static void loadToNozzle();
70
-    static void filamentRamming();
71
-    static void executeExtruderSequence(const E_Step * sequence, int steps);
69
+    static void load_to_nozzle();
70
+    static void filament_ramming();
71
+    static void execute_extruder_sequence(const E_Step * sequence, int steps);
72 72
   #endif
73 73
 
74
-  static void filamentRunout();
74
+  static void filament_runout();
75 75
 
76 76
   static bool enabled, ready, mmu_print_saved;
77 77
   static uint8_t cmd, cmd_arg, last_cmd, extruder;
78 78
   static int8_t state;
79 79
   static volatile int8_t finda;
80
-  static volatile bool findaRunoutValid;
80
+  static volatile bool finda_runout_valid;
81 81
   static int16_t version, buildnr;
82 82
   static millis_t last_request, next_P0_request;
83 83
   static char rx_buffer[16], tx_buffer[16];
84 84
 
85 85
   static inline void set_runout_valid(const bool valid) {
86
-    findaRunoutValid = valid;
86
+    finda_runout_valid = valid;
87 87
     #if HAS_FILAMENT_SENSOR
88 88
       if (valid) runout.reset();
89 89
     #endif

+ 1
- 1
Marlin/src/feature/runout.h View File

@@ -49,7 +49,7 @@ class FilamentMonitorBase {
49 49
     #if ENABLED(HOST_ACTION_COMMANDS)
50 50
       static bool host_handling;
51 51
     #else
52
-      constexpr static bool host_handling = false;
52
+      static constexpr bool host_handling = false;
53 53
     #endif
54 54
 };
55 55
 

+ 9
- 9
Marlin/src/feature/tmc_util.cpp View File

@@ -474,7 +474,7 @@
474 474
       switch (i) {
475 475
         case TMC_PWM_SCALE: SERIAL_PRINT(st.PWM_SCALE(), DEC); break;
476 476
         case TMC_SGT: SERIAL_PRINT(st.sgt(), DEC); break;
477
-        case TMC_STEALTHCHOP: serialprintPGM(st.en_pwm_mode() ? PSTR("true") : PSTR("false")); break;
477
+        case TMC_STEALTHCHOP: serialprint_truefalse(st.en_pwm_mode()); break;
478 478
         default: break;
479 479
       }
480 480
     }
@@ -497,7 +497,7 @@
497 497
       switch (i) {
498 498
         case TMC_PWM_SCALE: SERIAL_PRINT(st.PWM_SCALE(), DEC); break;
499 499
         case TMC_SGT: SERIAL_PRINT(st.sgt(), DEC); break;
500
-        case TMC_STEALTHCHOP: serialprintPGM(st.en_pwm_mode() ? PSTR("true") : PSTR("false")); break;
500
+        case TMC_STEALTHCHOP: serialprint_truefalse(st.en_pwm_mode()); break;
501 501
         case TMC_GLOBAL_SCALER:
502 502
           {
503 503
             uint16_t value = st.GLOBAL_SCALER();
@@ -514,7 +514,7 @@
514 514
     static void tmc_status(TMC2208Stepper &st, const TMC_debug_enum i) {
515 515
       switch (i) {
516 516
         case TMC_PWM_SCALE: SERIAL_PRINT(st.pwm_scale_sum(), DEC); break;
517
-        case TMC_STEALTHCHOP: serialprintPGM(st.stealth() ? PSTR("true") : PSTR("false")); break;
517
+        case TMC_STEALTHCHOP: serialprint_truefalse(st.stealth()); break;
518 518
         case TMC_S2VSA: if (st.s2vsa()) SERIAL_CHAR('X'); break;
519 519
         case TMC_S2VSB: if (st.s2vsb()) SERIAL_CHAR('X'); break;
520 520
         default: break;
@@ -541,7 +541,7 @@
541 541
     SERIAL_CHAR('\t');
542 542
     switch (i) {
543 543
       case TMC_CODES: st.printLabel(); break;
544
-      case TMC_ENABLED: serialprintPGM(st.isEnabled() ? PSTR("true") : PSTR("false")); break;
544
+      case TMC_ENABLED: serialprint_truefalse(st.isEnabled()); break;
545 545
       case TMC_CURRENT: SERIAL_ECHO(st.getMilliamps()); break;
546 546
       case TMC_RMS_CURRENT: SERIAL_ECHO(st.rms_current()); break;
547 547
       case TMC_MAX_CURRENT: SERIAL_PRINT((float)st.rms_current() * 1.41, 0); break;
@@ -578,9 +578,9 @@
578 578
             SERIAL_CHAR('-');
579 579
         }
580 580
         break;
581
-      case TMC_OTPW: serialprintPGM(st.otpw() ? PSTR("true") : PSTR("false")); break;
581
+      case TMC_OTPW: serialprint_truefalse(st.otpw()); break;
582 582
       #if ENABLED(MONITOR_DRIVER_STATUS)
583
-        case TMC_OTPW_TRIGGERED: serialprintPGM(st.getOTPW() ? PSTR("true") : PSTR("false")); break;
583
+        case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break;
584 584
       #endif
585 585
       case TMC_TOFF: SERIAL_PRINT(st.toff(), DEC); break;
586 586
       case TMC_TBL: SERIAL_PRINT(st.blank_time(), DEC); break;
@@ -596,7 +596,7 @@
596 596
       SERIAL_CHAR('\t');
597 597
       switch (i) {
598 598
         case TMC_CODES: st.printLabel(); break;
599
-        case TMC_ENABLED: serialprintPGM(st.isEnabled() ? PSTR("true") : PSTR("false")); break;
599
+        case TMC_ENABLED: serialprint_truefalse(st.isEnabled()); break;
600 600
         case TMC_CURRENT: SERIAL_ECHO(st.getMilliamps()); break;
601 601
         case TMC_RMS_CURRENT: SERIAL_ECHO(st.rms_current()); break;
602 602
         case TMC_MAX_CURRENT: SERIAL_PRINT((float)st.rms_current() * 1.41, 0); break;
@@ -606,8 +606,8 @@
606 606
           break;
607 607
         case TMC_VSENSE: serialprintPGM(st.vsense() ? PSTR("1=.165") : PSTR("0=.310")); break;
608 608
         case TMC_MICROSTEPS: SERIAL_ECHO(st.microsteps()); break;
609
-        //case TMC_OTPW: serialprintPGM(st.otpw() ? PSTR("true") : PSTR("false")); break;
610
-        //case TMC_OTPW_TRIGGERED: serialprintPGM(st.getOTPW() ? PSTR("true") : PSTR("false")); break;
609
+        //case TMC_OTPW: serialprint_truefalse(st.otpw()); break;
610
+        //case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break;
611 611
         case TMC_SGT: SERIAL_PRINT(st.sgt(), DEC); break;
612 612
         case TMC_TOFF: SERIAL_PRINT(st.toff(), DEC); break;
613 613
         case TMC_TBL: SERIAL_PRINT(st.blank_time(), DEC); break;

+ 1
- 1
Marlin/src/feature/tmc_util.h View File

@@ -227,7 +227,7 @@ void tmc_set_current(TMC &st, const int mA) {
227 227
   void tmc_report_otpw(TMC &st) {
228 228
     st.printLabel();
229 229
     SERIAL_ECHOPGM(" temperature prewarn triggered: ");
230
-    serialprintPGM(st.getOTPW() ? PSTR("true") : PSTR("false"));
230
+    serialprint_truefalse(st.getOTPW());
231 231
     SERIAL_EOL();
232 232
   }
233 233
   template<typename TMC>

+ 26
- 78
Marlin/src/gcode/bedlevel/G26.cpp View File

@@ -246,8 +246,6 @@ void move_to(const float &rx, const float &ry, const float &z, const float &e_de
246 246
   // Yes: a 'normal' movement. No: a retract() or recover()
247 247
   feed_value = has_xy_component ? G26_XY_FEEDRATE : planner.settings.max_feedrate_mm_s[E_AXIS] / 1.5;
248 248
 
249
-  if (g26_debug_flag) SERIAL_ECHOLNPAIR("in move_to() feed_value for XY:", feed_value);
250
-
251 249
   destination[X_AXIS] = rx;
252 250
   destination[Y_AXIS] = ry;
253 251
   destination[E_AXIS] += e_delta;
@@ -327,19 +325,15 @@ inline bool look_for_lines_to_connect() {
327 325
     for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) {
328 326
 
329 327
       #if HAS_LCD_MENU
330
-        if (user_canceled()) return true;     // Check if the user wants to stop the Mesh Validation
328
+        if (user_canceled()) return true;
331 329
       #endif
332 330
 
333
-      if (i < GRID_MAX_POINTS_X) { // We can't connect to anything to the right than GRID_MAX_POINTS_X.
334
-                                   // This is already a half circle because we are at the edge of the bed.
331
+      if (i < GRID_MAX_POINTS_X) { // Can't connect to anything to the right than GRID_MAX_POINTS_X.
332
+                                   // Already a half circle at the edge of the bed.
335 333
 
336 334
         if (is_bitmap_set(circle_flags, i, j) && is_bitmap_set(circle_flags, i + 1, j)) { // check if we can do a line to the left
337 335
           if (!is_bitmap_set(horizontal_mesh_line_flags, i, j)) {
338
-
339
-            //
340
-            // We found two circles that need a horizontal line to connect them
341
-            // Print it!
342
-            //
336
+            // Two circles need a horizontal line to connect them
343 337
             sx = _GET_MESH_X(  i  ) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // right edge
344 338
             ex = _GET_MESH_X(i + 1) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // left edge
345 339
 
@@ -347,27 +341,19 @@ inline bool look_for_lines_to_connect() {
347 341
             sy = ey = constrain(_GET_MESH_Y(j), Y_MIN_POS + 1, Y_MAX_POS - 1);
348 342
             ex = constrain(ex, X_MIN_POS + 1, X_MAX_POS - 1);
349 343
 
350
-            if (position_is_reachable(sx, sy) && position_is_reachable(ex, ey)) {
351
-
352
-              if (g26_debug_flag) {
353
-                SERIAL_ECHOLNPAIR(" Connecting with horizontal line (sx=", sx, ", sy=", sy, ") -> (ex=", ex, ", ey=", ey, ")");
354
-                //debug_current_and_destination(PSTR("Connecting horizontal line."));
355
-              }
344
+            if (position_is_reachable(sx, sy) && position_is_reachable(ex, ey))
356 345
               print_line_from_here_to_there(sx, sy, g26_layer_height, ex, ey, g26_layer_height);
357
-            }
358
-            bitmap_set(horizontal_mesh_line_flags, i, j);   // Mark it as done so we don't do it again, even if we skipped it
346
+
347
+            bitmap_set(horizontal_mesh_line_flags, i, j); // Mark done, even if skipped
359 348
           }
360 349
         }
361 350
 
362
-        if (j < GRID_MAX_POINTS_Y) { // We can't connect to anything further back than GRID_MAX_POINTS_Y.
363
-                                         // This is already a half circle because we are at the edge  of the bed.
351
+        if (j < GRID_MAX_POINTS_Y) {  // Can't connect to anything further back than GRID_MAX_POINTS_Y.
352
+                                      // Already a half circle at the edge of the bed.
364 353
 
365 354
           if (is_bitmap_set(circle_flags, i, j) && is_bitmap_set(circle_flags, i, j + 1)) { // check if we can do a line straight down
366 355
             if (!is_bitmap_set( vertical_mesh_line_flags, i, j)) {
367
-              //
368
-              // We found two circles that need a vertical line to connect them
369
-              // Print it!
370
-              //
356
+              // Two circles that need a vertical line to connect them
371 357
               sy = _GET_MESH_Y(  j  ) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // top edge
372 358
               ey = _GET_MESH_Y(j + 1) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // bottom edge
373 359
 
@@ -375,23 +361,10 @@ inline bool look_for_lines_to_connect() {
375 361
               sy = constrain(sy, Y_MIN_POS + 1, Y_MAX_POS - 1);
376 362
               ey = constrain(ey, Y_MIN_POS + 1, Y_MAX_POS - 1);
377 363
 
378
-              if (position_is_reachable(sx, sy) && position_is_reachable(ex, ey)) {
379
-
380
-                if (g26_debug_flag) {
381
-                  SERIAL_ECHOPAIR(" Connecting with vertical line (sx=", sx);
382
-                  SERIAL_ECHOPAIR(", sy=", sy);
383
-                  SERIAL_ECHOPAIR(") -> (ex=", ex);
384
-                  SERIAL_ECHOPAIR(", ey=", ey);
385
-                  SERIAL_CHAR(')');
386
-                  SERIAL_EOL();
387
-
388
-                  #if ENABLED(AUTO_BED_LEVELING_UBL)
389
-                    debug_current_and_destination(PSTR("Connecting vertical line."));
390
-                  #endif
391
-                }
364
+              if (position_is_reachable(sx, sy) && position_is_reachable(ex, ey))
392 365
                 print_line_from_here_to_there(sx, sy, g26_layer_height, ex, ey, g26_layer_height);
393
-              }
394
-              bitmap_set(vertical_mesh_line_flags, i, j);   // Mark it as done so we don't do it again, even if skipped
366
+
367
+              bitmap_set(vertical_mesh_line_flags, i, j); // Mark done, even if skipped
395 368
             }
396 369
           }
397 370
         }
@@ -725,8 +698,6 @@ void GcodeSuite::G26() {
725 698
     ui.capture();
726 699
   #endif
727 700
 
728
-  //debug_current_and_destination(PSTR("Starting G26 Mesh Validation Pattern."));
729
-
730 701
   #if DISABLED(ARC_SUPPORT)
731 702
 
732 703
     /**
@@ -768,6 +739,7 @@ void GcodeSuite::G26() {
768 739
       #if ENABLED(ARC_SUPPORT)
769 740
 
770 741
         #define ARC_LENGTH(quarters)  (INTERSECTION_CIRCLE_RADIUS * M_PI * (quarters) / 2)
742
+        #define INTERSECTION_CIRCLE_DIAM  ((INTERSECTION_CIRCLE_RADIUS) * 2)
771 743
         float sx = circle_x + INTERSECTION_CIRCLE_RADIUS,   // default to full circle
772 744
               ex = circle_x + INTERSECTION_CIRCLE_RADIUS,
773 745
               sy = circle_y, ey = circle_y,
@@ -775,14 +747,8 @@ void GcodeSuite::G26() {
775 747
 
776 748
         // Figure out where to start and end the arc - we always print counterclockwise
777 749
         if (xi == 0) {                             // left edge
778
-          if (!f) {
779
-            sx = circle_x;
780
-            sy -= (INTERSECTION_CIRCLE_RADIUS);
781
-          }
782
-          if (!b) {
783
-            ex = circle_x;
784
-            ey += INTERSECTION_CIRCLE_RADIUS;
785
-          }
750
+          if (!f) { sx = circle_x; sy -= INTERSECTION_CIRCLE_RADIUS; }
751
+          if (!b) { ex = circle_x; ey += INTERSECTION_CIRCLE_RADIUS; }
786 752
           arc_length = (f || b) ? ARC_LENGTH(1) : ARC_LENGTH(2);
787 753
         }
788 754
         else if (r) {                             // right edge
@@ -793,26 +759,23 @@ void GcodeSuite::G26() {
793 759
           arc_length = (f || b) ? ARC_LENGTH(1) : ARC_LENGTH(2);
794 760
         }
795 761
         else if (f) {
796
-          ex = circle_x - (INTERSECTION_CIRCLE_RADIUS);
762
+          ex -= INTERSECTION_CIRCLE_DIAM;
797 763
           arc_length = ARC_LENGTH(2);
798 764
         }
799 765
         else if (b) {
800
-          sx = circle_x - (INTERSECTION_CIRCLE_RADIUS);
766
+          sx -= INTERSECTION_CIRCLE_DIAM;
801 767
           arc_length = ARC_LENGTH(2);
802 768
         }
803
-        const float arc_offset[2] = {
804
-          circle_x - sx,
805
-          circle_y - sy
806
-        };
807 769
 
808
-        const float dx_s = current_position[X_AXIS] - sx,   // find our distance from the start of the actual circle
770
+        const float arc_offset[2] = { circle_x - sx, circle_y - sy },
771
+                    dx_s = current_position[X_AXIS] - sx,   // find our distance from the start of the actual circle
809 772
                     dy_s = current_position[Y_AXIS] - sy,
810
-                    dist_start = HYPOT2(dx_s, dy_s);
811
-        const float endpoint[XYZE] = {
812
-          ex, ey,
813
-          g26_layer_height,
814
-          current_position[E_AXIS] + (arc_length * g26_e_axis_feedrate * g26_extrusion_multiplier)
815
-        };
773
+                    dist_start = HYPOT2(dx_s, dy_s),
774
+                    endpoint[XYZE] = {
775
+                      ex, ey,
776
+                      g26_layer_height,
777
+                      current_position[E_AXIS] + (arc_length * g26_e_axis_feedrate * g26_extrusion_multiplier)
778
+                    };
816 779
 
817 780
         if (dist_start > 2.0) {
818 781
           retract_filament(destination);
@@ -827,18 +790,6 @@ void GcodeSuite::G26() {
827 790
         const float save_feedrate = feedrate_mm_s;
828 791
         feedrate_mm_s = PLANNER_XY_FEEDRATE() / 10.0;
829 792
 
830
-        if (g26_debug_flag) {
831
-          SERIAL_ECHOPAIR(" plan_arc(ex=", endpoint[X_AXIS]);
832
-          SERIAL_ECHOPAIR(", ey=", endpoint[Y_AXIS]);
833
-          SERIAL_ECHOPAIR(", ez=", endpoint[Z_AXIS]);
834
-          SERIAL_ECHOPAIR(", len=", arc_length);
835
-          SERIAL_ECHOPAIR(") -> (ex=", current_position[X_AXIS]);
836
-          SERIAL_ECHOPAIR(", ey=", current_position[Y_AXIS]);
837
-          SERIAL_ECHOPAIR(", ez=", current_position[Z_AXIS]);
838
-          SERIAL_CHAR(')');
839
-          SERIAL_EOL();
840
-        }
841
-
842 793
         plan_arc(endpoint, arc_offset, false);  // Draw a counter-clockwise arc
843 794
         feedrate_mm_s = save_feedrate;
844 795
         set_destination_from_current();
@@ -906,16 +857,13 @@ void GcodeSuite::G26() {
906 857
   retract_filament(destination);
907 858
   destination[Z_AXIS] = Z_CLEARANCE_BETWEEN_PROBES;
908 859
 
909
-  //debug_current_and_destination(PSTR("ready to do Z-Raise."));
910 860
   move_to(destination, 0); // Raise the nozzle
911
-  //debug_current_and_destination(PSTR("done doing Z-Raise."));
912 861
 
913 862
   destination[X_AXIS] = g26_x_pos;                            // Move back to the starting position
914 863
   destination[Y_AXIS] = g26_y_pos;
915 864
   //destination[Z_AXIS] = Z_CLEARANCE_BETWEEN_PROBES;         // Keep the nozzle where it is
916 865
 
917 866
   move_to(destination, 0);                                    // Move back to the starting position
918
-  //debug_current_and_destination(PSTR("done doing X/Y move."));
919 867
 
920 868
   #if DISABLED(NO_VOLUMETRICS)
921 869
     parser.volumetric_enabled = volumetric_was_enabled;

+ 26
- 15
Marlin/src/gcode/calibrate/G28.cpp View File

@@ -182,7 +182,6 @@
182 182
  *
183 183
  */
184 184
 void GcodeSuite::G28(const bool always_home_all) {
185
-
186 185
   if (DEBUGGING(LEVELING)) {
187 186
     DEBUG_ECHOLNPGM(">>> G28");
188 187
     log_machine_info();
@@ -268,13 +267,16 @@ void GcodeSuite::G28(const bool always_home_all) {
268 267
     const bool homeX = always_home_all || parser.seen('X'),
269 268
                homeY = always_home_all || parser.seen('Y'),
270 269
                homeZ = always_home_all || parser.seen('Z'),
271
-               home_all = (!homeX && !homeY && !homeZ) || (homeX && homeY && homeZ);
270
+               home_all = (!homeX && !homeY && !homeZ) || (homeX && homeY && homeZ),
271
+               doX = home_all || homeX,
272
+               doY = home_all || homeY,
273
+               doZ = home_all || homeZ;
272 274
 
273 275
     set_destination_from_current();
274 276
 
275 277
     #if Z_HOME_DIR > 0  // If homing away from BED do Z first
276 278
 
277
-      if (home_all || homeZ) homeaxis(Z_AXIS);
279
+      if (doZ) homeaxis(Z_AXIS);
278 280
 
279 281
     #endif
280 282
 
@@ -285,7 +287,7 @@ void GcodeSuite::G28(const bool always_home_all) {
285 287
           (parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT)
286 288
     );
287 289
 
288
-    if (z_homing_height && (home_all || homeX || homeY)) {
290
+    if (z_homing_height && (doX || doY)) {
289 291
       // Raise Z before homing any other axes and z is not already high enough (never lower z)
290 292
       destination[Z_AXIS] = z_homing_height;
291 293
       if (destination[Z_AXIS] > current_position[Z_AXIS]) {
@@ -296,25 +298,25 @@ void GcodeSuite::G28(const bool always_home_all) {
296 298
 
297 299
     #if ENABLED(QUICK_HOME)
298 300
 
299
-      if (home_all || (homeX && homeY)) quick_home_xy();
301
+      if (doX && doY) quick_home_xy();
300 302
 
301 303
     #endif
302 304
 
303 305
     // Home Y (before X)
304 306
     #if ENABLED(HOME_Y_BEFORE_X)
305 307
 
306
-      if (home_all || homeY
308
+      if (doY
307 309
         #if ENABLED(CODEPENDENT_XY_HOMING)
308
-          || homeX
310
+          || doX
309 311
         #endif
310 312
       ) homeaxis(Y_AXIS);
311 313
 
312 314
     #endif
313 315
 
314 316
     // Home X
315
-    if (home_all || homeX
317
+    if (doX
316 318
       #if ENABLED(CODEPENDENT_XY_HOMING) && DISABLED(HOME_Y_BEFORE_X)
317
-        || homeY
319
+        || doY
318 320
       #endif
319 321
     ) {
320 322
 
@@ -345,12 +347,12 @@ void GcodeSuite::G28(const bool always_home_all) {
345 347
 
346 348
     // Home Y (after X)
347 349
     #if DISABLED(HOME_Y_BEFORE_X)
348
-      if (home_all || homeY) homeaxis(Y_AXIS);
350
+      if (doY) homeaxis(Y_AXIS);
349 351
     #endif
350 352
 
351 353
     // Home Z last if homing towards the bed
352 354
     #if Z_HOME_DIR < 0
353
-      if (home_all || homeZ) {
355
+      if (doZ) {
354 356
         #if ENABLED(Z_SAFE_HOMING)
355 357
           home_z_safely();
356 358
         #else
@@ -361,7 +363,7 @@ void GcodeSuite::G28(const bool always_home_all) {
361 363
           move_z_after_probing();
362 364
         #endif
363 365
 
364
-      } // home_all || homeZ
366
+      } // doZ
365 367
     #endif // Z_HOME_DIR < 0
366 368
 
367 369
     sync_plan_position();
@@ -402,6 +404,15 @@ void GcodeSuite::G28(const bool always_home_all) {
402 404
 
403 405
   #endif // DUAL_X_CARRIAGE
404 406
 
407
+  #ifdef HOMING_BACKOFF_MM
408
+    endstops.enable(false);
409
+    constexpr float endstop_backoff[XYZ] = HOMING_BACKOFF_MM;
410
+    const float backoff_x = doX ? ABS(endstop_backoff[X_AXIS]) * (X_HOME_DIR) : 0,
411
+                backoff_y = doY ? ABS(endstop_backoff[Y_AXIS]) * (Y_HOME_DIR) : 0,
412
+                backoff_z = doZ ? ABS(endstop_backoff[Z_AXIS]) * (Z_HOME_DIR) : 0;
413
+    if (backoff_z) do_blocking_move_to_z(current_position[Z_AXIS] - backoff_z);
414
+    if (backoff_x || backoff_y) do_blocking_move_to_xy(current_position[X_AXIS] - backoff_x, current_position[Y_AXIS] - backoff_y);
415
+  #endif
405 416
   endstops.not_homing();
406 417
 
407 418
   #if BOTH(DELTA, DELTA_HOME_TO_SAFE_ZONE)
@@ -417,7 +428,7 @@ void GcodeSuite::G28(const bool always_home_all) {
417 428
 
418 429
   // Restore the active tool after homing
419 430
   #if HOTENDS > 1 && (DISABLED(DELTA) || ENABLED(DELTA_HOME_TO_SAFE_ZONE))
420
-    #if ENABLED(PARKING_EXTRUDER) || ENABLED(DUAL_X_CARRIAGE)
431
+    #if EITHER(PARKING_EXTRUDER, DUAL_X_CARRIAGE)
421 432
       #define NO_FETCH false // fetch the previous toolhead
422 433
     #else
423 434
       #define NO_FETCH true
@@ -430,9 +441,9 @@ void GcodeSuite::G28(const bool always_home_all) {
430 441
   report_current_position();
431 442
   #if ENABLED(NANODLP_Z_SYNC)
432 443
     #if ENABLED(NANODLP_ALL_AXIS)
433
-      #define _HOME_SYNC true                 // For any axis, output sync text.
444
+      #define _HOME_SYNC true       // For any axis, output sync text.
434 445
     #else
435
-      #define _HOME_SYNC (home_all || homeZ)  // Only for Z-axis
446
+      #define _HOME_SYNC doZ        // Only for Z-axis
436 447
     #endif
437 448
     if (_HOME_SYNC)
438 449
       SERIAL_ECHOLNPGM(MSG_Z_MOVE_COMP);

+ 1
- 1
Marlin/src/gcode/config/M217.cpp View File

@@ -30,7 +30,7 @@
30 30
 void M217_report(const bool eeprom=false) {
31 31
 
32 32
   #if ENABLED(TOOLCHANGE_FILAMENT_SWAP)
33
-    serialprintPGM(eeprom ? PSTR("  M217") : PSTR("Singlenozzle:"));
33
+    serialprintPGM(eeprom ? PSTR("  M217") : PSTR("Toolchange:"));
34 34
     SERIAL_ECHOPAIR(" S", LINEAR_UNIT(toolchange_settings.swap_length));
35 35
     SERIAL_ECHOPAIR(" P", LINEAR_UNIT(toolchange_settings.prime_speed));
36 36
     SERIAL_ECHOPAIR(" R", LINEAR_UNIT(toolchange_settings.retract_speed));

+ 8
- 8
Marlin/src/gcode/config/M43.cpp View File

@@ -47,13 +47,13 @@ inline void toggle_pins() {
47 47
 
48 48
   for (uint8_t i = start; i <= end; i++) {
49 49
     pin_t pin = GET_PIN_MAP_PIN(i);
50
-    //report_pin_state_extended(pin, ignore_protection, false);
51 50
     if (!VALID_PIN(pin)) continue;
52
-    if (!ignore_protection && pin_is_protected(pin)) {
51
+    if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) {
53 52
       report_pin_state_extended(pin, ignore_protection, true, "Untouched ");
54 53
       SERIAL_EOL();
55 54
     }
56 55
     else {
56
+      watchdog_reset();
57 57
       report_pin_state_extended(pin, ignore_protection, true, "Pulsing   ");
58 58
       #if AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO
59 59
         if (pin == TEENSY_E2) {
@@ -77,12 +77,12 @@ inline void toggle_pins() {
77 77
       {
78 78
         pinMode(pin, OUTPUT);
79 79
         for (int16_t j = 0; j < repeat; j++) {
80
-          extDigitalWrite(pin, 0); safe_delay(wait);
81
-          extDigitalWrite(pin, 1); safe_delay(wait);
82
-          extDigitalWrite(pin, 0); safe_delay(wait);
80
+          watchdog_reset(); extDigitalWrite(pin, 0); safe_delay(wait);
81
+          watchdog_reset(); extDigitalWrite(pin, 1); safe_delay(wait);
82
+          watchdog_reset(); extDigitalWrite(pin, 0); safe_delay(wait);
83
+          watchdog_reset();
83 84
         }
84 85
       }
85
-
86 86
     }
87 87
     SERIAL_EOL();
88 88
   }
@@ -277,7 +277,7 @@ void GcodeSuite::M43() {
277 277
     for (uint8_t i = first_pin; i <= last_pin; i++) {
278 278
       pin_t pin = GET_PIN_MAP_PIN(i);
279 279
       if (!VALID_PIN(pin)) continue;
280
-      if (!ignore_protection && pin_is_protected(pin)) continue;
280
+      if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) continue;
281 281
       pinMode(pin, INPUT_PULLUP);
282 282
       delay(1);
283 283
       /*
@@ -300,7 +300,7 @@ void GcodeSuite::M43() {
300 300
       for (uint8_t i = first_pin; i <= last_pin; i++) {
301 301
         pin_t pin = GET_PIN_MAP_PIN(i);
302 302
         if (!VALID_PIN(pin)) continue;
303
-        if (!ignore_protection && pin_is_protected(pin)) continue;
303
+        if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) continue;
304 304
         const byte val =
305 305
           /*
306 306
             IS_ANALOG(pin)

+ 6
- 6
Marlin/src/gcode/control/M3-M5.cpp View File

@@ -53,7 +53,7 @@ uint8_t spindle_laser_power; // = 0
53 53
  * NOTE: A minimum PWM frequency of 50 Hz is needed. All prescaler
54 54
  *       factors for timers 2, 3, 4, and 5 are acceptable.
55 55
  *
56
- *  SPINDLE_LASER_ENABLE_PIN needs an external pullup or it may power on
56
+ *  SPINDLE_LASER_ENA_PIN needs an external pullup or it may power on
57 57
  *  the spindle/laser during power-up or when connecting to the host
58 58
  *  (usually goes through a reset which sets all I/O pins to tri-state)
59 59
  *
@@ -73,7 +73,7 @@ inline void delay_for_power_down() { safe_delay(SPINDLE_LASER_POWERDOWN_DELAY);
73 73
  */
74 74
 
75 75
 inline void set_spindle_laser_ocr(const uint8_t ocr) {
76
-  WRITE(SPINDLE_LASER_ENABLE_PIN, SPINDLE_LASER_ENABLE_INVERT); // turn spindle on (active low)
76
+  WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ENABLE_INVERT); // turn spindle on (active low)
77 77
   analogWrite(SPINDLE_LASER_PWM_PIN, (SPINDLE_LASER_PWM_INVERT) ? 255 - ocr : ocr);
78 78
 }
79 79
 
@@ -81,7 +81,7 @@ inline void set_spindle_laser_ocr(const uint8_t ocr) {
81 81
 
82 82
   void update_spindle_laser_power() {
83 83
     if (spindle_laser_power == 0) {
84
-      WRITE(SPINDLE_LASER_ENABLE_PIN, !SPINDLE_LASER_ENABLE_INVERT);                      // turn spindle off (active low)
84
+      WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ENABLE_INVERT);                      // turn spindle off (active low)
85 85
       analogWrite(SPINDLE_LASER_PWM_PIN, SPINDLE_LASER_PWM_INVERT ? 255 : 0);             // only write low byte
86 86
       delay_for_power_down();
87 87
     }
@@ -101,7 +101,7 @@ inline void set_spindle_laser_ocr(const uint8_t ocr) {
101 101
 #endif // SPINDLE_LASER_PWM
102 102
 
103 103
 bool spindle_laser_enabled() {
104
-  return !!spindle_laser_power; // READ(SPINDLE_LASER_ENABLE_PIN) == SPINDLE_LASER_ENABLE_INVERT;
104
+  return !!spindle_laser_power; // READ(SPINDLE_LASER_ENA_PIN) == SPINDLE_LASER_ENABLE_INVERT;
105 105
 }
106 106
 
107 107
 void set_spindle_laser_enabled(const bool enable) {
@@ -111,11 +111,11 @@ void set_spindle_laser_enabled(const bool enable) {
111 111
     update_spindle_laser_power();
112 112
   #else
113 113
     if (enable) {
114
-      WRITE(SPINDLE_LASER_ENABLE_PIN, SPINDLE_LASER_ENABLE_INVERT);
114
+      WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ENABLE_INVERT);
115 115
       delay_for_power_up();
116 116
     }
117 117
     else {
118
-      WRITE(SPINDLE_LASER_ENABLE_PIN, !SPINDLE_LASER_ENABLE_INVERT);
118
+      WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ENABLE_INVERT);
119 119
       delay_for_power_down();
120 120
     }
121 121
   #endif

+ 2
- 2
Marlin/src/gcode/control/M605.cpp View File

@@ -42,10 +42,10 @@
42 42
    *
43 43
    *   M605 S0 : (FULL_CONTROL) The slicer has full control over both X-carriages and can achieve optimal travel
44 44
    *             results as long as it supports dual X-carriages.
45
-   * 
45
+   *
46 46
    *   M605 S1 : (AUTO_PARK) The firmware automatically parks and unparks the X-carriages on tool-change so that
47 47
    *             additional slicer support is not required.
48
-   * 
48
+   *
49 49
    *   M605 S2 X R : (DUPLICATION) The firmware moves the second X-carriage and extruder in synchronization with
50 50
    *             the first X-carriage and extruder, to print 2 copies of the same object at the same time.
51 51
    *             Set the constant X-offset and temperature differential with M605 S2 X[offs] R[deg] and

+ 1
- 1
Marlin/src/gcode/control/T.cpp View File

@@ -55,7 +55,7 @@ void GcodeSuite::T(const uint8_t tool_index) {
55 55
 
56 56
   #if ENABLED(PRUSA_MMU2)
57 57
     if (parser.string_arg) {
58
-      mmu2.toolChange(parser.string_arg);   // Special commands T?/Tx/Tc
58
+      mmu2.tool_change(parser.string_arg);   // Special commands T?/Tx/Tc
59 59
       return;
60 60
     }
61 61
   #endif

+ 1
- 1
Marlin/src/gcode/feature/pause/M701_M702.cpp View File

@@ -84,7 +84,7 @@ void GcodeSuite::M701() {
84 84
 
85 85
   // Load filament
86 86
   #if ENABLED(PRUSA_MMU2)
87
-    mmu2.loadFilamentToNozzle(target_extruder);
87
+    mmu2.load_filament_to_nozzle(target_extruder);
88 88
   #else
89 89
     constexpr float slow_load_length = FILAMENT_CHANGE_SLOW_LOAD_LENGTH;
90 90
     const float fast_load_length = ABS(parser.seen('L') ? parser.value_axis_units(E_AXIS)

+ 13
- 13
Marlin/src/gcode/feature/powerloss/M1000.cpp View File

@@ -29,17 +29,20 @@
29 29
 #include "../../../module/motion.h"
30 30
 #include "../../../lcd/ultralcd.h"
31 31
 
32
-void menu_job_recovery();
32
+#define DEBUG_OUT ENABLED(DEBUG_POWER_LOSS_RECOVERY)
33
+#include "../../../core/debug_out.h"
33 34
 
34
-#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
35
+void menu_job_recovery();
35 36
 
36
-  inline void plr_error(PGM_P const prefix) {
37
-    SERIAL_ECHO_START();
37
+inline void plr_error(PGM_P const prefix) {
38
+  #if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
39
+    DEBUG_ECHO_START();
38 40
     serialprintPGM(prefix);
39
-    SERIAL_ECHOLNPGM(" Power-Loss Recovery Data");
40
-  }
41
-
42
-#endif
41
+    DEBUG_ECHOLNPGM(" Power-Loss Recovery Data");
42
+  #else
43
+    UNUSED(prefix);
44
+  #endif
45
+}
43 46
 
44 47
 /**
45 48
  * M1000: Resume from power-loss (undocumented)
@@ -54,11 +57,8 @@ void GcodeSuite::M1000() {
54 57
     else
55 58
       recovery.resume();
56 59
   }
57
-  else {
58
-    #if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
59
-      plr_error(recovery.info.valid_head ? PSTR("No") : PSTR("Invalid"));
60
-    #endif
61
-  }
60
+  else
61
+    plr_error(recovery.info.valid_head ? PSTR("No") : PSTR("Invalid"));
62 62
 
63 63
 }
64 64
 

+ 1
- 1
Marlin/src/gcode/feature/prusa_MMU2/M403.cpp View File

@@ -41,7 +41,7 @@ void GcodeSuite::M403() {
41 41
          type = parser.intval('F', -1);
42 42
 
43 43
   if (WITHIN(index, 0, 4) && WITHIN(type, 0, 2))
44
-    mmu2.setFilamentType(index, type);
44
+    mmu2.set_filament_type(index, type);
45 45
   else
46 46
     SERIAL_ECHO_MSG("M403 - bad arguments.");
47 47
 }

+ 11
- 5
Marlin/src/gcode/gcode.cpp View File

@@ -105,7 +105,7 @@ void GcodeSuite::get_destination_from_command() {
105 105
 
106 106
   #if ENABLED(POWER_LOSS_RECOVERY)
107 107
     // Only update power loss recovery on moves with E
108
-    if ((seen[E_AXIS] || seen[Z_AXIS]) && IS_SD_PRINTING()) recovery.save();
108
+    if (seen[E_AXIS] && (seen[X_AXIS] || seen[Y_AXIS]) && IS_SD_PRINTING()) recovery.save();
109 109
   #endif
110 110
 
111 111
   if (parser.linearval('F') > 0)
@@ -269,6 +269,16 @@ void GcodeSuite::process_parsed_command(
269 269
           break;
270 270
       #endif
271 271
 
272
+      #if ENABLED(CNC_COORDINATE_SYSTEMS)
273
+        case 53: G53(); break;
274
+        case 54: G54(); break;
275
+        case 55: G55(); break;
276
+        case 56: G56(); break;
277
+        case 57: G57(); break;
278
+        case 58: G58(); break;
279
+        case 59: G59(); break;
280
+      #endif
281
+
272 282
       #if ENABLED(GCODE_MOTION_MODES)
273 283
         case 80: G80(); break;                                    // G80: Reset the current motion mode
274 284
       #endif
@@ -348,10 +358,6 @@ void GcodeSuite::process_parsed_command(
348 358
         case 48: M48(); break;                                    // M48: Z probe repeatability test
349 359
       #endif
350 360
 
351
-      #if ENABLED(G26_MESH_VALIDATION)
352
-        case 49: M49(); break;                                    // M49: Turn on or off G26 debug flag for verbose output
353
-      #endif
354
-
355 361
       #if ENABLED(LCD_SET_PROGRESS_MANUALLY)
356 362
         case 73: M73(); break;                                    // M73: Set progress percentage (for display on LCD)
357 363
       #endif

+ 0
- 4
Marlin/src/gcode/gcode.h View File

@@ -495,10 +495,6 @@ private:
495 495
     static void M48();
496 496
   #endif
497 497
 
498
-  #if ENABLED(G26_MESH_VALIDATION)
499
-    static void M49();
500
-  #endif
501
-
502 498
   #if ENABLED(LCD_SET_PROGRESS_MANUALLY)
503 499
     static void M73();
504 500
   #endif

+ 1
- 1
Marlin/src/gcode/geometry/G53-G59.cpp View File

@@ -59,7 +59,7 @@ bool GcodeSuite::select_coordinate_system(const int8_t _new) {
59 59
  *
60 60
  * Marlin also uses G53 on a line by itself to go back to native space.
61 61
  */
62
-inline void GcodeSuite::G53() {
62
+void GcodeSuite::G53() {
63 63
   const int8_t _system = active_coordinate_system;
64 64
   active_coordinate_system = -1;
65 65
   if (parser.chain()) { // If this command has more following...

+ 1
- 1
Marlin/src/gcode/host/M876.cpp View File

@@ -1,6 +1,6 @@
1 1
 /**
2 2
  * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
3
+ * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4 4
  *
5 5
  * Based on Sprinter and grbl.
6 6
  * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm

+ 4
- 3
Marlin/src/gcode/motion/M290.cpp View File

@@ -25,6 +25,7 @@
25 25
 #if ENABLED(BABYSTEPPING)
26 26
 
27 27
 #include "../gcode.h"
28
+#include "../../feature/babystep.h"
28 29
 #include "../../module/probe.h"
29 30
 #include "../../module/temperature.h"
30 31
 #include "../../module/planner.h"
@@ -49,7 +50,7 @@
49 50
       else {
50 51
         hotend_offset[Z_AXIS][active_extruder] -= offs;
51 52
         SERIAL_ECHO_START();
52
-        SERIAL_ECHOLNPAIR(MSG_IDEX_Z_OFFSET ": ", hotend_offset[Z_AXIS][active_extruder]);
53
+        SERIAL_ECHOLNPAIR(MSG_Z_OFFSET ": ", hotend_offset[Z_AXIS][active_extruder]);
53 54
       }
54 55
     #endif
55 56
   }
@@ -64,7 +65,7 @@ void GcodeSuite::M290() {
64 65
     for (uint8_t a = X_AXIS; a <= Z_AXIS; a++)
65 66
       if (parser.seenval(axis_codes[a]) || (a == Z_AXIS && parser.seenval('S'))) {
66 67
         const float offs = constrain(parser.value_axis_units((AxisEnum)a), -2, 2);
67
-        thermalManager.babystep_axis((AxisEnum)a, offs * planner.settings.axis_steps_per_mm[a]);
68
+        babystep.add_mm((AxisEnum)a, offs);
68 69
         #if ENABLED(BABYSTEP_ZPROBE_OFFSET)
69 70
           if (a == Z_AXIS && (!parser.seen('P') || parser.value_bool())) mod_zprobe_zoffset(offs);
70 71
         #endif
@@ -72,7 +73,7 @@ void GcodeSuite::M290() {
72 73
   #else
73 74
     if (parser.seenval('Z') || parser.seenval('S')) {
74 75
       const float offs = constrain(parser.value_axis_units(Z_AXIS), -2, 2);
75
-      thermalManager.babystep_axis(Z_AXIS, offs * planner.settings.axis_steps_per_mm[Z_AXIS]);
76
+      babystep.add_mm(Z_AXIS, offs);
76 77
       #if ENABLED(BABYSTEP_ZPROBE_OFFSET)
77 78
         if (!parser.seen('P') || parser.value_bool()) mod_zprobe_zoffset(offs);
78 79
       #endif

+ 0
- 4
Marlin/src/gcode/queue.cpp View File

@@ -37,10 +37,6 @@
37 37
   #include "../feature/leds/printer_event_leds.h"
38 38
 #endif
39 39
 
40
-#if ENABLED(POWER_LOSS_RECOVERY)
41
-  #include "../feature/power_loss_recovery.h"
42
-#endif
43
-
44 40
 /**
45 41
  * GCode line number handling. Hosts may opt to include line numbers when
46 42
  * sending commands to Marlin, and lines will be checked for sequentiality.

+ 1
- 1
Marlin/src/gcode/temperature/M141_M191.cpp View File

@@ -1,6 +1,6 @@
1 1
 /**
2 2
  * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
3
+ * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4 4
  *
5 5
  * Based on Sprinter and grbl.
6 6
  * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm

+ 32
- 35
Marlin/src/inc/Conditionals_LCD.h View File

@@ -87,8 +87,8 @@
87 87
     #define U8GLIB_LM6059_AF
88 88
     #define SD_DETECT_INVERTED
89 89
   #elif ENABLED(AZSMZ_12864)
90
-    #define LCD_CONTRAST_MIN  120
91
-    #define LCD_CONTRAST_MAX 255
90
+    #define LCD_CONTRAST_MIN     120
91
+    #define LCD_CONTRAST_MAX     255
92 92
     #define DEFAULT_LCD_CONTRAST 190
93 93
     #define U8GLIB_ST7565_64128N
94 94
   #endif
@@ -139,6 +139,13 @@
139 139
 
140 140
   #define MINIPANEL
141 141
 
142
+#elif ENABLED(FYSETC_MINI_12864)
143
+
144
+  #define DOGLCD
145
+  #define ULTIPANEL
146
+  #define DEFAULT_LCD_CONTRAST 255
147
+  #define LED_COLORS_REDUCE_GREEN
148
+
142 149
 #endif
143 150
 
144 151
 #if EITHER(MAKRPANEL, MINIPANEL)
@@ -313,36 +320,20 @@
313 320
 
314 321
 #define HAS_ADC_BUTTONS     ENABLED(ADC_KEYPAD)
315 322
 
316
-#if HAS_GRAPHICAL_LCD
317
-  /**
318
-   * Default LCD contrast for Graphical LCD displays
319
-   */
320
-  #define HAS_LCD_CONTRAST (                \
321
-       ENABLED(MAKRPANEL)                   \
322
-    || ENABLED(CARTESIO_UI)                 \
323
-    || ENABLED(VIKI2)                       \
324
-    || ENABLED(AZSMZ_12864)                 \
325
-    || ENABLED(miniVIKI)                    \
326
-    || ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) \
327
-  )
328
-  #if HAS_LCD_CONTRAST
329
-    #ifndef LCD_CONTRAST_MIN
330
-      #define LCD_CONTRAST_MIN 0
331
-    #endif
332
-    #ifndef LCD_CONTRAST_MAX
333
-      #define LCD_CONTRAST_MAX 63
334
-    #endif
335
-    #ifndef DEFAULT_LCD_CONTRAST
336
-      #define DEFAULT_LCD_CONTRAST 32
337
-    #endif
323
+/**
324
+ * Default LCD contrast for Graphical LCD displays
325
+ */
326
+#define HAS_LCD_CONTRAST HAS_GRAPHICAL_LCD && defined(DEFAULT_LCD_CONTRAST)
327
+#if HAS_LCD_CONTRAST
328
+  #ifndef LCD_CONTRAST_MIN
329
+    #define LCD_CONTRAST_MIN 0
330
+  #endif
331
+  #ifndef LCD_CONTRAST_MAX
332
+    #define LCD_CONTRAST_MAX 63
333
+  #endif
334
+  #ifndef DEFAULT_LCD_CONTRAST
335
+    #define DEFAULT_LCD_CONTRAST 32
338 336
   #endif
339
-#endif
340
-
341
-// Boot screens
342
-#if !HAS_SPI_LCD
343
-  #undef SHOW_BOOTSCREEN
344
-#elif !defined(BOOTSCREEN_TIMEOUT)
345
-  #define BOOTSCREEN_TIMEOUT 2500
346 337
 #endif
347 338
 
348 339
 /**
@@ -434,7 +425,7 @@
434 425
  */
435 426
 #if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1
436 427
   #define XYZE_N (XYZ + E_STEPPERS)
437
-  #define E_AXIS_N(E) (E_AXIS + E)
428
+  #define E_AXIS_N(E) AxisEnum(E_AXIS + E)
438 429
 #else
439 430
   #undef DISTINCT_E_FACTORS
440 431
   #define XYZE_N XYZE
@@ -517,9 +508,11 @@
517 508
 #define HAS_FILAMENT_SENSOR   ENABLED(FILAMENT_RUNOUT_SENSOR)
518 509
 
519 510
 #define Z_MULTI_STEPPER_DRIVERS EITHER(Z_DUAL_STEPPER_DRIVERS, Z_TRIPLE_STEPPER_DRIVERS)
520
-#define Z_MULTI_ENDSTOPS EITHER(Z_DUAL_ENDSTOPS, Z_TRIPLE_ENDSTOPS)
521
-#define HAS_EXTRA_ENDSTOPS (EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS)
522
-#define HAS_GAME_MENU (1 < ENABLED(MARLIN_BRICKOUT) + ENABLED(MARLIN_INVADERS) + ENABLED(MARLIN_SNAKE))
511
+#define Z_MULTI_ENDSTOPS        EITHER(Z_DUAL_ENDSTOPS, Z_TRIPLE_ENDSTOPS)
512
+#define HAS_EXTRA_ENDSTOPS     (EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS)
513
+
514
+#define HAS_GAMES     ANY(MARLIN_BRICKOUT, MARLIN_INVADERS, MARLIN_SNAKE, MARLIN_MAZE)
515
+#define HAS_GAME_MENU (1 < ENABLED(MARLIN_BRICKOUT) + ENABLED(MARLIN_INVADERS) + ENABLED(MARLIN_SNAKE) + ENABLED(MARLIN_MAZE))
523 516
 
524 517
 #define IS_SCARA     EITHER(MORGAN_SCARA, MAKERARM_SCARA)
525 518
 #define IS_KINEMATIC (ENABLED(DELTA) || IS_SCARA)
@@ -563,3 +556,7 @@
563 556
     #endif
564 557
   #endif
565 558
 #endif
559
+
560
+#if ENABLED(SLIM_LCD_MENUS)
561
+  #define BOOT_MARLIN_LOGO_SMALL
562
+#endif

+ 2
- 5
Marlin/src/inc/Conditionals_post.h View File

@@ -873,9 +873,6 @@
873 873
   #define TMC_HAS_SPI       (HAS_TMCX1X0 || HAS_DRIVER(TMC2660))
874 874
   #define HAS_STALLGUARD    (HAS_TMCX1X0 || HAS_DRIVER(TMC2660))
875 875
   #define HAS_STEALTHCHOP   (HAS_TMCX1X0 || HAS_DRIVER(TMC2208))
876
-  #define AXIS_HAS_SPI(ST)         (AXIS_DRIVER_TYPE(ST, TMC2130) || AXIS_DRIVER_TYPE(ST, TMC2160) || AXIS_DRIVER_TYPE(ST, TMC2660))
877
-  #define AXIS_HAS_STALLGUARD(ST)  (AXIS_DRIVER_TYPE(ST, TMC2130) || AXIS_DRIVER_TYPE(ST, TMC2160) || AXIS_DRIVER_TYPE(ST, TMC2660) || AXIS_DRIVER_TYPE(ST, TMC5130) || AXIS_DRIVER_TYPE(ST, TMC5160))
878
-  #define AXIS_HAS_STEALTHCHOP(ST) (AXIS_DRIVER_TYPE(ST, TMC2130) || AXIS_DRIVER_TYPE(ST, TMC2160) || AXIS_DRIVER_TYPE(ST, TMC2208) || AXIS_DRIVER_TYPE(ST, TMC5130) || AXIS_DRIVER_TYPE(ST, TMC5160))
879 876
 
880 877
   #define STEALTHCHOP_ENABLED ANY(STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_E)
881 878
   #define USE_SENSORLESS EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING)
@@ -921,7 +918,7 @@
921 918
 #define HAS_TEMP_HOTEND (HAS_TEMP_ADC_0 || ENABLED(HEATER_0_USES_MAX6675))
922 919
 #define HAS_TEMP_BED HAS_TEMP_ADC_BED
923 920
 #define HAS_TEMP_CHAMBER HAS_TEMP_ADC_CHAMBER
924
-#define HAS_HEATED_CHAMBER (HAS_TEMP_CHAMBER && PIN_EXISTS(CHAMBER_HEATER))
921
+#define HAS_HEATED_CHAMBER (HAS_TEMP_CHAMBER && PIN_EXISTS(HEATER_CHAMBER))
925 922
 
926 923
 // Heaters
927 924
 #define HAS_HEATER_0 (PIN_EXISTS(HEATER_0))
@@ -1679,7 +1676,7 @@
1679 1676
 // Get LCD character width/height, which may be overridden by pins, configs, etc.
1680 1677
 #ifndef LCD_WIDTH
1681 1678
   #if HAS_GRAPHICAL_LCD
1682
-    #define LCD_WIDTH 22
1679
+    #define LCD_WIDTH 21
1683 1680
   #elif ENABLED(ULTIPANEL)
1684 1681
     #define LCD_WIDTH 20
1685 1682
   #elif HAS_SPI_LCD

+ 9
- 0
Marlin/src/inc/SanityCheck.h View File

@@ -341,6 +341,10 @@
341 341
   #error "MAX6675_SS is now MAX6675_SS_PIN. Please update your configuration and/or pins."
342 342
 #elif defined(MAX6675_SS2)
343 343
   #error "MAX6675_SS2 is now MAX6675_SS2_PIN. Please update your configuration and/or pins."
344
+#elif defined(SPINDLE_LASER_ENABLE_PIN)
345
+  #error "SPINDLE_LASER_ENABLE_PIN is now SPINDLE_LASER_ENA_PIN. Please update your configuration and/or pins."
346
+#elif defined(CHAMBER_HEATER_PIN)
347
+  #error "CHAMBER_HEATER_PIN is now HEATER_CHAMBER_PIN. Please update your configuration and/or pins."
344 348
 #elif defined(TMC_Z_CALIBRATION)
345 349
   #error "TMC_Z_CALIBRATION has been deprecated in favor of Z_STEPPER_AUTO_ALIGN. Please update your configuration."
346 350
 #elif defined(Z_MIN_PROBE_ENDSTOP)
@@ -551,6 +555,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
551 555
   #endif
552 556
 #endif
553 557
 
558
+#if defined(EVENT_GCODE_SD_STOP) && DISABLED(NOZZLE_PARK_FEATURE)
559
+  static_assert(NULL == strstr(EVENT_GCODE_SD_STOP, "G27"), "NOZZLE_PARK_FEATURE is required to use G27 in EVENT_GCODE_SD_STOP.");
560
+#endif
561
+
554 562
 /**
555 563
  * I2C Position Encoders
556 564
  */
@@ -1758,6 +1766,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1758 1766
   + ENABLED(G3D_PANEL) \
1759 1767
   + (ENABLED(MINIPANEL) && DISABLED(MKS_MINI_12864)) \
1760 1768
   + ENABLED(MKS_MINI_12864) \
1769
+  + ENABLED(FYSETC_MINI_12864) \
1761 1770
   + (ENABLED(REPRAPWORLD_KEYPAD) && DISABLED(CARTESIO_UI, ZONESTAR_LCD)) \
1762 1771
   + ENABLED(RIGIDBOT_PANEL) \
1763 1772
   + ENABLED(RA_CONTROL_PANEL) \

+ 11
- 1
Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp View File

@@ -1025,7 +1025,7 @@ void MarlinUI::draw_status_screen() {
1025 1025
   }
1026 1026
 
1027 1027
   void draw_edit_screen(PGM_P const pstr, const char* const value/*=NULL*/) {
1028
-    lcd_moveto(1, 1);
1028
+    lcd_moveto(0, 1);
1029 1029
     lcd_put_u8str_P(pstr);
1030 1030
     if (value != NULL) {
1031 1031
       lcd_put_wchar(':');
@@ -1037,6 +1037,16 @@ void MarlinUI::draw_status_screen() {
1037 1037
     }
1038 1038
   }
1039 1039
 
1040
+  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) {
1041
+    SETCURSOR(0, 0); lcd_put_u8str_P(pref);
1042
+    if (string) wrap_string(1, string);
1043
+    if (suff) lcd_put_u8str_P(suff);
1044
+    SETCURSOR(0, LCD_HEIGHT - 1);
1045
+    lcd_put_wchar(yesno ? ' ' : '['); lcd_put_u8str_P(no); lcd_put_wchar(yesno ? ' ' : ']');
1046
+    SETCURSOR_RJ(utf8_strlen_P(yes) + 2, LCD_HEIGHT - 1);
1047
+    lcd_put_wchar(yesno ? '[' : ' '); lcd_put_u8str_P(yes); lcd_put_wchar(yesno ? ']' : ' ');
1048
+  }
1049
+
1040 1050
   #if ENABLED(SDSUPPORT)
1041 1051
 
1042 1052
     void draw_sd_menu_item(const bool sel, const uint8_t row, PGM_P const pstr, CardReader &theCard, const bool isDir) {

+ 1
- 1
Marlin/src/lcd/dogm/HAL_LCD_com_defines.h View File

@@ -47,7 +47,7 @@
47 47
   uint8_t u8g_com_HAL_LPC1768_ssd_hw_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr);
48 48
   #define U8G_COM_SSD_I2C_HAL u8g_com_arduino_ssd_i2c_fn
49 49
 
50
-  #if defined(ARDUINO_ARCH_STM32F1)
50
+  #ifdef ARDUINO_ARCH_STM32F1
51 51
     uint8_t u8g_com_stm32duino_fsmc_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr);
52 52
     #define U8G_COM_HAL_FSMC_FN u8g_com_stm32duino_fsmc_fn
53 53
   #else

+ 83
- 93
Marlin/src/lcd/dogm/dogm_Bootscreen.h View File

@@ -29,107 +29,97 @@
29 29
 
30 30
 #include "../../inc/MarlinConfig.h"
31 31
 
32
-#if ENABLED(SHOW_BOOTSCREEN)
32
+#if ENABLED(SHOW_CUSTOM_BOOTSCREEN)
33 33
 
34
-  //#define START_BMPHIGH // Costs 399 bytes more flash
35
-
36
-  #if ENABLED(SHOW_CUSTOM_BOOTSCREEN)
37
-
38
-    #include "../../../_Bootscreen.h"
39
-
40
-    #ifndef CUSTOM_BOOTSCREEN_TIMEOUT
41
-      #define CUSTOM_BOOTSCREEN_TIMEOUT 2500
42
-    #endif
34
+  #include "../../../_Bootscreen.h"
43 35
 
36
+  #ifndef CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH
37
+    #define CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH ((CUSTOM_BOOTSCREEN_BMPWIDTH + 7) / 8)
44 38
   #endif
45
-
46
-  #if ENABLED(START_BMPHIGH)
47
-
48
-    #define START_BMPWIDTH      112
49
-
50
-    const unsigned char start_bmp[] PROGMEM = {
51
-      B00000001,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
52
-      B00001111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
53
-      B00011110,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B11111111,B11111111,
54
-      B00111000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000011,B11111111,B11111111,
55
-      B01110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000001,B11111111,B11111111,
56
-      B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B11111111,B11111111,
57
-      B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01111111,B11111111,
58
-      B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00000000,B00000000,B00111111,B11111111,
59
-      B11000000,B00001111,B11000000,B11111100,B00000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00011000,B00000000,B00011111,B11111111,
60
-      B11000000,B00111111,B11100001,B11111111,B00000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00111100,B00000000,B00001111,B11111111,
61
-      B11000000,B01111111,B11110011,B11111111,B10000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00111100,B00000000,B00000111,B11111111,
62
-      B11000000,B11111111,B11111111,B11111111,B11000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00111100,B00000000,B00000011,B11111111,
63
-      B11000001,B11111000,B01111111,B10000111,B11100000,B00000000,B00000000,B00000000,B00000000,B01111000,B00000000,B00000000,B00000001,B11111111,
64
-      B11000001,B11110000,B00111111,B00000011,B11100000,B00000000,B00000000,B00000000,B00000000,B01111000,B00000000,B00000000,B00000000,B11111111,
65
-      B11000001,B11100000,B00011110,B00000001,B11100000,B00011111,B00000000,B00000011,B11100000,B01111000,B00111100,B00000011,B11110000,B01111111,
66
-      B11000001,B11100000,B00011110,B00000001,B11100000,B01111111,B11000000,B00001111,B11111000,B01111000,B00111100,B00000111,B11111100,B00111111,
67
-      B11000001,B11100000,B00011110,B00000001,B11100001,B11111111,B11100000,B00011111,B11111100,B01111000,B00111100,B00001111,B11111110,B00011111,
68
-      B11000001,B11100000,B00011110,B00000001,B11100011,B11111111,B11110000,B00111111,B11111110,B01111000,B00111100,B00011111,B11111110,B00001111,
69
-      B11000001,B11100000,B00011110,B00000001,B11100011,B11110011,B11111000,B00111111,B00111110,B01111000,B00111100,B00111111,B00111111,B00000111,
70
-      B11000001,B11100000,B00011110,B00000001,B11100111,B11100000,B11111100,B01111100,B00011111,B01111000,B00111100,B00111110,B00011111,B00000111,
71
-      B11000001,B11100000,B00011110,B00000001,B11100111,B11000000,B01111100,B01111100,B00001111,B01111000,B00111100,B00111100,B00001111,B00000011,
72
-      B11000001,B11100000,B00011110,B00000001,B11100111,B10000000,B01111100,B01111000,B00001111,B01111000,B00111100,B00111100,B00001111,B00000011,
73
-      B11000001,B11100000,B00011110,B00000001,B11100111,B10000000,B00111100,B01111000,B00000000,B01111000,B00111100,B00111100,B00001111,B00000011,
74
-      B11000001,B11100000,B00011110,B00000001,B11100111,B10000000,B00111100,B01111000,B00000000,B01111000,B00111100,B00111100,B00001111,B00000011,
75
-      B11000001,B11100000,B00011110,B00000001,B11100111,B10000000,B00111100,B01111000,B00000000,B01111000,B00111100,B00111100,B00001111,B00000011,
76
-      B11000001,B11100000,B00011110,B00000001,B11100111,B11000000,B00111100,B01111000,B00000000,B01111000,B00111100,B00111100,B00001111,B00000011,
77
-      B11000001,B11100000,B00011110,B00000001,B11100011,B11100000,B00111100,B01111000,B00000000,B01111100,B00111100,B00111100,B00001111,B00000011,
78
-      B11000001,B11100000,B00011110,B00000001,B11100011,B11111111,B00111111,B11111000,B00000000,B01111111,B10111100,B00111100,B00001111,B00000011,
79
-      B11000001,B11100000,B00011110,B00000001,B11100001,B11111111,B00111111,B11111000,B00000000,B00111111,B10111111,B11111100,B00001111,B00000011,
80
-      B11000001,B11100000,B00011110,B00000001,B11100000,B11111111,B00111111,B11111000,B00000000,B00011111,B10111111,B11111100,B00001111,B00000011,
81
-      B11000001,B11100000,B00011110,B00000001,B11100000,B01111111,B00111111,B11111000,B00000000,B00001111,B10111111,B11111100,B00001111,B00000011,
82
-      B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,
83
-      B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,
84
-      B01110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00001110,
85
-      B00111000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00011100,
86
-      B00011110,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01111000,
87
-      B00001111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11110000,
88
-      B00000001,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B10000000
89
-    };
90
-
91
-  #else
92
-
93
-    #define START_BMPWIDTH      56
94
-
95
-    const unsigned char start_bmp[] PROGMEM = {
96
-      B00011111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
97
-      B01100000,B00000000,B00000000,B00000000,B00000000,B00000001,B11111111,
98
-      B01000000,B00000000,B00000000,B00000000,B00000000,B00000000,B11111111,
99
-      B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01111111,
100
-      B10000011,B11001111,B00000000,B00000000,B00001100,B00110000,B00111111,
101
-      B10000111,B11111111,B10000000,B00000000,B00001100,B00110000,B00011111,
102
-      B10000110,B01111001,B10000000,B00000000,B00001100,B00000000,B00001111,
103
-      B10001100,B00110000,B11000111,B10000011,B10001100,B00110000,B11100111,
104
-      B10001100,B00110000,B11001111,B11000111,B11001100,B00110001,B11110011,
105
-      B10001100,B00110000,B11011100,B11101100,B11101100,B00110011,B10111001,
106
-      B10001100,B00110000,B11011000,B01101100,B01101100,B00110011,B00011001,
107
-      B10001100,B00110000,B11010000,B01101100,B00001100,B00110011,B00011001,
108
-      B10001100,B00110000,B11011000,B01101100,B00001100,B00110011,B00011001,
109
-      B10001100,B00110000,B11011100,B01101100,B00001110,B00111011,B00011001,
110
-      B10001100,B00110000,B11001111,B01111100,B00000111,B10011111,B00011001,
111
-      B10001100,B00110000,B11000111,B01111100,B00000011,B10001111,B00011001,
112
-      B01000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000010,
113
-      B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,
114
-      B00011111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111000
115
-    };
116
-
39
+  #ifndef CUSTOM_BOOTSCREEN_BMPHEIGHT
40
+    #define CUSTOM_BOOTSCREEN_BMPHEIGHT (sizeof(custom_start_bmp) / (CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH))
117 41
   #endif
118 42
 
119
-  #ifndef START_BMP_BYTEWIDTH
120
-    #define START_BMP_BYTEWIDTH ((START_BMPWIDTH + 7) / 8)
121
-  #endif
122
-  #ifndef START_BMPHEIGHT
123
-    #define START_BMPHEIGHT (sizeof(start_bmp) / (START_BMP_BYTEWIDTH))
124
-  #endif
43
+#endif
125 44
 
126
-  static_assert(sizeof(start_bmp) == (START_BMP_BYTEWIDTH) * (START_BMPHEIGHT), "Bootscreen (start_bmp) dimensions don't match data.");
45
+#if ENABLED(BOOT_MARLIN_LOGO_SMALL)
46
+
47
+  #define START_BMPWIDTH      56
48
+
49
+  const unsigned char start_bmp[] PROGMEM = {
50
+    B00011111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
51
+    B01100000,B00000000,B00000000,B00000000,B00000000,B00000001,B11111111,
52
+    B01000000,B00000000,B00000000,B00000000,B00000000,B00000000,B11111111,
53
+    B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01111111,
54
+    B10000011,B11001111,B00000000,B00000000,B00001100,B00110000,B00111111,
55
+    B10000111,B11111111,B10000000,B00000000,B00001100,B00110000,B00011111,
56
+    B10000110,B01111001,B10000000,B00000000,B00001100,B00000000,B00001111,
57
+    B10001100,B00110000,B11000111,B10000011,B10001100,B00110000,B11100111,
58
+    B10001100,B00110000,B11001111,B11000111,B11001100,B00110001,B11110011,
59
+    B10001100,B00110000,B11011100,B11101100,B11101100,B00110011,B10111001,
60
+    B10001100,B00110000,B11011000,B01101100,B01101100,B00110011,B00011001,
61
+    B10001100,B00110000,B11010000,B01101100,B00001100,B00110011,B00011001,
62
+    B10001100,B00110000,B11011000,B01101100,B00001100,B00110011,B00011001,
63
+    B10001100,B00110000,B11011100,B01101100,B00001110,B00111011,B00011001,
64
+    B10001100,B00110000,B11001111,B01111100,B00000111,B10011111,B00011001,
65
+    B10001100,B00110000,B11000111,B01111100,B00000011,B10001111,B00011001,
66
+    B01000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000010,
67
+    B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,
68
+    B00011111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111000
69
+  };
70
+
71
+#else
72
+
73
+  #define START_BMPWIDTH      112
74
+
75
+  const unsigned char start_bmp[] PROGMEM = {
76
+    B00000001,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
77
+    B00001111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
78
+    B00011110,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B11111111,B11111111,
79
+    B00111000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000011,B11111111,B11111111,
80
+    B01110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000001,B11111111,B11111111,
81
+    B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B11111111,B11111111,
82
+    B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01111111,B11111111,
83
+    B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00000000,B00000000,B00111111,B11111111,
84
+    B11000000,B00001111,B11000000,B11111100,B00000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00011000,B00000000,B00011111,B11111111,
85
+    B11000000,B00111111,B11100001,B11111111,B00000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00111100,B00000000,B00001111,B11111111,
86
+    B11000000,B01111111,B11110011,B11111111,B10000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00111100,B00000000,B00000111,B11111111,
87
+    B11000000,B11111111,B11111111,B11111111,B11000000,B00000000,B00000000,B00000000,B00000000,B01111000,B00111100,B00000000,B00000011,B11111111,
88
+    B11000001,B11111000,B01111111,B10000111,B11100000,B00000000,B00000000,B00000000,B00000000,B01111000,B00000000,B00000000,B00000001,B11111111,
89
+    B11000001,B11110000,B00111111,B00000011,B11100000,B00000000,B00000000,B00000000,B00000000,B01111000,B00000000,B00000000,B00000000,B11111111,
90
+    B11000001,B11100000,B00011110,B00000001,B11100000,B00011111,B00000000,B00000011,B11100000,B01111000,B00111100,B00000011,B11110000,B01111111,
91
+    B11000001,B11100000,B00011110,B00000001,B11100000,B01111111,B11000000,B00001111,B11111000,B01111000,B00111100,B00000111,B11111100,B00111111,
92
+    B11000001,B11100000,B00011110,B00000001,B11100001,B11111111,B11100000,B00011111,B11111100,B01111000,B00111100,B00001111,B11111110,B00011111,
93
+    B11000001,B11100000,B00011110,B00000001,B11100011,B11111111,B11110000,B00111111,B11111110,B01111000,B00111100,B00011111,B11111110,B00001111,
94
+    B11000001,B11100000,B00011110,B00000001,B11100011,B11110011,B11111000,B00111111,B00111110,B01111000,B00111100,B00111111,B00111111,B00000111,
95
+    B11000001,B11100000,B00011110,B00000001,B11100111,B11100000,B11111100,B01111100,B00011111,B01111000,B00111100,B00111110,B00011111,B00000111,
96
+    B11000001,B11100000,B00011110,B00000001,B11100111,B11000000,B01111100,B01111100,B00001111,B01111000,B00111100,B00111100,B00001111,B00000011,
97
+    B11000001,B11100000,B00011110,B00000001,B11100111,B10000000,B01111100,B01111000,B00001111,B01111000,B00111100,B00111100,B00001111,B00000011,
98
+    B11000001,B11100000,B00011110,B00000001,B11100111,B10000000,B00111100,B01111000,B00000000,B01111000,B00111100,B00111100,B00001111,B00000011,
99
+    B11000001,B11100000,B00011110,B00000001,B11100111,B10000000,B00111100,B01111000,B00000000,B01111000,B00111100,B00111100,B00001111,B00000011,
100
+    B11000001,B11100000,B00011110,B00000001,B11100111,B10000000,B00111100,B01111000,B00000000,B01111000,B00111100,B00111100,B00001111,B00000011,
101
+    B11000001,B11100000,B00011110,B00000001,B11100111,B11000000,B00111100,B01111000,B00000000,B01111000,B00111100,B00111100,B00001111,B00000011,
102
+    B11000001,B11100000,B00011110,B00000001,B11100011,B11100000,B00111100,B01111000,B00000000,B01111100,B00111100,B00111100,B00001111,B00000011,
103
+    B11000001,B11100000,B00011110,B00000001,B11100011,B11111111,B00111111,B11111000,B00000000,B01111111,B10111100,B00111100,B00001111,B00000011,
104
+    B11000001,B11100000,B00011110,B00000001,B11100001,B11111111,B00111111,B11111000,B00000000,B00111111,B10111111,B11111100,B00001111,B00000011,
105
+    B11000001,B11100000,B00011110,B00000001,B11100000,B11111111,B00111111,B11111000,B00000000,B00011111,B10111111,B11111100,B00001111,B00000011,
106
+    B11000001,B11100000,B00011110,B00000001,B11100000,B01111111,B00111111,B11111000,B00000000,B00001111,B10111111,B11111100,B00001111,B00000011,
107
+    B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,
108
+    B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,
109
+    B01110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00001110,
110
+    B00111000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00011100,
111
+    B00011110,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01111000,
112
+    B00001111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11110000,
113
+    B00000001,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B10000000
114
+  };
127 115
 
128 116
 #endif
129 117
 
130
-#ifndef CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH
131
-  #define CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH ((CUSTOM_BOOTSCREEN_BMPWIDTH + 7) / 8)
118
+#ifndef START_BMP_BYTEWIDTH
119
+  #define START_BMP_BYTEWIDTH ((START_BMPWIDTH + 7) / 8)
132 120
 #endif
133
-#ifndef CUSTOM_BOOTSCREEN_BMPHEIGHT
134
-  #define CUSTOM_BOOTSCREEN_BMPHEIGHT (sizeof(custom_start_bmp) / (CUSTOM_BOOTSCREEN_BMP_BYTEWIDTH))
121
+#ifndef START_BMPHEIGHT
122
+  #define START_BMPHEIGHT (sizeof(start_bmp) / (START_BMP_BYTEWIDTH))
135 123
 #endif
124
+
125
+static_assert(sizeof(start_bmp) == (START_BMP_BYTEWIDTH) * (START_BMPHEIGHT), "Bootscreen (start_bmp) dimensions don't match data.");

+ 1
- 1
Marlin/src/lcd/dogm/u8g_fontutf8.cpp View File

@@ -97,7 +97,7 @@ static void fontgroup_drawwchar(font_group_t *group, const font_t *fnt_default,
97 97
  * @param utf8_msg : the UTF-8 string
98 98
  * @param cb_read_byte : how to read the utf8_msg, from RAM or ROM (call read_byte_ram or pgm_read_byte)
99 99
  * @param userdata : User's data
100
- * @param cb_draw_ram : the callback function of userdata to draw a !RAM! string (actural it is to draw a one byte string in RAM)
100
+ * @param cb_draw_ram : the callback function of userdata to draw a !RAM! string (actually it is to draw a one byte string in RAM)
101 101
  *
102 102
  * @return N/A
103 103
  *

+ 91
- 37
Marlin/src/lcd/dogm/ultralcd_DOGM.cpp View File

@@ -41,7 +41,10 @@
41 41
 
42 42
 #include "ultralcd_DOGM.h"
43 43
 #include "u8g_fontutf8.h"
44
-#include "dogm_Bootscreen.h"
44
+
45
+#if ENABLED(SHOW_BOOTSCREEN)
46
+  #include "dogm_Bootscreen.h"
47
+#endif
45 48
 
46 49
 #include "../lcdprint.h"
47 50
 #include "../fontutils.h"
@@ -138,6 +141,9 @@ void MarlinUI::set_font(const MarlinFont font_nr) {
138 141
       #else
139 142
         draw_custom_bootscreen(custom_start_bmp);
140 143
       #endif
144
+      #ifndef CUSTOM_BOOTSCREEN_TIMEOUT
145
+        #define CUSTOM_BOOTSCREEN_TIMEOUT 2500
146
+      #endif
141 147
       safe_delay(CUSTOM_BOOTSCREEN_TIMEOUT);
142 148
     }
143 149
 
@@ -148,31 +154,58 @@ void MarlinUI::set_font(const MarlinFont font_nr) {
148 154
       lcd_custom_bootscreen();
149 155
     #endif
150 156
 
151
-    constexpr uint8_t offy =
152
-      #if ENABLED(START_BMPHIGH)
153
-        (LCD_PIXEL_HEIGHT - (START_BMPHEIGHT)) / 2
154
-      #else
155
-        MENU_FONT_HEIGHT
156
-      #endif
157
-    ;
157
+    // Screen dimensions.
158
+    //const uint8_t width = u8g.getWidth(), height = u8g.getHeight();
159
+    constexpr uint8_t width = LCD_PIXEL_WIDTH, height = LCD_PIXEL_HEIGHT;
158 160
 
159
-    const uint8_t width = u8g.getWidth(), height = u8g.getHeight(),
160
-                  offx = (width - (START_BMPWIDTH)) / 2;
161
+    // Determine text space needed
162
+    #ifndef STRING_SPLASH_LINE2
163
+      constexpr uint8_t text_total_height = MENU_FONT_HEIGHT,
164
+                        text_width_1 = (sizeof(STRING_SPLASH_LINE1) - 1) * (MENU_FONT_WIDTH),
165
+                        text_width_2 = 0;
166
+    #else
167
+      constexpr uint8_t text_total_height = (MENU_FONT_HEIGHT) * 2,
168
+                        text_width_1 = (sizeof(STRING_SPLASH_LINE1) - 1) * (MENU_FONT_WIDTH),
169
+                        text_width_2 = (sizeof(STRING_SPLASH_LINE2) - 1) * (MENU_FONT_WIDTH);
170
+    #endif
171
+    constexpr uint8_t text_max_width = MAX(text_width_1, text_width_2),
172
+                      rspace = width - (START_BMPWIDTH);
173
+
174
+    int8_t offx, offy, txt_base, txt_offx_1, txt_offx_2;
175
+
176
+    // Can the text fit to the right of the bitmap?
177
+    if (text_max_width < rspace) {
178
+      constexpr uint8_t inter = (width - text_max_width - (START_BMPWIDTH)) / 3; // Evenly distribute horizontal space
179
+      offx = inter;                             // First the boot logo...
180
+      offy = (height - (START_BMPHEIGHT)) / 2;  // ...V-aligned in the full height
181
+      txt_offx_1 = txt_offx_2 = inter + (START_BMPWIDTH) + inter; // Text right of the bitmap
182
+      txt_base = (height + MENU_FONT_ASCENT + text_total_height - (MENU_FONT_HEIGHT)) / 2; // Text vertical center
183
+    }
184
+    else {
185
+      constexpr uint8_t inter = (height - text_total_height - (START_BMPHEIGHT)) / 3; // Evenly distribute vertical space
186
+      offy = inter;                             // V-align boot logo proportionally
187
+      offx = rspace / 2;                        // Center the boot logo in the whole space
188
+      txt_offx_1 = (width - text_width_1) / 2;  // Text 1 centered
189
+      txt_offx_2 = (width - text_width_2) / 2;  // Text 2 centered
190
+      txt_base = offy + START_BMPHEIGHT + offy + text_total_height - (MENU_FONT_DESCENT);   // Even spacing looks best
191
+    }
192
+    NOLESS(offx, 0);
193
+    NOLESS(offy, 0);
161 194
 
162 195
     u8g.firstPage();
163 196
     do {
164 197
       u8g.drawBitmapP(offx, offy, (START_BMPWIDTH + 7) / 8, START_BMPHEIGHT, start_bmp);
165 198
       set_font(FONT_MENU);
166 199
       #ifndef STRING_SPLASH_LINE2
167
-        const uint8_t txt1X = width - (sizeof(STRING_SPLASH_LINE1) - 1) * (MENU_FONT_WIDTH);
168
-        u8g.drawStr(txt1X, (height + MENU_FONT_HEIGHT) / 2, STRING_SPLASH_LINE1);
200
+        u8g.drawStr(txt_offx_1, txt_base, STRING_SPLASH_LINE1);
169 201
       #else
170
-        const uint8_t txt1X = (width - (sizeof(STRING_SPLASH_LINE1) - 1) * (MENU_FONT_WIDTH)) / 2,
171
-                      txt2X = (width - (sizeof(STRING_SPLASH_LINE2) - 1) * (MENU_FONT_WIDTH)) / 2;
172
-        u8g.drawStr(txt1X, height - (MENU_FONT_HEIGHT) * 3 / 2, STRING_SPLASH_LINE1);
173
-        u8g.drawStr(txt2X, height - (MENU_FONT_HEIGHT) * 1 / 2, STRING_SPLASH_LINE2);
202
+        u8g.drawStr(txt_offx_1, txt_base - (MENU_FONT_HEIGHT), STRING_SPLASH_LINE1);
203
+        u8g.drawStr(txt_offx_2, txt_base, STRING_SPLASH_LINE2);
174 204
       #endif
175 205
     } while (u8g.nextPage());
206
+    #ifndef BOOTSCREEN_TIMEOUT
207
+      #define BOOTSCREEN_TIMEOUT 2500
208
+    #endif
176 209
     safe_delay(BOOTSCREEN_TIMEOUT);
177 210
   }
178 211
 
@@ -380,7 +413,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
380 413
     if (value != NULL) {
381 414
       lcd_put_wchar(':');
382 415
       if (extra_row) {
383
-        // Assume the value is numeric (with no descender)
416
+        // Assume that value is numeric (with no descender)
384 417
         baseline += EDIT_FONT_ASCENT + 2;
385 418
         onpage = PAGE_CONTAINS(baseline - (EDIT_FONT_ASCENT - 1), baseline);
386 419
       }
@@ -392,6 +425,27 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
392 425
     }
393 426
   }
394 427
 
428
+  inline void draw_boxed_string(const uint8_t x, const uint8_t y, PGM_P const pstr, const bool inv) {
429
+    const uint8_t len = utf8_strlen_P(pstr), bw = len * (MENU_FONT_WIDTH),
430
+                  bx = x * (MENU_FONT_WIDTH), by = (y + 1) * (MENU_FONT_HEIGHT);
431
+    if (inv) {
432
+      u8g.setColorIndex(1);
433
+      u8g.drawBox(bx - 1, by - (MENU_FONT_ASCENT) + 1, bw + 2, MENU_FONT_HEIGHT - 1);
434
+      u8g.setColorIndex(0);
435
+    }
436
+    lcd_moveto(bx, by);
437
+    lcd_put_u8str_P(pstr);
438
+    if (inv) u8g.setColorIndex(1);
439
+  }
440
+
441
+  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) {
442
+    SETCURSOR(0, 0); lcd_put_u8str_P(pref);
443
+    if (string) wrap_string(1, string);
444
+    if (suff) lcd_put_u8str_P(suff);
445
+    draw_boxed_string(1, LCD_HEIGHT - 1, no, !yesno);
446
+    draw_boxed_string(LCD_WIDTH - (utf8_strlen_P(yes) + 1), LCD_HEIGHT - 1, yes, yesno);
447
+  }
448
+
395 449
   #if ENABLED(SDSUPPORT)
396 450
 
397 451
     void draw_sd_menu_item(const bool sel, const uint8_t row, PGM_P const pstr, CardReader &theCard, const bool isDir) {
@@ -500,22 +554,22 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
500 554
   #if EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY)
501 555
 
502 556
     const unsigned char cw_bmp[] PROGMEM = {
503
-      B00000011,B11111000,B00000000,
504
-      B00001111,B11111110,B00000000,
505
-      B00011110,B00001111,B00000000,
506
-      B00111000,B00000111,B00000000,
507
-      B00111000,B00000011,B10000000,
508
-      B01110000,B00000011,B10000000,
509
-      B01110000,B00001111,B11100000,
510
-      B01110000,B00000111,B11000000,
511
-      B01110000,B00000011,B10000000,
512
-      B01110000,B00000001,B00000000,
513
-      B01110000,B00000000,B00000000,
514
-      B00111000,B00000000,B00000000,
515
-      B00111000,B00000111,B00000000,
516
-      B00011110,B00001111,B00000000,
517
-      B00001111,B11111110,B00000000,
518
-      B00000011,B11111000,B00000000
557
+      B00000001,B11111100,B00000000,
558
+      B00000111,B11111111,B00000000,
559
+      B00001111,B00000111,B10000000,
560
+      B00001110,B00000001,B11000000,
561
+      B00000000,B00000001,B11000000,
562
+      B00000000,B00000000,B11100000,
563
+      B00001000,B00000000,B11100000,
564
+      B00011100,B00000000,B11100000,
565
+      B00111110,B00000000,B11100000,
566
+      B01111111,B00000000,B11100000,
567
+      B00011100,B00000000,B11100000,
568
+      B00001110,B00000000,B11100000,
569
+      B00001110,B00000001,B11000000,
570
+      B00000111,B10000011,B11000000,
571
+      B00000011,B11111111,B10000000,
572
+      B00000000,B11111110,B00000000
519 573
     };
520 574
 
521 575
     const unsigned char ccw_bmp[] PROGMEM = {
@@ -615,10 +669,10 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
615 669
 
616 670
       // Draw cw/ccw indicator and up/down arrows.
617 671
       if (PAGE_CONTAINS(47, 62)) {
618
-        u8g.drawBitmapP(left  + 0, 47, 3, 16, rot_down);
619
-        u8g.drawBitmapP(right + 0, 47, 3, 16, rot_up);
620
-        u8g.drawBitmapP(right + 20, 48 - dir, 2, 13, up_arrow_bmp);
621
-        u8g.drawBitmapP(left  + 20, 49 - dir, 2, 13, down_arrow_bmp);
672
+        u8g.drawBitmapP(right + 0, 48 - dir, 2, 13, up_arrow_bmp);
673
+        u8g.drawBitmapP(left  + 0, 49 - dir, 2, 13, down_arrow_bmp);
674
+        u8g.drawBitmapP(left  + 13, 47, 3, 16, rot_down);
675
+        u8g.drawBitmapP(right + 13, 47, 3, 16, rot_up);
622 676
       }
623 677
     }
624 678
 

+ 1
- 1
Marlin/src/lcd/dogm/ultralcd_DOGM.h View File

@@ -107,7 +107,7 @@
107 107
   // Generic support for SSD1309 OLED I2C LCDs
108 108
   #define U8G_CLASS U8GLIB_SSD1309_128X64
109 109
   #define U8G_PARAM (U8G_I2C_OPT_NONE | U8G_I2C_OPT_FAST)
110
-#elif ENABLED(MINIPANEL)
110
+#elif EITHER(MINIPANEL, FYSETC_MINI_12864)
111 111
   // The MINIPanel display
112 112
   //#define U8G_CLASS U8GLIB_MINI12864
113 113
   //#define U8G_PARAM DOGLCD_CS, DOGLCD_A0                            // 8 stripes

+ 7
- 3
Marlin/src/lcd/extensible_ui/ui_api.cpp View File

@@ -97,6 +97,10 @@
97 97
   #include "../../feature/runout.h"
98 98
 #endif
99 99
 
100
+#if ENABLED(BABYSTEPPING)
101
+  #include "../../feature/babystep.h"
102
+#endif
103
+
100 104
 inline float clamp(const float value, const float minimum, const float maximum) {
101 105
   return MAX(MIN(value, maximum), minimum);
102 106
 }
@@ -584,10 +588,10 @@ namespace ExtUI {
584 588
     bool babystepAxis_steps(const int16_t steps, const axis_t axis) {
585 589
       switch (axis) {
586 590
         #if ENABLED(BABYSTEP_XY)
587
-          case X: thermalManager.babystep_axis(X_AXIS, steps); break;
588
-          case Y: thermalManager.babystep_axis(Y_AXIS, steps); break;
591
+          case X: babystep.add_steps(X_AXIS, steps); break;
592
+          case Y: babystep.add_steps(Y_AXIS, steps); break;
589 593
         #endif
590
-        case Z: thermalManager.babystep_axis(Z_AXIS, steps); break;
594
+        case Z: babystep.add_steps(Z_AXIS, steps); break;
591 595
         default: return false;
592 596
       };
593 597
       return true;

+ 1
- 1
Marlin/src/lcd/extensible_ui/ui_api.h View File

@@ -105,7 +105,7 @@ namespace ExtUI {
105 105
   float getFeedrate_percent();
106 106
   uint8_t getProgress_percent();
107 107
   uint32_t getProgress_seconds_elapsed();
108
-  
108
+
109 109
   #if HAS_LEVELING
110 110
     bool getLevelingActive();
111 111
     void setLevelingActive(const bool);

+ 2
- 2
Marlin/src/lcd/fontutils.cpp View File

@@ -10,8 +10,8 @@
10 10
 #include "../inc/MarlinConfig.h"
11 11
 
12 12
 #if ENABLED(ULTRA_LCD)
13
-#include "ultralcd.h"
14
-#include "../Marlin.h"
13
+  #include "ultralcd.h"
14
+  #include "../Marlin.h"
15 15
 #endif
16 16
 
17 17
 #include "fontutils.h"

+ 26
- 4
Marlin/src/lcd/language/language_de.h View File

@@ -34,6 +34,8 @@
34 34
 #define THIS_LANGUAGES_SPECIAL_SYMBOLS      _UxGT("ÄäÖöÜüß²³")
35 35
 
36 36
 #define WELCOME_MSG                         MACHINE_NAME _UxGT(" bereit")
37
+#define MSG_YES                             _UxGT("JA")
38
+#define MSG_NO                              _UxGT("NEIN")
37 39
 #define MSG_BACK                            _UxGT("Zurück")
38 40
 #define MSG_SD_INSERTED                     _UxGT("SD-Karte erkannt")
39 41
 #define MSG_SD_REMOVED                      _UxGT("SD-Karte entfernt")
@@ -97,14 +99,14 @@
97 99
 #define MSG_UBL_TOOLS                       _UxGT("UBL-Werkzeuge")
98 100
 #define MSG_UBL_LEVEL_BED                   _UxGT("Unified Bed Leveling")
99 101
 #define MSG_IDEX_MENU                       _UxGT("IDEX-Modus")
102
+#define MSG_OFFSETS_MENU                    _UxGT("Werkzeugversätze")
100 103
 #define MSG_IDEX_MODE_AUTOPARK              _UxGT("Autom. Parken")
101 104
 #define MSG_IDEX_MODE_DUPLICATE             _UxGT("Duplizieren")
102 105
 #define MSG_IDEX_MODE_MIRRORED_COPY         _UxGT("Spiegelkopie")
103 106
 #define MSG_IDEX_MODE_FULL_CTRL             _UxGT("vollstä. Kontrolle")
104
-#define MSG_IDEX_X_OFFSET                   _UxGT("2. Düse X")
105
-#define MSG_IDEX_Y_OFFSET                   _UxGT("2. Düse Y")
106
-#define MSG_IDEX_Z_OFFSET                   _UxGT("2. Düse Z")
107
-#define MSG_IDEX_SAVE_OFFSETS               _UxGT("Versätze speichern")
107
+#define MSG_X_OFFSET                        _UxGT("2. Düse X")
108
+#define MSG_Y_OFFSET                        _UxGT("2. Düse Y")
109
+#define MSG_Z_OFFSET                        _UxGT("2. Düse Z")
108 110
 #define MSG_UBL_MANUAL_MESH                 _UxGT("Netz manuell erst.")
109 111
 #define MSG_UBL_BC_INSERT                   _UxGT("Unterlegen & messen")
110 112
 #define MSG_UBL_BC_INSERT2                  _UxGT("Messen")
@@ -197,6 +199,7 @@
197 199
 #define MSG_BED_Z                           _UxGT("Bett Z")
198 200
 #define MSG_NOZZLE                          _UxGT("Düse")
199 201
 #define MSG_BED                             _UxGT("Bett")
202
+#define MSG_CHAMBER                         _UxGT("Gehäuse")
200 203
 #define MSG_FAN_SPEED                       _UxGT("Lüfter")
201 204
 #define MSG_EXTRA_FAN_SPEED                 _UxGT("Geschw. Extralüfter")
202 205
 #define MSG_FLOW                            _UxGT("Flussrate")
@@ -269,6 +272,9 @@
269 272
 #define MSG_WATCH                           _UxGT("Info")
270 273
 #define MSG_PREPARE                         _UxGT("Vorbereitung")
271 274
 #define MSG_TUNE                            _UxGT("Justierung")
275
+#define MSG_START_PRINT                     _UxGT("Starte Druck")
276
+#define MSG_BUTTON_PRINT                    _UxGT("Drucke")
277
+#define MSG_BUTTON_CANCEL                   _UxGT("Abbrechen")
272 278
 #define MSG_PAUSE_PRINT                     _UxGT("SD-Druck pausieren")
273 279
 #define MSG_RESUME_PRINT                    _UxGT("SD-Druck fortsetzen")
274 280
 #define MSG_STOP_PRINT                      _UxGT("SD-Druck abbrechen")
@@ -310,6 +316,9 @@
310 316
 #define MSG_BLTOUCH_SELFTEST                _UxGT("BLTouch Selbsttest")
311 317
 #define MSG_BLTOUCH_RESET                   _UxGT("BLTouch zurücks.")
312 318
 #define MSG_BLTOUCH_DEPLOY                  _UxGT("BLTouch ausfahren")
319
+#define MSG_BLTOUCH_SW_MODE                 _UxGT("BLTouch SW-Modus")
320
+#define MSG_BLTOUCH_5V_MODE                 _UxGT("BLTouch 5V-Modus")
321
+#define MSG_BLTOUCH_STOW                    _UxGT("BLTouch einfahren")
313 322
 #define MSG_BLTOUCH_STOW                    _UxGT("BLTouch einfahren")
314 323
 #define MSG_MANUAL_DEPLOY                   _UxGT("Z-Sonde ausfahren")
315 324
 #define MSG_MANUAL_STOW                     _UxGT("Z-Sonde einfahren")
@@ -319,6 +328,7 @@
319 328
 #define MSG_BABYSTEP_X                      _UxGT("Babystep X")
320 329
 #define MSG_BABYSTEP_Y                      _UxGT("Babystep Y")
321 330
 #define MSG_BABYSTEP_Z                      _UxGT("Babystep Z")
331
+#define MSG_BABYSTEP_TOTAL                  _UxGT("Total")
322 332
 #define MSG_ENDSTOP_ABORT                   _UxGT("Endstopp Abbr.")
323 333
 #define MSG_HEATING_FAILED_LCD              _UxGT("HEIZEN ERFOLGLOS")
324 334
 #define MSG_HEATING_FAILED_LCD_BED          _UxGT("Bett heizen fehlge.")
@@ -329,6 +339,8 @@
329 339
 #define MSG_ERR_MINTEMP                     LCD_STR_THERMOMETER _UxGT(" UNTERSCHRITTEN")
330 340
 #define MSG_ERR_MAXTEMP_BED                 _UxGT("BETT ") LCD_STR_THERMOMETER _UxGT(" ÜBERSCHRITTEN")
331 341
 #define MSG_ERR_MINTEMP_BED                 _UxGT("BETT ") LCD_STR_THERMOMETER _UxGT(" UNTERSCHRITTEN")
342
+#define MSG_ERR_MAXTEMP_CHAMBER             _UxGT("Err: GEHÄUSE MAX TEM")
343
+#define MSG_ERR_MINTEMP_CHAMBER             _UxGT("Err: GEHÄUSE MIN TEM")
332 344
 #define MSG_ERR_Z_HOMING                    MSG_HOME _UxGT(" ") MSG_X MSG_Y _UxGT(" ") MSG_FIRST
333 345
 #define MSG_HALTED                          _UxGT("DRUCKER STOPP")
334 346
 #define MSG_PLEASE_RESET                    _UxGT("Bitte neustarten")
@@ -447,6 +459,10 @@
447 459
 #define MSG_VTOOLS_RESET                    _UxGT("V-Tools ist resetet")
448 460
 #define MSG_START_Z                         _UxGT("Z Start")
449 461
 #define MSG_END_Z                           _UxGT("Z End")
462
+#define MSG_BRICKOUT                        _UxGT("Brickout")
463
+#define MSG_INVADERS                        _UxGT("Invaders")
464
+#define MSG_SNAKE                           _UxGT("Sn4k3")
465
+#define MSG_MAZE                            _UxGT("Maze")
450 466
 
451 467
 //
452 468
 // Die Filament-Change-Bildschirme können bis zu 3 Zeilen auf einem 4-Zeilen-Display anzeigen
@@ -454,6 +470,7 @@
454 470
 #if LCD_HEIGHT >= 4
455 471
   #define MSG_ADVANCED_PAUSE_WAITING_1      _UxGT("Knopf drücken um")
456 472
   #define MSG_ADVANCED_PAUSE_WAITING_2      _UxGT("Druck fortzusetzen")
473
+  #define MSG_PAUSE_PRINT_INIT_1            _UxGT("Parken...")
457 474
   #define MSG_FILAMENT_CHANGE_INIT_1        _UxGT("Warte auf den")
458 475
   #define MSG_FILAMENT_CHANGE_INIT_2        _UxGT("Start des")
459 476
   #define MSG_FILAMENT_CHANGE_INIT_3        _UxGT("Filamentwechsels...")
@@ -499,3 +516,8 @@
499 516
 #define MSG_TMC_HOMING_THRS                 _UxGT("Sensorloses Homing")
500 517
 #define MSG_TMC_STEPPING_MODE               _UxGT("Schrittmodus")
501 518
 #define MSG_TMC_STEALTH_ENABLED             _UxGT("StealthChop einsch.")
519
+#define MSG_SERVICE_RESET                   _UxGT("Reset")
520
+#define MSG_SERVICE_IN                      _UxGT(" im:")
521
+#define MSG_BACKLASH                        _UxGT("Spiel")
522
+#define MSG_BACKLASH_CORRECTION             _UxGT("Korrektur")
523
+#define MSG_BACKLASH_SMOOTHING              _UxGT("Glätten")

+ 27
- 9
Marlin/src/lcd/language/language_en.h View File

@@ -52,6 +52,12 @@
52 52
 #ifndef WELCOME_MSG
53 53
   #define WELCOME_MSG                         MACHINE_NAME _UxGT(" Ready.")
54 54
 #endif
55
+#ifndef MSG_YES
56
+  #define MSG_YES                             _UxGT("YES")
57
+#endif
58
+#ifndef MSG_NO
59
+  #define MSG_NO                              _UxGT("NO")
60
+#endif
55 61
 #ifndef MSG_BACK
56 62
   #define MSG_BACK                            _UxGT("Back")
57 63
 #endif
@@ -241,6 +247,9 @@
241 247
 #ifndef MSG_IDEX_MENU
242 248
   #define MSG_IDEX_MENU                       _UxGT("IDEX Mode")
243 249
 #endif
250
+#ifndef MSG_OFFSETS_MENU
251
+  #define MSG_OFFSETS_MENU                    _UxGT("Tool Offsets")
252
+#endif
244 253
 #ifndef MSG_IDEX_MODE_AUTOPARK
245 254
   #define MSG_IDEX_MODE_AUTOPARK              _UxGT("Auto-Park")
246 255
 #endif
@@ -253,17 +262,14 @@
253 262
 #ifndef MSG_IDEX_MODE_FULL_CTRL
254 263
   #define MSG_IDEX_MODE_FULL_CTRL             _UxGT("Full control")
255 264
 #endif
256
-#ifndef MSG_IDEX_X_OFFSET
257
-  #define MSG_IDEX_X_OFFSET                   _UxGT("2nd nozzle X")
258
-#endif
259
-#ifndef MSG_IDEX_Y_OFFSET
260
-  #define MSG_IDEX_Y_OFFSET                   _UxGT("2nd nozzle Y")
265
+#ifndef MSG_X_OFFSET
266
+  #define MSG_X_OFFSET                        _UxGT("2nd nozzle X")
261 267
 #endif
262
-#ifndef MSG_IDEX_Z_OFFSET
263
-  #define MSG_IDEX_Z_OFFSET                   _UxGT("2nd nozzle Z")
268
+#ifndef MSG_Y_OFFSET
269
+  #define MSG_Y_OFFSET                        _UxGT("2nd nozzle Y")
264 270
 #endif
265
-#ifndef MSG_IDEX_SAVE_OFFSETS
266
-  #define MSG_IDEX_SAVE_OFFSETS               _UxGT("Save Offsets")
271
+#ifndef MSG_Z_OFFSET
272
+  #define MSG_Z_OFFSET                        _UxGT("2nd nozzle Z")
267 273
 #endif
268 274
 #ifndef MSG_UBL_MANUAL_MESH
269 275
   #define MSG_UBL_MANUAL_MESH                 _UxGT("Manually Build Mesh")
@@ -744,6 +750,15 @@
744 750
 #ifndef MSG_TUNE
745 751
   #define MSG_TUNE                            _UxGT("Tune")
746 752
 #endif
753
+#ifndef MSG_START_PRINT
754
+  #define MSG_START_PRINT                     _UxGT("Start print")
755
+#endif
756
+#ifndef MSG_BUTTON_PRINT
757
+  #define MSG_BUTTON_PRINT                    _UxGT("Print")
758
+#endif
759
+#ifndef MSG_BUTTON_CANCEL
760
+  #define MSG_BUTTON_CANCEL                   _UxGT("Cancel")
761
+#endif
747 762
 #ifndef MSG_PAUSE_PRINT
748 763
   #define MSG_PAUSE_PRINT                     _UxGT("Pause print")
749 764
 #endif
@@ -903,6 +918,9 @@
903 918
 #ifndef MSG_BABYSTEP_Z
904 919
   #define MSG_BABYSTEP_Z                      _UxGT("Babystep Z")
905 920
 #endif
921
+#ifndef MSG_BABYSTEP_TOTAL
922
+  #define MSG_BABYSTEP_TOTAL                  _UxGT("Total")
923
+#endif
906 924
 #ifndef MSG_ENDSTOP_ABORT
907 925
   #define MSG_ENDSTOP_ABORT                   _UxGT("Endstop abort")
908 926
 #endif

+ 0
- 0
Marlin/src/lcd/language/language_it.h View File


Some files were not shown because too many files changed in this diff

Loading…
Cancel
Save