소스 검색

Merge branch '1.1.x' into fabrikator-mini

Added E1 output as Fan pin.
Thomas Buck 6 년 전
부모
커밋
3c932960ea
100개의 변경된 파일36876개의 추가작업 그리고 11716개의 파일을 삭제
  1. 11
    4
      .gitignore
  2. 70
    45
      .travis.yml
  3. 100
    65
      Marlin/Conditionals_LCD.h
  4. 400
    106
      Marlin/Conditionals_post.h
  5. 248
    107
      Marlin/Configuration.h
  6. 372
    167
      Marlin/Configuration_adv.h
  7. 465
    500
      Marlin/G26_Mesh_Validation_Tool.cpp
  8. 2
    15
      Marlin/I2CPositionEncoder.h
  9. 29
    3
      Marlin/Makefile
  10. 109
    50
      Marlin/Marlin.h
  11. 1
    0
      Marlin/MarlinConfig.h
  12. 3
    3
      Marlin/MarlinSPI.h
  13. 197
    60
      Marlin/MarlinSerial.cpp
  14. 42
    35
      Marlin/MarlinSerial.h
  15. 3660
    2249
      Marlin/Marlin_main.cpp
  16. 349
    0
      Marlin/Max7219_Debug_LEDs.cpp
  17. 90
    0
      Marlin/Max7219_Debug_LEDs.h
  18. 371
    110
      Marlin/SanityCheck.h
  19. 162
    176
      Marlin/Sd2Card.cpp
  20. 85
    132
      Marlin/Sd2Card.h
  21. 340
    437
      Marlin/SdBaseFile.cpp
  22. 229
    220
      Marlin/SdBaseFile.h
  23. 91
    104
      Marlin/SdFatConfig.h
  24. 384
    424
      Marlin/SdFatStructs.h
  25. 23
    23
      Marlin/SdFatUtil.cpp
  26. 3
    8
      Marlin/SdFatUtil.h
  27. 26
    28
      Marlin/SdFile.cpp
  28. 9
    12
      Marlin/SdFile.h
  29. 36
    58
      Marlin/SdInfo.h
  30. 82
    118
      Marlin/SdVolume.cpp
  31. 106
    122
      Marlin/SdVolume.h
  32. 4
    4
      Marlin/Version.h
  33. 38
    0
      Marlin/bitmap_flags.h
  34. 8
    8
      Marlin/blinkm.cpp
  35. 9
    5
      Marlin/blinkm.h
  36. 121
    72
      Marlin/boards.h
  37. 96
    72
      Marlin/cardreader.cpp
  38. 33
    23
      Marlin/cardreader.h
  39. 632
    356
      Marlin/configuration_store.cpp
  40. 2
    2
      Marlin/configuration_store.h
  41. 199
    58
      Marlin/dogm_bitmaps.h
  42. 252
    164
      Marlin/dogm_font_data_ISO10646_1.h
  43. 151
    0
      Marlin/dogm_font_data_ISO10646_SK.h
  44. 49
    9
      Marlin/endstop_interrupts.h
  45. 137
    61
      Marlin/endstops.cpp
  46. 17
    2
      Marlin/endstops.h
  47. 4
    0
      Marlin/enum.h
  48. 254
    108
      Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h
  49. 370
    157
      Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h
  50. 246
    102
      Marlin/example_configurations/AliExpress/CL-260/Configuration.h
  51. 1
    1
      Marlin/example_configurations/AliExpress/CL-260/README.txt
  52. 272
    130
      Marlin/example_configurations/Anet/A6/Configuration.h
  53. 367
    161
      Marlin/example_configurations/Anet/A6/Configuration_adv.h
  54. 247
    105
      Marlin/example_configurations/Anet/A8/Configuration.h
  55. 367
    161
      Marlin/example_configurations/Anet/A8/Configuration_adv.h
  56. 248
    102
      Marlin/example_configurations/BQ/Hephestos/Configuration.h
  57. 370
    157
      Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h
  58. 289
    136
      Marlin/example_configurations/BQ/Hephestos_2/Configuration.h
  59. 393
    163
      Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h
  60. 7
    0
      Marlin/example_configurations/BQ/Hephestos_2/README.md
  61. 0
    0
      Marlin/example_configurations/BQ/Hephestos_2/_Bootscreen.h
  62. 247
    101
      Marlin/example_configurations/BQ/WITBOX/Configuration.h
  63. 370
    157
      Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h
  64. 244
    98
      Marlin/example_configurations/Cartesio/Configuration.h
  65. 370
    157
      Marlin/example_configurations/Cartesio/Configuration_adv.h
  66. 1779
    0
      Marlin/example_configurations/Creality/CR-10/Configuration.h
  67. 1570
    0
      Marlin/example_configurations/Creality/CR-10/Configuration_adv.h
  68. 100
    0
      Marlin/example_configurations/Creality/CR-10/_Bootscreen.h
  69. 248
    103
      Marlin/example_configurations/Felix/Configuration.h
  70. 370
    157
      Marlin/example_configurations/Felix/Configuration_adv.h
  71. 247
    102
      Marlin/example_configurations/Felix/DUAL/Configuration.h
  72. 248
    102
      Marlin/example_configurations/FolgerTech/i3-2020/Configuration.h
  73. 366
    166
      Marlin/example_configurations/FolgerTech/i3-2020/Configuration_adv.h
  74. 1793
    0
      Marlin/example_configurations/Geeetech/GT2560/Configuration.h
  75. 1769
    0
      Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h
  76. 0
    1260
      Marlin/example_configurations/Infitary-i3-M508/Configuration_adv.h
  77. 293
    114
      Marlin/example_configurations/Infitary/i3-M508/Configuration.h
  78. 1567
    0
      Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h
  79. 247
    101
      Marlin/example_configurations/Malyan/M150/Configuration.h
  80. 1567
    0
      Marlin/example_configurations/Malyan/M150/Configuration_adv.h
  81. 0
    0
      Marlin/example_configurations/Malyan/M150/README.md
  82. 0
    0
      Marlin/example_configurations/Malyan/M150/_Bootscreen.h
  83. 15
    0
      Marlin/example_configurations/Micromake/C1/README.md
  84. 1773
    0
      Marlin/example_configurations/Micromake/C1/basic/Configuration.h
  85. 1773
    0
      Marlin/example_configurations/Micromake/C1/enhanced/Configuration.h
  86. 1568
    0
      Marlin/example_configurations/Micromake/C1/enhanced/Configuration_adv.h
  87. 245
    100
      Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h
  88. 246
    101
      Marlin/example_configurations/RigidBot/Configuration.h
  89. 370
    157
      Marlin/example_configurations/RigidBot/Configuration_adv.h
  90. 246
    101
      Marlin/example_configurations/SCARA/Configuration.h
  91. 370
    157
      Marlin/example_configurations/SCARA/Configuration_adv.h
  92. 1800
    0
      Marlin/example_configurations/Sanguinololu/Configuration.h
  93. 340
    167
      Marlin/example_configurations/Sanguinololu/Configuration_adv.h
  94. 242
    102
      Marlin/example_configurations/TinyBoy2/Configuration.h
  95. 367
    157
      Marlin/example_configurations/TinyBoy2/Configuration_adv.h
  96. 236
    100
      Marlin/example_configurations/Velleman/K8200/Configuration.h
  97. 367
    156
      Marlin/example_configurations/Velleman/K8200/Configuration_adv.h
  98. 0
    0
      Marlin/example_configurations/Velleman/K8200/README.md
  99. 245
    100
      Marlin/example_configurations/Velleman/K8400/Configuration.h
  100. 0
    0
      Marlin/example_configurations/Velleman/K8400/Configuration_adv.h

+ 11
- 4
.gitignore 파일 보기

@@ -118,16 +118,23 @@ tags
118 118
 
119 119
 # PlatformIO files/dirs
120 120
 .pio*
121
+.pioenvs
122
+.piolibdeps
121 123
 lib/readme.txt
122 124
 
123 125
 #Visual Studio
124 126
 *.sln
125 127
 *.vcxproj
126 128
 *.vcxproj.filters
127
-Marlin/Release/
128
-Marlin/Debug/
129
-Marlin/__vm/
130
-Marlin/.vs/
129
+Release/
130
+Debug/
131
+__vm/
132
+.vs/
133
+vc-fileutils.settings
134
+
135
+#VScode
136
+.vscode
137
+.vscode/c_cpp_properties.json
131 138
 
132 139
 #cmake
133 140
 CMakeLists.txt

+ 70
- 45
.travis.yml 파일 보기

@@ -1,4 +1,6 @@
1
----
1
+dist: trusty
2
+sudo: true
3
+  #
2 4
 language: c
3 5
   #
4 6
 notifications:
@@ -11,7 +13,7 @@ before_install:
11 13
   #
12 14
   # Publish the buildroot script folder
13 15
   - chmod +x ${TRAVIS_BUILD_DIR}/buildroot/bin/*
14
-  - ln -s ${TRAVIS_BUILD_DIR}/buildroot/bin/ ~/bin
16
+  - export PATH=${TRAVIS_BUILD_DIR}/buildroot/bin/:${PATH}
15 17
   #
16 18
   # Start fb X server
17 19
   - "/sbin/start-stop-daemon --start --quiet --pidfile /tmp/custom_xvfb_1.pid --make-pidfile --background --exec /usr/bin/Xvfb -- :1 -ac -screen 0 1280x1024x16"
@@ -50,6 +52,14 @@ install:
50 52
   - git clone https://github.com/teemuatlut/TMC2130Stepper.git
51 53
   - sudo mv TMC2130Stepper /usr/local/share/arduino/libraries/TMC2130Stepper
52 54
   #
55
+  # Install: TMC2208 Stepper Motor Controller library
56
+  - git clone https://github.com/teemuatlut/TMC2208Stepper.git
57
+  - sudo mv TMC2208Stepper /usr/local/share/arduino/libraries/TMC2208Stepper
58
+  #
59
+  # Install: Adafruit Neopixel library
60
+  - git clone https://github.com/adafruit/Adafruit_NeoPixel.git
61
+  - sudo mv Adafruit_NeoPixel /usr/local/share/arduino/libraries/Adafruit_NeoPixel
62
+  #
53 63
 before_script:
54 64
   #
55 65
   # Change current working directory to the build dir
@@ -72,35 +82,36 @@ script:
72 82
   - build_marlin
73 83
   #
74 84
   # Test 2 extruders (one MAX6675) and heated bed on basic RAMPS 1.4
75
-  #  plus a "Fix Mounted" Probe with Safe Homing and some arc options
85
+  # Test a "Fix Mounted" Probe with Safe Homing, some arc options,
86
+  # linear bed leveling, M48, leveling debug, and firmware retraction.
76 87
   #
77 88
   - opt_set MOTHERBOARD BOARD_RAMPS_14_EEB
78 89
   - opt_set EXTRUDERS 2
79 90
   - opt_set TEMP_SENSOR_0 -2
80 91
   - opt_set TEMP_SENSOR_1 1
81 92
   - opt_set TEMP_SENSOR_BED 1
82
-  - opt_enable PIDTEMPBED FIX_MOUNTED_PROBE Z_SAFE_HOMING ARC_P_CIRCLES CNC_WORKSPACE_PLANES
83
-  - build_marlin
84
-  #
85
-  # ...with AUTO_BED_LEVELING_LINEAR, Z_MIN_PROBE_REPEATABILITY_TEST, and DEBUG_LEVELING_FEATURE
86
-  #
87
-  - opt_enable AUTO_BED_LEVELING_LINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE
93
+  - opt_enable PIDTEMPBED FIX_MOUNTED_PROBE Z_SAFE_HOMING ARC_P_CIRCLES CNC_WORKSPACE_PLANES CNC_COORDINATE_SYSTEMS
94
+  - opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS
95
+  - opt_enable BLINKM PCA9632 RGB_LED NEOPIXEL_LED
96
+  - opt_enable AUTO_BED_LEVELING_LINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE
97
+  - opt_enable_adv FWRETRACT MAX7219_DEBUG LED_CONTROL_MENU
88 98
   - opt_set ABL_GRID_POINTS_X 16
89 99
   - opt_set ABL_GRID_POINTS_Y 16
100
+  - opt_set_adv FANMUX0_PIN 53
90 101
   - build_marlin
91 102
   #
92
-  # Test a simple build of AUTO_BED_LEVELING_UBL
103
+  # Test a probeless build of AUTO_BED_LEVELING_UBL
93 104
   #
94 105
   - restore_configs
95
-  - opt_enable AUTO_BED_LEVELING_UBL UBL_G26_MESH_EDITING ENABLE_LEVELING_FADE_HEIGHT FIX_MOUNTED_PROBE EEPROM_SETTINGS G3D_PANEL
96
-  - opt_enable_adv CUSTOM_USER_MENUS I2C_POSITION_ENCODERS BABYSTEPPING
106
+  - opt_enable AUTO_BED_LEVELING_UBL DEBUG_LEVELING_FEATURE G26_MESH_EDITING ENABLE_LEVELING_FADE_HEIGHT EEPROM_SETTINGS EEPROM_CHITCHAT G3D_PANEL
107
+  - opt_enable_adv CUSTOM_USER_MENUS I2C_POSITION_ENCODERS BABYSTEPPING NANODLP_Z_SYNC
97 108
   - build_marlin
98 109
   #
99
-  # Test a Sled Z Probe
100
-  # ...with AUTO_BED_LEVELING_LINEAR, DEBUG_LEVELING_FEATURE, EEPROM_SETTINGS, and EEPROM_CHITCHAT
110
+  # Add a Sled Z Probe, use UBL Cartesian moves
101 111
   #
102
-  - restore_configs
103
-  - opt_enable Z_PROBE_SLED AUTO_BED_LEVELING_LINEAR DEBUG_LEVELING_FEATURE EEPROM_SETTINGS EEPROM_CHITCHAT
112
+  - opt_enable Z_PROBE_SLED SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE
113
+  - opt_disable SEGMENT_LEVELED_MOVES
114
+  - opt_enable_adv BABYSTEP_ZPROBE_OFFSET DOUBLECLICK_FOR_Z_BABYSTEPPING
104 115
   - build_marlin
105 116
   #
106 117
   # Test a Servo Probe
@@ -108,24 +119,36 @@ script:
108 119
   #
109 120
   - restore_configs
110 121
   - opt_enable NUM_SERVOS Z_ENDSTOP_SERVO_NR Z_SERVO_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE
122
+  - opt_set NUM_SERVOS 1
111 123
   - opt_enable AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS EEPROM_CHITCHAT
112
-  - opt_enable_adv EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES AUTOTEMP
124
+  - opt_enable_adv EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES AUTOTEMP G38_PROBE_TARGET
113 125
   - build_marlin
114 126
   #
115 127
   # Test MESH_BED_LEVELING feature, with LCD
116 128
   #
117 129
   - restore_configs
118
-  - opt_enable MESH_BED_LEVELING MESH_G28_REST_ORIGIN LCD_BED_LEVELING ULTIMAKERCONTROLLER
130
+  - opt_enable MESH_BED_LEVELING G26_MESH_EDITING MESH_G28_REST_ORIGIN LCD_BED_LEVELING ULTIMAKERCONTROLLER
119 131
   - build_marlin
120 132
   #
121
-  # Test PROBE_MANUALLY feature, with LCD support,
133
+  # Test MINIRAMBO for PWM_MOTOR_CURRENT
134
+  #      PROBE_MANUALLY feature, with LCD support,
135
+  #      ULTIMAKERCONTROLLER, FILAMENT_LCD_DISPLAY, FILAMENT_WIDTH_SENSOR,
136
+  #      PRINTCOUNTER, NOZZLE_PARK_FEATURE, NOZZLE_CLEAN_FEATURE, PCA9632,
137
+  #      Z_DUAL_STEPPER_DRIVERS, Z_DUAL_ENDSTOPS, BEZIER_CURVE_SUPPORT, EXPERIMENTAL_I2CBUS,
138
+  #      ADVANCED_PAUSE_FEATURE, PARK_HEAD_ON_PAUSE, LCD_INFO_MENU,
122 139
   #      EEPROM_SETTINGS, EEPROM_CHITCHAT, M100_FREE_MEMORY_WATCHER,
123 140
   #      INCH_MODE_SUPPORT, TEMPERATURE_UNITS_SUPPORT
124 141
   #
125 142
   - restore_configs
126 143
   - opt_set MOTHERBOARD BOARD_MINIRAMBO
127
-  - opt_enable PROBE_MANUALLY AUTO_BED_LEVELING_BILINEAR LCD_BED_LEVELING ULTIMAKERCONTROLLER
144
+  - opt_enable PROBE_MANUALLY AUTO_BED_LEVELING_BILINEAR G26_MESH_EDITING LCD_BED_LEVELING ULTIMAKERCONTROLLER
128 145
   - opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT M100_FREE_MEMORY_WATCHER M100_FREE_MEMORY_DUMPER M100_FREE_MEMORY_CORRUPTOR INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT
146
+  - opt_enable ULTIMAKERCONTROLLER SDSUPPORT
147
+  - opt_enable PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE PCA9632 USE_XMAX_PLUG
148
+  - opt_enable_adv BEZIER_CURVE_SUPPORT EXPERIMENTAL_I2CBUS
149
+  - opt_enable_adv ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE LCD_INFO_MENU M114_DETAIL
150
+  - opt_set_adv PWM_MOTOR_CURRENT {1300,1300,1250}
151
+  - opt_set_adv I2C_SLAVE_ADDRESS 63
129 152
   - build_marlin
130 153
   #
131 154
   # Test 5 extruders on AZTEEG_X3_PRO (can use any board with >=5 extruders defined)
@@ -178,34 +201,29 @@ script:
178 201
   - opt_enable SWITCHING_EXTRUDER ULTIMAKERCONTROLLER
179 202
   - build_marlin
180 203
   #
181
-  # Test MINIRAMBO for PWM_MOTOR_CURRENT
182
-  #      ULTIMAKERCONTROLLER, FILAMENT_LCD_DISPLAY, FILAMENT_WIDTH_SENSOR,
183
-  #      PRINTCOUNTER, NOZZLE_PARK_FEATURE, NOZZLE_CLEAN_FEATURE, PCA9632,
184
-  #      Z_DUAL_STEPPER_DRIVERS, Z_DUAL_ENDSTOPS, BEZIER_CURVE_SUPPORT, EXPERIMENTAL_I2CBUS,
185
-  #      FILAMENT_CHANGE_FEATURE, PARK_HEAD_ON_PAUSE, LCD_INFO_MENU,
186
-  #
187
-  - restore_configs
188
-  - opt_enable ULTIMAKERCONTROLLER FILAMENT_LCD_DISPLAY FILAMENT_WIDTH_SENSOR SDSUPPORT
189
-  - opt_enable PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE PCA9632
190
-  - opt_enable_adv Z_DUAL_STEPPER_DRIVERS Z_DUAL_ENDSTOPS BEZIER_CURVE_SUPPORT EXPERIMENTAL_I2CBUS
191
-  - opt_set_adv I2C_SLAVE_ADDRESS 63
192
-  - opt_enable_adv FILAMENT_CHANGE_FEATURE PARK_HEAD_ON_PAUSE LCD_INFO_MENU
193
-  - pins_set RAMPS X_MAX_PIN -1
194
-  - opt_set_adv Z2_MAX_PIN 2
195
-  - build_marlin
196
-  #
197 204
   # Enable COREXY
198 205
   #
199 206
   - restore_configs
200 207
   - opt_enable COREXY
201 208
   - build_marlin
202 209
   #
203
-  # Enable COREYX (swapped)
204
-  #
205
-  #- restore_configs
206
-  #- opt_enable COREYX
207
-  #- build_marlin
210
+  # Test many less common options
208 211
   #
212
+  - restore_configs
213
+  - opt_enable COREYX
214
+  - opt_set_adv FAN_MIN_PWM 50
215
+  - opt_set_adv FAN_KICKSTART_TIME 100
216
+  - opt_set_adv XY_FREQUENCY_LIMIT  15
217
+  - opt_enable_adv SHOW_TEMP_ADC_VALUES HOME_Y_BEFORE_X EMERGENCY_PARSER FAN_KICKSTART_TIME
218
+  - opt_enable_adv ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED ADVANCED_OK
219
+  - opt_enable_adv VOLUMETRIC_DEFAULT_ON NO_WORKSPACE_OFFSETS ACTION_ON_KILL
220
+  - opt_enable_adv EXTRA_FAN_SPEED FWERETRACT Z_DUAL_STEPPER_DRIVERS Z_DUAL_ENDSTOPS
221
+  - opt_enable_adv MENU_ADDAUTOSTART SDCARD_SORT_ALPHA
222
+  - opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER
223
+  - opt_enable FILAMENT_LCD_DISPLAY FILAMENT_WIDTH_SENSOR
224
+  - opt_enable ENDSTOP_INTERRUPTS_FEATURE FAN_SOFT_PWM SDSUPPORT
225
+  - opt_enable USE_XMAX_PLUG
226
+  - build_marlin
209 227
   #
210 228
   ######## Other Standard LCD/Panels ##############
211 229
   #
@@ -239,7 +257,7 @@ script:
239 257
   #
240 258
   - restore_configs
241 259
   - opt_enable G3D_PANEL SDSUPPORT
242
-  - opt_enable_adv SDCARD_SORT_ALPHA STATUS_MESSAGE_SCROLLING
260
+  - opt_enable_adv SDCARD_SORT_ALPHA STATUS_MESSAGE_SCROLLING SCROLL_LONG_FILENAMES
243 261
   - opt_set_adv SDSORT_GCODE true
244 262
   - opt_set_adv SDSORT_USES_RAM true
245 263
   - opt_set_adv SDSORT_USES_STACK true
@@ -250,7 +268,7 @@ script:
250 268
   #
251 269
   - restore_configs
252 270
   - opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT
253
-  - opt_enable_adv SDCARD_SORT_ALPHA STATUS_MESSAGE_SCROLLING
271
+  - opt_enable_adv SDCARD_SORT_ALPHA STATUS_MESSAGE_SCROLLING SCROLL_LONG_FILENAMES
254 272
   - build_marlin
255 273
   #
256 274
   # REPRAPWORLD_KEYPAD
@@ -313,7 +331,7 @@ script:
313 331
   #
314 332
   - use_example_configs delta/generic
315 333
   - opt_disable DISABLE_MIN_ENDSTOPS
316
-  - opt_enable AUTO_BED_LEVELING_UBL Z_PROBE_ALLEN_KEY EEPROM_SETTINGS EEPROM_CHITCHAT OLED_PANEL_TINYBOY2
334
+  - opt_enable AUTO_BED_LEVELING_UBL Z_PROBE_ALLEN_KEY EEPROM_SETTINGS EEPROM_CHITCHAT OLED_PANEL_TINYBOY2 MESH_EDIT_GFX_OVERLAY
317 335
   - build_marlin
318 336
   #
319 337
   # Delta Config (FLSUN AC because it's complex)
@@ -331,7 +349,14 @@ script:
331 349
   - use_example_configs SCARA
332 350
   - opt_enable AUTO_BED_LEVELING_BILINEAR FIX_MOUNTED_PROBE USE_ZMIN_PLUG EEPROM_SETTINGS EEPROM_CHITCHAT ULTIMAKERCONTROLLER
333 351
   - opt_enable_adv HAVE_TMC2130 X_IS_TMC2130 Y_IS_TMC2130 Z_IS_TMC2130
334
-  - opt_enable_adv AUTOMATIC_CURRENT_CONTROL STEALTHCHOP HYBRID_THRESHOLD SENSORLESS_HOMING
352
+  - opt_enable_adv MONITOR_DRIVER_STATUS STEALTHCHOP HYBRID_THRESHOLD TMC_DEBUG SENSORLESS_HOMING
353
+  - build_marlin
354
+  #
355
+  # TMC2208 Config
356
+  #
357
+  - restore_configs
358
+  - opt_enable_adv HAVE_TMC2208 X_IS_TMC2208 Y_IS_TMC2208 Z_IS_TMC2208
359
+  - opt_enable_adv MONITOR_DRIVER_STATUS STEALTHCHOP HYBRID_THRESHOLD TMC_DEBUG
335 360
   - build_marlin
336 361
   #
337 362
   # tvrrug Config need to check board type for sanguino atmega644p

+ 100
- 65
Marlin/Conditionals_LCD.h 파일 보기

@@ -34,27 +34,26 @@
34 34
 
35 35
     #define DOGLCD
36 36
     #define ULTIPANEL
37
-    #define NEWPANEL
38 37
     #define DEFAULT_LCD_CONTRAST 90
39 38
     #define LCD_CONTRAST_MIN 60
40 39
     #define LCD_CONTRAST_MAX 140
41 40
 
42
-  #elif ENABLED(MAKRPANEL) || ENABLED(MINIPANEL)
41
+  #elif ENABLED(MAKRPANEL)
43 42
 
44
-    #define DOGLCD
45
-    #define ULTIPANEL
46
-    #define NEWPANEL
47
-    #define DEFAULT_LCD_CONTRAST 17
43
+    #define U8GLIB_ST7565_64128N
48 44
 
49
-  #elif ENABLED(ANET_KEYPAD_LCD)
45
+  #elif ENABLED(ZONESTAR_LCD)
50 46
 
51 47
     #define REPRAPWORLD_KEYPAD
52 48
     #define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0
53 49
     #define ADC_KEYPAD
54 50
     #define ADC_KEY_NUM 8
55 51
     #define ULTIPANEL
52
+
56 53
     // this helps to implement ADC_KEYPAD menus
54
+    #define ENCODER_PULSES_PER_STEP 1
57 55
     #define ENCODER_STEPS_PER_MENU_ITEM 1
56
+    #define ENCODER_FEEDRATE_DEADZONE 2
58 57
     #define REVERSE_MENU_DIRECTION
59 58
 
60 59
   #elif ENABLED(ANET_FULL_GRAPHICS_LCD)
@@ -64,7 +63,6 @@
64 63
   #elif ENABLED(BQ_LCD_SMART_CONTROLLER)
65 64
 
66 65
     #define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
67
-    #define LONG_FILENAME_HOST_SUPPORT
68 66
 
69 67
   #elif ENABLED(miniVIKI) || ENABLED(VIKI2) || ENABLED(ELB_FULL_GRAPHIC_CONTROLLER)
70 68
 
@@ -73,14 +71,18 @@
73 71
     #define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
74 72
 
75 73
     #if ENABLED(miniVIKI)
76
-      #define LCD_CONTRAST_MIN  75
77
-      #define LCD_CONTRAST_MAX 115
78
-      #define DEFAULT_LCD_CONTRAST 95
74
+      #define LCD_CONTRAST_MIN      75
75
+      #define LCD_CONTRAST_MAX     115
76
+      #define DEFAULT_LCD_CONTRAST  95
77
+      #define U8GLIB_ST7565_64128N
79 78
     #elif ENABLED(VIKI2)
80
-      #define DEFAULT_LCD_CONTRAST 40
79
+      #define LCD_CONTRAST_MIN       0
80
+      #define LCD_CONTRAST_MAX     255
81
+      #define DEFAULT_LCD_CONTRAST 140
82
+      #define U8GLIB_ST7565_64128N
81 83
     #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER)
82
-      #define LCD_CONTRAST_MIN  90
83
-      #define LCD_CONTRAST_MAX 130
84
+      #define LCD_CONTRAST_MIN      90
85
+      #define LCD_CONTRAST_MAX     130
84 86
       #define DEFAULT_LCD_CONTRAST 110
85 87
       #define U8GLIB_LM6059_AF
86 88
       #define SD_DETECT_INVERTED
@@ -90,7 +92,6 @@
90 92
 
91 93
     #define U8GLIB_SSD1306
92 94
     #define ULTIPANEL
93
-    #define NEWPANEL
94 95
     #define REVERSE_ENCODER_DIRECTION
95 96
     #define REVERSE_MENU_DIRECTION
96 97
 
@@ -99,17 +100,43 @@
99 100
     #define LCD_I2C_TYPE_PCA8574
100 101
     #define LCD_I2C_ADDRESS 0x27   // I2C Address of the port expander
101 102
     #define ULTIPANEL
102
-    #define NEWPANEL
103 103
 
104 104
   #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD)
105 105
 
106 106
     #define DOGLCD
107 107
     #define U8GLIB_ST7920
108 108
     #define ULTIPANEL
109
-    #define NEWPANEL
109
+
110
+  #elif ENABLED(CR10_STOCKDISPLAY)
111
+
112
+    #define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
113
+    #ifndef ST7920_DELAY_1
114
+      #define ST7920_DELAY_1 DELAY_2_NOP
115
+    #endif
116
+    #ifndef ST7920_DELAY_2
117
+      #define ST7920_DELAY_2 DELAY_2_NOP
118
+    #endif
119
+    #ifndef ST7920_DELAY_3
120
+      #define ST7920_DELAY_3 DELAY_2_NOP
121
+    #endif
122
+
123
+  #elif ENABLED(MKS_12864OLED)
124
+
125
+    #define REPRAP_DISCOUNT_SMART_CONTROLLER
126
+    #define U8GLIB_SH1106
127
+
128
+  #elif ENABLED(MKS_MINI_12864)
129
+
130
+    #define MINIPANEL
110 131
 
111 132
   #endif
112 133
 
134
+  #if ENABLED(MAKRPANEL) || ENABLED(MINIPANEL)
135
+    #define DOGLCD
136
+    #define ULTIPANEL
137
+    #define DEFAULT_LCD_CONTRAST 17
138
+  #endif
139
+
113 140
   // Generic support for SSD1306 / SH1106 OLED based LCDs.
114 141
   #if ENABLED(U8GLIB_SSD1306) || ENABLED(U8GLIB_SH1106)
115 142
     #define ULTRA_LCD  //general LCD support, also 16x2
@@ -117,10 +144,18 @@
117 144
   #endif
118 145
 
119 146
   #if ENABLED(PANEL_ONE) || ENABLED(U8GLIB_SH1106)
147
+
120 148
     #define ULTIMAKERCONTROLLER
149
+
150
+  #elif ENABLED(MAKEBOARD_MINI_2_LINE_DISPLAY_1602)
151
+
152
+    #define REPRAP_DISCOUNT_SMART_CONTROLLER
153
+    #define LCD_WIDTH 16
154
+    #define LCD_HEIGHT 2
155
+
121 156
   #endif
122 157
 
123
-  #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) || ENABLED(LCD_FOR_MELZI)
158
+  #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) || ENABLED(LCD_FOR_MELZI) || ENABLED(SILVER_GATE_GLCD_CONTROLLER)
124 159
     #define DOGLCD
125 160
     #define U8GLIB_ST7920
126 161
     #define REPRAP_DISCOUNT_SMART_CONTROLLER
@@ -131,7 +166,6 @@
131 166
    || ENABLED(G3D_PANEL)                        \
132 167
    || ENABLED(RIGIDBOT_PANEL)
133 168
     #define ULTIPANEL
134
-    #define NEWPANEL
135 169
   #endif
136 170
 
137 171
   #if ENABLED(REPRAPWORLD_KEYPAD)
@@ -153,7 +187,6 @@
153 187
     #define LCD_I2C_TYPE_PCF8575
154 188
     #define LCD_I2C_ADDRESS 0x27   // I2C Address of the port expander
155 189
     #define ULTIPANEL
156
-    #define NEWPANEL
157 190
 
158 191
   #elif ENABLED(LCD_I2C_PANELOLU2)
159 192
 
@@ -163,7 +196,6 @@
163 196
     #define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
164 197
     #define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD
165 198
     #define ULTIPANEL
166
-    #define NEWPANEL
167 199
 
168 200
   #elif ENABLED(LCD_I2C_VIKI)
169 201
 
@@ -179,27 +211,41 @@
179 211
     #define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
180 212
     #define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD (requires LiquidTWI2 v1.2.3 or later)
181 213
     #define ULTIPANEL
182
-    #define NEWPANEL
183 214
 
184 215
     #define ENCODER_FEEDRATE_DEADZONE 4
185 216
 
186
-    #ifndef ENCODER_PULSES_PER_STEP
187
-      #define ENCODER_PULSES_PER_STEP 1
188
-    #endif
189
-    #ifndef ENCODER_STEPS_PER_MENU_ITEM
190
-      #define ENCODER_STEPS_PER_MENU_ITEM 2
191
-    #endif
217
+    #define STD_ENCODER_PULSES_PER_STEP 1
218
+    #define STD_ENCODER_STEPS_PER_MENU_ITEM 2
219
+
220
+  #elif ENABLED(G3D_PANEL)
221
+
222
+    #define STD_ENCODER_PULSES_PER_STEP 2
223
+    #define STD_ENCODER_STEPS_PER_MENU_ITEM 1
224
+
225
+  #elif ENABLED(miniVIKI) || ENABLED(VIKI2) \
226
+     || ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) \
227
+     || ENABLED(OLED_PANEL_TINYBOY2) \
228
+     || ENABLED(BQ_LCD_SMART_CONTROLLER) \
229
+     || ENABLED(LCD_I2C_PANELOLU2) \
230
+     || ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER)
231
+    #define STD_ENCODER_PULSES_PER_STEP 4
232
+    #define STD_ENCODER_STEPS_PER_MENU_ITEM 1
192 233
   #endif
193 234
 
194
-  // Set encoder detents for well-known controllers
195
-  #if ENABLED(miniVIKI) || ENABLED(VIKI2) || ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) || ENABLED(OLED_PANEL_TINYBOY2) \
196
-   || ENABLED(BQ_LCD_SMART_CONTROLLER) || ENABLED(LCD_I2C_PANELOLU2) || ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER)
197
-    #ifndef ENCODER_PULSES_PER_STEP
198
-      #define ENCODER_PULSES_PER_STEP 4
199
-    #endif
200
-    #ifndef ENCODER_STEPS_PER_MENU_ITEM
201
-      #define ENCODER_STEPS_PER_MENU_ITEM 1
202
-    #endif
235
+  #ifndef STD_ENCODER_PULSES_PER_STEP
236
+    #define STD_ENCODER_PULSES_PER_STEP 5
237
+  #endif
238
+  #ifndef STD_ENCODER_STEPS_PER_MENU_ITEM
239
+    #define STD_ENCODER_STEPS_PER_MENU_ITEM 1
240
+  #endif
241
+  #ifndef ENCODER_PULSES_PER_STEP
242
+    #define ENCODER_PULSES_PER_STEP STD_ENCODER_PULSES_PER_STEP
243
+  #endif
244
+  #ifndef ENCODER_STEPS_PER_MENU_ITEM
245
+    #define ENCODER_STEPS_PER_MENU_ITEM STD_ENCODER_STEPS_PER_MENU_ITEM
246
+  #endif
247
+  #ifndef ENCODER_FEEDRATE_DEADZONE
248
+    #define ENCODER_FEEDRATE_DEADZONE 6
203 249
   #endif
204 250
 
205 251
   // Shift register panels
@@ -210,7 +256,6 @@
210 256
   #if ENABLED(SAV_3DLCD)
211 257
     #define SR_LCD_2W_NL    // Non latching 2 wire shift register
212 258
     #define ULTIPANEL
213
-    #define NEWPANEL
214 259
   #endif
215 260
 
216 261
   #if ENABLED(DOGLCD) // Change number of lines to match the DOG graphic display
@@ -223,7 +268,7 @@
223 268
   #endif
224 269
 
225 270
   #if ENABLED(ULTIPANEL)
226
-    #define NEWPANEL  //enable this if you have a click-encoder panel
271
+    #define NEWPANEL  // Disable this if you actually have no click-encoder panel
227 272
     #define ULTRA_LCD
228 273
     #ifndef LCD_WIDTH
229 274
       #define LCD_WIDTH 20
@@ -231,14 +276,12 @@
231 276
     #ifndef LCD_HEIGHT
232 277
       #define LCD_HEIGHT 4
233 278
     #endif
234
-  #else // no panel but just LCD
235
-    #if ENABLED(ULTRA_LCD)
236
-      #ifndef LCD_WIDTH
237
-        #define LCD_WIDTH 16
238
-      #endif
239
-      #ifndef LCD_HEIGHT
240
-        #define LCD_HEIGHT 2
241
-      #endif
279
+  #elif ENABLED(ULTRA_LCD)  // no panel but just LCD
280
+    #ifndef LCD_WIDTH
281
+      #define LCD_WIDTH 16
282
+    #endif
283
+    #ifndef LCD_HEIGHT
284
+      #define LCD_HEIGHT 2
242 285
     #endif
243 286
   #endif
244 287
 
@@ -263,7 +306,7 @@
263 306
     #define LCD_STR_FILAM_DIA   "\xf8"
264 307
     #define LCD_STR_FILAM_MUL   "\xa4"
265 308
   #else
266
-    /* Custom characters defined in the first 8 characters of the LCD */
309
+    // Custom characters defined in the first 8 characters of the LCD
267 310
     #define LCD_BEDTEMP_CHAR     0x00  // Print only as a char. This will have 'unexpected' results when used in a string!
268 311
     #define LCD_DEGREE_CHAR      0x01
269 312
     #define LCD_STR_THERMOMETER "\x02" // Still used with string concatenation
@@ -273,12 +316,6 @@
273 316
     #define LCD_FEEDRATE_CHAR    0x06
274 317
     #define LCD_CLOCK_CHAR       0x07
275 318
     #define LCD_STR_ARROW_RIGHT ">"  /* from the default character set */
276
-
277
-    #if ENABLED(AUTO_BED_LEVELING_UBL)
278
-      #define LCD_UBL_BOXTOP_CHAR 0x01
279
-      #define LCD_UBL_BOXBOT_CHAR 0x02
280
-    #endif
281
-
282 319
   #endif
283 320
 
284 321
   /**
@@ -307,7 +344,10 @@
307 344
     #endif
308 345
   #endif
309 346
 
310
-  #ifndef BOOTSCREEN_TIMEOUT
347
+  // Boot screens
348
+  #if DISABLED(ULTRA_LCD)
349
+    #undef SHOW_BOOTSCREEN
350
+  #elif !defined(BOOTSCREEN_TIMEOUT)
311 351
     #define BOOTSCREEN_TIMEOUT 2500
312 352
   #endif
313 353
 
@@ -379,8 +419,10 @@
379 419
       #define NUM_SERVOS (Z_ENDSTOP_SERVO_NR + 1)
380 420
     #endif
381 421
     #undef DEACTIVATE_SERVOS_AFTER_MOVE
382
-    #undef SERVO_DELAY
383
-    #define SERVO_DELAY 50
422
+    #if NUM_SERVOS == 1
423
+      #undef SERVO_DELAY
424
+      #define SERVO_DELAY { 50 }
425
+    #endif
384 426
     #ifndef BLTOUCH_DELAY
385 427
       #define BLTOUCH_DELAY 375
386 428
     #endif
@@ -412,13 +454,6 @@
412 454
   #define HAS_Z_SERVO_ENDSTOP (defined(Z_ENDSTOP_SERVO_NR) && Z_ENDSTOP_SERVO_NR >= 0)
413 455
 
414 456
   /**
415
-   * UBL has its own manual probing, so this just causes trouble.
416
-   */
417
-  #if ENABLED(AUTO_BED_LEVELING_UBL)
418
-    #undef PROBE_MANUALLY
419
-  #endif
420
-
421
-  /**
422 457
    * Set a flag for any enabled probe
423 458
    */
424 459
   #define PROBE_SELECTED (ENABLED(PROBE_MANUALLY) || ENABLED(FIX_MOUNTED_PROBE) || ENABLED(Z_PROBE_ALLEN_KEY) || HAS_Z_SERVO_ENDSTOP || ENABLED(Z_PROBE_SLED) || ENABLED(SOLENOID_PROBE))
@@ -433,6 +468,6 @@
433 468
 
434 469
   #define HAS_SOFTWARE_ENDSTOPS (ENABLED(MIN_SOFTWARE_ENDSTOPS) || ENABLED(MAX_SOFTWARE_ENDSTOPS))
435 470
   #define HAS_RESUME_CONTINUE (ENABLED(NEWPANEL) || ENABLED(EMERGENCY_PARSER))
436
-  #define HAS_COLOR_LEDS (ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632))
471
+  #define HAS_COLOR_LEDS (ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED))
437 472
 
438 473
 #endif // CONDITIONALS_LCD_H

+ 400
- 106
Marlin/Conditionals_post.h 파일 보기

@@ -28,15 +28,45 @@
28 28
 #ifndef CONDITIONALS_POST_H
29 29
 #define CONDITIONALS_POST_H
30 30
 
31
+  #define IS_SCARA (ENABLED(MORGAN_SCARA) || ENABLED(MAKERARM_SCARA))
32
+  #define IS_KINEMATIC (ENABLED(DELTA) || IS_SCARA)
33
+  #define IS_CARTESIAN !IS_KINEMATIC
34
+
31 35
   /**
32 36
    * Axis lengths and center
33 37
    */
34 38
   #define X_MAX_LENGTH (X_MAX_POS - (X_MIN_POS))
35 39
   #define Y_MAX_LENGTH (Y_MAX_POS - (Y_MIN_POS))
36 40
   #define Z_MAX_LENGTH (Z_MAX_POS - (Z_MIN_POS))
37
-  #define X_CENTER float((X_MIN_POS + X_MAX_POS) * 0.5)
38
-  #define Y_CENTER float((Y_MIN_POS + Y_MAX_POS) * 0.5)
39
-  #define Z_CENTER float((Z_MIN_POS + Z_MAX_POS) * 0.5)
41
+
42
+  // Defined only if the sanity-check is bypassed
43
+  #ifndef X_BED_SIZE
44
+    #define X_BED_SIZE X_MAX_LENGTH
45
+  #endif
46
+  #ifndef Y_BED_SIZE
47
+    #define Y_BED_SIZE Y_MAX_LENGTH
48
+  #endif
49
+
50
+  // Require 0,0 bed center for Delta and SCARA
51
+  #if IS_KINEMATIC
52
+    #define BED_CENTER_AT_0_0
53
+  #endif
54
+
55
+  // Define center values for future use
56
+  #if ENABLED(BED_CENTER_AT_0_0)
57
+    #define X_CENTER 0
58
+    #define Y_CENTER 0
59
+  #else
60
+    #define X_CENTER ((X_BED_SIZE) / 2)
61
+    #define Y_CENTER ((Y_BED_SIZE) / 2)
62
+  #endif
63
+  #define Z_CENTER ((Z_MIN_POS + Z_MAX_POS) / 2)
64
+
65
+  // Get the linear boundaries of the bed
66
+  #define X_MIN_BED (X_CENTER - (X_BED_SIZE) / 2)
67
+  #define X_MAX_BED (X_CENTER + (X_BED_SIZE) / 2)
68
+  #define Y_MIN_BED (Y_CENTER - (Y_BED_SIZE) / 2)
69
+  #define Y_MAX_BED (Y_CENTER + (Y_BED_SIZE) / 2)
40 70
 
41 71
   /**
42 72
    * CoreXY, CoreXZ, and CoreYZ - and their reverse
@@ -59,16 +89,19 @@
59 89
       #define CORE_AXIS_1 B_AXIS
60 90
       #define CORE_AXIS_2 C_AXIS
61 91
     #endif
62
-    #if (ENABLED(COREYX) || ENABLED(COREZX) || ENABLED(COREZY))
92
+    #if ENABLED(COREYX) || ENABLED(COREZX) || ENABLED(COREZY)
63 93
       #define CORESIGN(n) (-(n))
64 94
     #else
65 95
       #define CORESIGN(n) (n)
66 96
     #endif
67 97
   #endif
68 98
 
69
-  #define IS_SCARA (ENABLED(MORGAN_SCARA) || ENABLED(MAKERARM_SCARA))
70
-  #define IS_KINEMATIC (ENABLED(DELTA) || IS_SCARA)
71
-  #define IS_CARTESIAN !IS_KINEMATIC
99
+  /**
100
+   * No adjustable bed on non-cartesians
101
+   */
102
+  #if IS_KINEMATIC
103
+    #undef LEVEL_BED_CORNERS
104
+  #endif
72 105
 
73 106
   /**
74 107
    * SCARA cannot use SLOWDOWN and requires QUICKHOME
@@ -87,11 +120,11 @@
87 120
     #if ENABLED(DELTA)
88 121
       #define X_HOME_POS 0
89 122
     #else
90
-      #define X_HOME_POS ((X_MAX_LENGTH) * (X_HOME_DIR) * 0.5)
123
+      #define X_HOME_POS ((X_BED_SIZE) * (X_HOME_DIR) * 0.5)
91 124
     #endif
92 125
   #else
93 126
     #if ENABLED(DELTA)
94
-      #define X_HOME_POS (X_MIN_POS + (X_MAX_LENGTH) * 0.5)
127
+      #define X_HOME_POS (X_MIN_POS + (X_BED_SIZE) * 0.5)
95 128
     #else
96 129
       #define X_HOME_POS (X_HOME_DIR < 0 ? X_MIN_POS : X_MAX_POS)
97 130
     #endif
@@ -103,11 +136,11 @@
103 136
     #if ENABLED(DELTA)
104 137
       #define Y_HOME_POS 0
105 138
     #else
106
-      #define Y_HOME_POS ((Y_MAX_LENGTH) * (Y_HOME_DIR) * 0.5)
139
+      #define Y_HOME_POS ((Y_BED_SIZE) * (Y_HOME_DIR) * 0.5)
107 140
     #endif
108 141
   #else
109 142
     #if ENABLED(DELTA)
110
-      #define Y_HOME_POS (Y_MIN_POS + (Y_MAX_LENGTH) * 0.5)
143
+      #define Y_HOME_POS (Y_MIN_POS + (Y_BED_SIZE) * 0.5)
111 144
     #else
112 145
       #define Y_HOME_POS (Y_HOME_DIR < 0 ? Y_MIN_POS : Y_MAX_POS)
113 146
     #endif
@@ -151,10 +184,10 @@
151 184
    */
152 185
   #if ENABLED(Z_SAFE_HOMING)
153 186
     #ifndef Z_SAFE_HOMING_X_POINT
154
-      #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)
187
+      #define Z_SAFE_HOMING_X_POINT X_CENTER
155 188
     #endif
156 189
     #ifndef Z_SAFE_HOMING_Y_POINT
157
-      #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)
190
+      #define Z_SAFE_HOMING_Y_POINT Y_CENTER
158 191
     #endif
159 192
     #define X_TILT_FULCRUM Z_SAFE_HOMING_X_POINT
160 193
     #define Y_TILT_FULCRUM Z_SAFE_HOMING_Y_POINT
@@ -171,6 +204,13 @@
171 204
   #endif
172 205
 
173 206
   /**
207
+   * Provide a MAX_AUTORETRACT for older configs
208
+   */
209
+  #if ENABLED(FWRETRACT) && !defined(MAX_AUTORETRACT)
210
+    #define MAX_AUTORETRACT 99
211
+  #endif
212
+
213
+  /**
174 214
    * MAX_STEP_FREQUENCY differs for TOSHIBA
175 215
    */
176 216
   #if ENABLED(CONFIG_STEPPERS_TOSHIBA)
@@ -187,13 +227,8 @@
187 227
   #define MICROSTEP16 HIGH,HIGH
188 228
 
189 229
   /**
190
-   * Advance calculated values
230
+   * Override here because this is set in Configuration_adv.h
191 231
    */
192
-  #if ENABLED(ADVANCE)
193
-    #define EXTRUSION_AREA (0.25 * (D_FILAMENT) * (D_FILAMENT) * M_PI)
194
-    #define STEPS_PER_CUBIC_MM_E (axis_steps_per_mm[E_AXIS_N] / (EXTRUSION_AREA))
195
-  #endif
196
-
197 232
   #if ENABLED(ULTIPANEL) && DISABLED(ELB_FULL_GRAPHIC_CONTROLLER)
198 233
     #undef SD_DETECT_INVERTED
199 234
   #endif
@@ -344,28 +379,121 @@
344 379
   #define ARRAY_BY_HOTENDS1(v1) ARRAY_BY_HOTENDS(v1, v1, v1, v1, v1, v1)
345 380
 
346 381
   /**
382
+   * X_DUAL_ENDSTOPS endstop reassignment
383
+   */
384
+  #if ENABLED(X_DUAL_ENDSTOPS)
385
+    #if X_HOME_DIR > 0
386
+      #if X2_USE_ENDSTOP == _XMIN_
387
+        #define X2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
388
+        #define X2_MAX_PIN X_MIN_PIN
389
+      #elif X2_USE_ENDSTOP == _XMAX_
390
+        #define X2_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
391
+        #define X2_MAX_PIN X_MAX_PIN
392
+      #elif X2_USE_ENDSTOP == _YMIN_
393
+        #define X2_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
394
+        #define X2_MAX_PIN Y_MIN_PIN
395
+      #elif X2_USE_ENDSTOP == _YMAX_
396
+        #define X2_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
397
+        #define X2_MAX_PIN Y_MAX_PIN
398
+      #elif X2_USE_ENDSTOP == _ZMIN_
399
+        #define X2_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
400
+        #define X2_MAX_PIN Z_MIN_PIN
401
+      #elif X2_USE_ENDSTOP == _ZMAX_
402
+        #define X2_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
403
+        #define X2_MAX_PIN Z_MAX_PIN
404
+      #else
405
+        #define X2_MAX_ENDSTOP_INVERTING false
406
+      #endif
407
+      #define X2_MIN_ENDSTOP_INVERTING false
408
+    #else
409
+      #if X2_USE_ENDSTOP == _XMIN_
410
+        #define X2_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
411
+        #define X2_MIN_PIN X_MIN_PIN
412
+      #elif X2_USE_ENDSTOP == _XMAX_
413
+        #define X2_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
414
+        #define X2_MIN_PIN X_MAX_PIN
415
+      #elif X2_USE_ENDSTOP == _YMIN_
416
+        #define X2_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
417
+        #define X2_MIN_PIN Y_MIN_PIN
418
+      #elif X2_USE_ENDSTOP == _YMAX_
419
+        #define X2_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
420
+        #define X2_MIN_PIN Y_MAX_PIN
421
+      #elif X2_USE_ENDSTOP == _ZMIN_
422
+        #define X2_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
423
+        #define X2_MIN_PIN Z_MIN_PIN
424
+      #elif X2_USE_ENDSTOP == _ZMAX_
425
+        #define X2_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
426
+        #define X2_MIN_PIN Z_MAX_PIN
427
+      #else
428
+        #define X2_MIN_ENDSTOP_INVERTING false
429
+      #endif
430
+      #define X2_MAX_ENDSTOP_INVERTING false
431
+    #endif
432
+  #endif
433
+
434
+  // Is an endstop plug used for the X2 endstop?
435
+  #define IS_X2_ENDSTOP(A,M) (ENABLED(X_DUAL_ENDSTOPS) && X2_USE_ENDSTOP == _##A##M##_)
436
+
437
+  /**
438
+   * Y_DUAL_ENDSTOPS endstop reassignment
439
+   */
440
+  #if ENABLED(Y_DUAL_ENDSTOPS)
441
+    #if Y_HOME_DIR > 0
442
+      #if Y2_USE_ENDSTOP == _XMIN_
443
+        #define Y2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
444
+        #define Y2_MAX_PIN X_MIN_PIN
445
+      #elif Y2_USE_ENDSTOP == _XMAX_
446
+        #define Y2_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
447
+        #define Y2_MAX_PIN X_MAX_PIN
448
+      #elif Y2_USE_ENDSTOP == _YMIN_
449
+        #define Y2_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
450
+        #define Y2_MAX_PIN Y_MIN_PIN
451
+      #elif Y2_USE_ENDSTOP == _YMAX_
452
+        #define Y2_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
453
+        #define Y2_MAX_PIN Y_MAX_PIN
454
+      #elif Y2_USE_ENDSTOP == _ZMIN_
455
+        #define Y2_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
456
+        #define Y2_MAX_PIN Z_MIN_PIN
457
+      #elif Y2_USE_ENDSTOP == _ZMAX_
458
+        #define Y2_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
459
+        #define Y2_MAX_PIN Z_MAX_PIN
460
+      #else
461
+        #define Y2_MAX_ENDSTOP_INVERTING false
462
+      #endif
463
+      #define Y2_MIN_ENDSTOP_INVERTING false
464
+    #else
465
+      #if Y2_USE_ENDSTOP == _XMIN_
466
+        #define Y2_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
467
+        #define Y2_MIN_PIN X_MIN_PIN
468
+      #elif Y2_USE_ENDSTOP == _XMAX_
469
+        #define Y2_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
470
+        #define Y2_MIN_PIN X_MAX_PIN
471
+      #elif Y2_USE_ENDSTOP == _YMIN_
472
+        #define Y2_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
473
+        #define Y2_MIN_PIN Y_MIN_PIN
474
+      #elif Y2_USE_ENDSTOP == _YMAX_
475
+        #define Y2_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
476
+        #define Y2_MIN_PIN Y_MAX_PIN
477
+      #elif Y2_USE_ENDSTOP == _ZMIN_
478
+        #define Y2_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
479
+        #define Y2_MIN_PIN Z_MIN_PIN
480
+      #elif Y2_USE_ENDSTOP == _ZMAX_
481
+        #define Y2_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
482
+        #define Y2_MIN_PIN Z_MAX_PIN
483
+      #else
484
+        #define Y2_MIN_ENDSTOP_INVERTING false
485
+      #endif
486
+      #define Y2_MAX_ENDSTOP_INVERTING false
487
+    #endif
488
+  #endif
489
+
490
+  // Is an endstop plug used for the Y2 endstop or the bed probe?
491
+  #define IS_Y2_ENDSTOP(A,M) (ENABLED(Y_DUAL_ENDSTOPS) && Y2_USE_ENDSTOP == _##A##M##_)
492
+
493
+  /**
347 494
    * Z_DUAL_ENDSTOPS endstop reassignment
348 495
    */
349 496
   #if ENABLED(Z_DUAL_ENDSTOPS)
350
-    #define _XMIN_ 100
351
-    #define _YMIN_ 200
352
-    #define _ZMIN_ 300
353
-    #define _XMAX_ 101
354
-    #define _YMAX_ 201
355
-    #define _ZMAX_ 301
356
-    #if Z2_USE_ENDSTOP == _XMIN_
357
-      #define USE_XMIN_PLUG
358
-    #elif Z2_USE_ENDSTOP == _XMAX_
359
-      #define USE_XMAX_PLUG
360
-    #elif Z2_USE_ENDSTOP == _YMIN_
361
-      #define USE_YMIN_PLUG
362
-    #elif Z2_USE_ENDSTOP == _YMAX_
363
-      #define USE_YMAX_PLUG
364
-    #elif Z2_USE_ENDSTOP == _ZMIN_
365
-      #define USE_ZMIN_PLUG
366
-    #elif Z2_USE_ENDSTOP == _ZMAX_
367
-      #define USE_ZMAX_PLUG
368
-    #endif
369 497
     #if Z_HOME_DIR > 0
370 498
       #if Z2_USE_ENDSTOP == _XMIN_
371 499
         #define Z2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
@@ -388,6 +516,7 @@
388 516
       #else
389 517
         #define Z2_MAX_ENDSTOP_INVERTING false
390 518
       #endif
519
+      #define Z2_MIN_ENDSTOP_INVERTING false
391 520
     #else
392 521
       #if Z2_USE_ENDSTOP == _XMIN_
393 522
         #define Z2_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
@@ -410,6 +539,7 @@
410 539
       #else
411 540
         #define Z2_MIN_ENDSTOP_INVERTING false
412 541
       #endif
542
+      #define Z2_MAX_ENDSTOP_INVERTING false
413 543
     #endif
414 544
   #endif
415 545
 
@@ -506,12 +636,16 @@
506 636
   #define HAS_SOLENOID_4    (PIN_EXISTS(SOL4))
507 637
 
508 638
   // Endstops and bed probe
509
-  #define HAS_X_MIN (PIN_EXISTS(X_MIN) && !IS_Z2_OR_PROBE(X,MIN))
510
-  #define HAS_X_MAX (PIN_EXISTS(X_MAX) && !IS_Z2_OR_PROBE(X,MAX))
511
-  #define HAS_Y_MIN (PIN_EXISTS(Y_MIN) && !IS_Z2_OR_PROBE(Y,MIN))
512
-  #define HAS_Y_MAX (PIN_EXISTS(Y_MAX) && !IS_Z2_OR_PROBE(Y,MAX))
513
-  #define HAS_Z_MIN (PIN_EXISTS(Z_MIN) && !IS_Z2_OR_PROBE(Z,MIN))
514
-  #define HAS_Z_MAX (PIN_EXISTS(Z_MAX) && !IS_Z2_OR_PROBE(Z,MAX))
639
+  #define HAS_X_MIN (PIN_EXISTS(X_MIN) && !IS_X2_ENDSTOP(X,MIN) && !IS_Y2_ENDSTOP(X,MIN) && !IS_Z2_OR_PROBE(X,MIN))
640
+  #define HAS_X_MAX (PIN_EXISTS(X_MAX) && !IS_X2_ENDSTOP(X,MAX) && !IS_Y2_ENDSTOP(X,MAX) && !IS_Z2_OR_PROBE(X,MAX))
641
+  #define HAS_Y_MIN (PIN_EXISTS(Y_MIN) && !IS_X2_ENDSTOP(Y,MIN) && !IS_Y2_ENDSTOP(Y,MIN) && !IS_Z2_OR_PROBE(Y,MIN))
642
+  #define HAS_Y_MAX (PIN_EXISTS(Y_MAX) && !IS_X2_ENDSTOP(Y,MAX) && !IS_Y2_ENDSTOP(Y,MAX) && !IS_Z2_OR_PROBE(Y,MAX))
643
+  #define HAS_Z_MIN (PIN_EXISTS(Z_MIN) && !IS_X2_ENDSTOP(Z,MIN) && !IS_Y2_ENDSTOP(Z,MIN) && !IS_Z2_OR_PROBE(Z,MIN))
644
+  #define HAS_Z_MAX (PIN_EXISTS(Z_MAX) && !IS_X2_ENDSTOP(Z,MAX) && !IS_Y2_ENDSTOP(Z,MAX) && !IS_Z2_OR_PROBE(Z,MAX))
645
+  #define HAS_X2_MIN (PIN_EXISTS(X2_MIN))
646
+  #define HAS_X2_MAX (PIN_EXISTS(X2_MAX))
647
+  #define HAS_Y2_MIN (PIN_EXISTS(Y2_MIN))
648
+  #define HAS_Y2_MAX (PIN_EXISTS(Y2_MAX))
515 649
   #define HAS_Z2_MIN (PIN_EXISTS(Z2_MIN))
516 650
   #define HAS_Z2_MAX (PIN_EXISTS(Z2_MAX))
517 651
   #define HAS_Z_MIN_PROBE_PIN (PIN_EXISTS(Z_MIN_PROBE))
@@ -616,8 +750,18 @@
616 750
   #else
617 751
     #define WRITE_HEATER_0(v) WRITE_HEATER_0P(v)
618 752
   #endif
753
+
754
+  /**
755
+   * Heated bed requires settings
756
+   */
619 757
   #if HAS_HEATER_BED
620
-    #define WRITE_HEATER_BED(v) WRITE(HEATER_BED_PIN, v)
758
+    #ifndef MAX_BED_POWER
759
+      #define MAX_BED_POWER 255
760
+    #endif
761
+    #ifndef HEATER_BED_INVERTING
762
+      #define HEATER_BED_INVERTING false
763
+    #endif
764
+    #define WRITE_HEATER_BED(v) WRITE(HEATER_BED_PIN, (v) ^ HEATER_BED_INVERTING)
621 765
   #endif
622 766
 
623 767
   /**
@@ -645,15 +789,10 @@
645 789
   #endif
646 790
   #define WRITE_FAN_N(n, v) WRITE_FAN##n(v)
647 791
 
648
-
649 792
   /**
650
-   * Heater & Fan Pausing
793
+   * Part Cooling fan multipliexer
651 794
    */
652
-  #if FAN_COUNT == 0
653
-    #undef PROBING_FANS_OFF
654
-  #endif
655
-  #define QUIET_PROBING (HAS_BED_PROBE && (ENABLED(PROBING_HEATERS_OFF) || ENABLED(PROBING_FANS_OFF)))
656
-  #define HEATER_IDLE_HANDLER (ENABLED(ADVANCED_PAUSE_FEATURE) || ENABLED(PROBING_HEATERS_OFF))
795
+  #define HAS_FANMUX PIN_EXISTS(FANMUX0)
657 796
 
658 797
   /**
659 798
    * Servos and probes
@@ -665,9 +804,7 @@
665 804
     #endif
666 805
   #endif
667 806
 
668
-  #define PROBE_PIN_CONFIGURED (HAS_Z_MIN_PROBE_PIN || (HAS_Z_MIN && ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)))
669
-
670
-  #define HAS_BED_PROBE (PROBE_SELECTED && PROBE_PIN_CONFIGURED && DISABLED(PROBE_MANUALLY))
807
+  #define HAS_BED_PROBE (PROBE_SELECTED && DISABLED(PROBE_MANUALLY))
671 808
 
672 809
   #if ENABLED(Z_PROBE_ALLEN_KEY)
673 810
     #define PROBE_IS_TRIGGERED_WHEN_STOWED_TEST
@@ -708,9 +845,74 @@
708 845
   #endif
709 846
 
710 847
   /**
848
+   * XYZ Bed Skew Correction
849
+   */
850
+  #if ENABLED(SKEW_CORRECTION)
851
+    #define SKEW_FACTOR_MIN -1
852
+    #define SKEW_FACTOR_MAX 1
853
+
854
+    #define _GET_SIDE(a,b,c) (SQRT(2*sq(a)+2*sq(b)-4*sq(c))*0.5)
855
+    #define _SKEW_SIDE(a,b,c) tan(M_PI*0.5-acos((sq(a)-sq(b)-sq(c))/(2*c*b)))
856
+    #define _SKEW_FACTOR(a,b,c) _SKEW_SIDE(a,_GET_SIDE(a,b,c),c)
857
+
858
+    #ifndef XY_SKEW_FACTOR
859
+      constexpr float XY_SKEW_FACTOR = (
860
+        #if defined(XY_DIAG_AC) && defined(XY_DIAG_BD) && defined(XY_SIDE_AD)
861
+          _SKEW_FACTOR(XY_DIAG_AC, XY_DIAG_BD, XY_SIDE_AD)
862
+        #else
863
+          0.0
864
+        #endif
865
+      );
866
+    #endif
867
+    #ifndef XZ_SKEW_FACTOR
868
+      #if defined(XY_SIDE_AD) && !defined(XZ_SIDE_AD)
869
+        #define XZ_SIDE_AD XY_SIDE_AD
870
+      #endif
871
+      constexpr float XZ_SKEW_FACTOR = (
872
+        #if defined(XZ_DIAG_AC) && defined(XZ_DIAG_BD) && defined(XZ_SIDE_AD)
873
+          _SKEW_FACTOR(XZ_DIAG_AC, XZ_DIAG_BD, XZ_SIDE_AD)
874
+        #else
875
+          0.0
876
+        #endif
877
+      );
878
+    #endif
879
+    #ifndef YZ_SKEW_FACTOR
880
+      constexpr float YZ_SKEW_FACTOR = (
881
+        #if defined(YZ_DIAG_AC) && defined(YZ_DIAG_BD) && defined(YZ_SIDE_AD)
882
+          _SKEW_FACTOR(YZ_DIAG_AC, YZ_DIAG_BD, YZ_SIDE_AD)
883
+        #else
884
+          0.0
885
+        #endif
886
+      );
887
+    #endif
888
+  #endif // SKEW_CORRECTION
889
+
890
+  /**
891
+   * Heater & Fan Pausing
892
+   */
893
+  #if FAN_COUNT == 0
894
+    #undef PROBING_FANS_OFF
895
+  #endif
896
+  #define QUIET_PROBING (HAS_BED_PROBE && (ENABLED(PROBING_HEATERS_OFF) || ENABLED(PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0))
897
+  #define HEATER_IDLE_HANDLER (ENABLED(ADVANCED_PAUSE_FEATURE) || ENABLED(PROBING_HEATERS_OFF))
898
+
899
+  /**
900
+   * Only constrain Z on DELTA / SCARA machines
901
+   */
902
+  #if IS_KINEMATIC
903
+    #undef MIN_SOFTWARE_ENDSTOP_X
904
+    #undef MIN_SOFTWARE_ENDSTOP_Y
905
+    #undef MAX_SOFTWARE_ENDSTOP_X
906
+    #undef MAX_SOFTWARE_ENDSTOP_Y
907
+  #endif
908
+
909
+  /**
711 910
    * Delta radius/rod trimmers/angle trimmers
712 911
    */
713 912
   #if ENABLED(DELTA)
913
+    #ifndef DELTA_PROBEABLE_RADIUS
914
+      #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
915
+    #endif
714 916
     #ifndef DELTA_CALIBRATION_RADIUS
715 917
       #define DELTA_CALIBRATION_RADIUS DELTA_PRINTABLE_RADIUS - 10
716 918
     #endif
@@ -731,19 +933,103 @@
731 933
   /**
732 934
    * Set granular options based on the specific type of leveling
733 935
    */
734
-
735
-  #define UBL_DELTA  (ENABLED(AUTO_BED_LEVELING_UBL) && (ENABLED(DELTA) || ENABLED(UBL_GRANULAR_SEGMENTATION_FOR_CARTESIAN)))
736
-  #define ABL_PLANAR (ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_3POINT))
737
-  #define ABL_GRID   (ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR))
738
-  #define HAS_ABL    (ABL_PLANAR || ABL_GRID || ENABLED(AUTO_BED_LEVELING_UBL))
739
-  #define HAS_LEVELING          (HAS_ABL || ENABLED(MESH_BED_LEVELING))
740
-  #define PLANNER_LEVELING      (ABL_PLANAR || ABL_GRID || ENABLED(MESH_BED_LEVELING) || UBL_DELTA)
936
+  #define UBL_SEGMENTED  (ENABLED(AUTO_BED_LEVELING_UBL) && (ENABLED(DELTA) || ENABLED(SEGMENT_LEVELED_MOVES)))
937
+  #define ABL_PLANAR     (ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_3POINT))
938
+  #define ABL_GRID       (ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR))
939
+  #define OLDSCHOOL_ABL  (ABL_PLANAR || ABL_GRID)
940
+  #define HAS_ABL        (OLDSCHOOL_ABL || ENABLED(AUTO_BED_LEVELING_UBL))
941
+  #define HAS_LEVELING   (HAS_ABL || ENABLED(MESH_BED_LEVELING))
942
+  #define HAS_AUTOLEVEL  (HAS_ABL && DISABLED(PROBE_MANUALLY))
943
+  #define HAS_MESH       (ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(MESH_BED_LEVELING))
944
+  #define PLANNER_LEVELING      (OLDSCHOOL_ABL || ENABLED(MESH_BED_LEVELING) || UBL_SEGMENTED || ENABLED(SKEW_CORRECTION))
741 945
   #define HAS_PROBING_PROCEDURE (HAS_ABL || ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST))
742 946
   #if HAS_PROBING_PROCEDURE
743 947
     #define PROBE_BED_WIDTH abs(RIGHT_PROBE_BED_POSITION - (LEFT_PROBE_BED_POSITION))
744 948
     #define PROBE_BED_HEIGHT abs(BACK_PROBE_BED_POSITION - (FRONT_PROBE_BED_POSITION))
745 949
   #endif
746 950
 
951
+  #if ENABLED(SEGMENT_LEVELED_MOVES) && !defined(LEVELED_SEGMENT_LENGTH)
952
+    #define LEVELED_SEGMENT_LENGTH 5
953
+  #endif
954
+
955
+  /**
956
+   * Bed Probing rectangular bounds
957
+   * These can be further constrained in code for Delta and SCARA
958
+   */
959
+  #if ENABLED(DELTA)
960
+    // Probing points may be verified at compile time within the radius
961
+    // using static_assert(HYPOT2(X2-X1,Y2-Y1)<=sq(DELTA_PRINTABLE_RADIUS),"bad probe point!")
962
+    // so that may be added to SanityCheck.h in the future.
963
+    #define _MIN_PROBE_X (X_CENTER - DELTA_PRINTABLE_RADIUS)
964
+    #define _MIN_PROBE_Y (Y_CENTER - DELTA_PRINTABLE_RADIUS)
965
+    #define _MAX_PROBE_X (X_CENTER + DELTA_PRINTABLE_RADIUS)
966
+    #define _MAX_PROBE_Y (Y_CENTER + DELTA_PRINTABLE_RADIUS)
967
+  #elif IS_SCARA
968
+    #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
969
+    #define _MIN_PROBE_X (X_CENTER - (SCARA_PRINTABLE_RADIUS))
970
+    #define _MIN_PROBE_Y (Y_CENTER - (SCARA_PRINTABLE_RADIUS))
971
+    #define _MAX_PROBE_X (X_CENTER +  SCARA_PRINTABLE_RADIUS)
972
+    #define _MAX_PROBE_Y (Y_CENTER +  SCARA_PRINTABLE_RADIUS)
973
+  #else
974
+    // Boundaries for Cartesian probing based on bed limits
975
+    #define _MIN_PROBE_X (max(X_MIN_BED, X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
976
+    #define _MIN_PROBE_Y (max(Y_MIN_BED, Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
977
+    #define _MAX_PROBE_X (min(X_MAX_BED, X_MAX_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
978
+    #define _MAX_PROBE_Y (min(Y_MAX_BED, Y_MAX_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
979
+  #endif
980
+
981
+  // Allow configuration to override these for special purposes
982
+  #ifndef MIN_PROBE_X
983
+    #define MIN_PROBE_X _MIN_PROBE_X
984
+  #endif
985
+  #ifndef MIN_PROBE_Y
986
+    #define MIN_PROBE_Y _MIN_PROBE_Y
987
+  #endif
988
+  #ifndef MAX_PROBE_X
989
+    #define MAX_PROBE_X _MAX_PROBE_X
990
+  #endif
991
+  #ifndef MAX_PROBE_Y
992
+    #define MAX_PROBE_Y _MAX_PROBE_Y
993
+  #endif
994
+
995
+  /**
996
+   * Default mesh area is an area with an inset margin on the print area.
997
+   */
998
+  #if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
999
+    #if IS_KINEMATIC
1000
+      // Probing points may be verified at compile time within the radius
1001
+      // using static_assert(HYPOT2(X2-X1,Y2-Y1)<=sq(DELTA_PRINTABLE_RADIUS),"bad probe point!")
1002
+      // so that may be added to SanityCheck.h in the future.
1003
+      #define _MESH_MIN_X (MIN_PROBE_X + MESH_INSET)
1004
+      #define _MESH_MIN_Y (MIN_PROBE_Y + MESH_INSET)
1005
+      #define _MESH_MAX_X (MAX_PROBE_X - (MESH_INSET))
1006
+      #define _MESH_MAX_Y (MAX_PROBE_Y - (MESH_INSET))
1007
+    #else
1008
+      // Boundaries for Cartesian probing based on set limits
1009
+      #define _MESH_MIN_X (max(X_MIN_BED + MESH_INSET, X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
1010
+      #define _MESH_MIN_Y (max(Y_MIN_BED + MESH_INSET, Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
1011
+      #define _MESH_MAX_X (min(X_MAX_BED - (MESH_INSET), X_MAX_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
1012
+      #define _MESH_MAX_Y (min(Y_MAX_BED - (MESH_INSET), Y_MAX_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
1013
+    #endif
1014
+    /**
1015
+     * These may be overridden in Configuration if a smaller area is wanted
1016
+     */
1017
+    #if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
1018
+      #ifndef MESH_MIN_X
1019
+        #define MESH_MIN_X _MESH_MIN_X
1020
+      #endif
1021
+      #ifndef MESH_MIN_Y
1022
+        #define MESH_MIN_Y _MESH_MIN_Y
1023
+      #endif
1024
+      #ifndef MESH_MAX_X
1025
+        #define MESH_MAX_X _MESH_MAX_X
1026
+      #endif
1027
+      #ifndef MESH_MAX_Y
1028
+        #define MESH_MAX_Y _MESH_MAX_Y
1029
+      #endif
1030
+    #endif
1031
+  #endif // MESH_BED_LEVELING || AUTO_BED_LEVELING_UBL
1032
+
747 1033
   /**
748 1034
    * Buzzer/Speaker
749 1035
    */
@@ -764,6 +1050,18 @@
764 1050
   #endif
765 1051
 
766 1052
   /**
1053
+   * VIKI2, miniVIKI, and AZSMZ_12864 require DOGLCD_SCK and DOGLCD_MOSI to be defined.
1054
+   */
1055
+  #if ENABLED(VIKI2) || ENABLED(miniVIKI) || ENABLED(AZSMZ_12864)
1056
+    #ifndef DOGLCD_SCK
1057
+      #define DOGLCD_SCK  SCK_PIN
1058
+    #endif
1059
+    #ifndef DOGLCD_MOSI
1060
+      #define DOGLCD_MOSI MOSI_PIN
1061
+    #endif
1062
+  #endif
1063
+
1064
+  /**
767 1065
    * Z_HOMING_HEIGHT / Z_CLEARANCE_BETWEEN_PROBES
768 1066
    */
769 1067
   #ifndef Z_HOMING_HEIGHT
@@ -782,27 +1080,6 @@
782 1080
     #define MANUAL_PROBE_HEIGHT Z_HOMING_HEIGHT
783 1081
   #endif
784 1082
 
785
-  #if ENABLED(DELTA)
786
-    // These will be further constrained in code, but UBL_PROBE_PT values
787
-    // cannot be compile-time verified within the radius.
788
-    #define MIN_PROBE_X (-DELTA_PRINTABLE_RADIUS)
789
-    #define MAX_PROBE_X ( DELTA_PRINTABLE_RADIUS)
790
-    #define MIN_PROBE_Y (-DELTA_PRINTABLE_RADIUS)
791
-    #define MAX_PROBE_Y ( DELTA_PRINTABLE_RADIUS)
792
-  #elif IS_SCARA
793
-    #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
794
-    #define MIN_PROBE_X (-SCARA_PRINTABLE_RADIUS)
795
-    #define MAX_PROBE_X ( SCARA_PRINTABLE_RADIUS)
796
-    #define MIN_PROBE_Y (-SCARA_PRINTABLE_RADIUS)
797
-    #define MAX_PROBE_Y ( SCARA_PRINTABLE_RADIUS)
798
-  #else
799
-    // Boundaries for probing based on set limits
800
-    #define MIN_PROBE_X (max(X_MIN_POS, X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
801
-    #define MAX_PROBE_X (min(X_MAX_POS, X_MAX_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
802
-    #define MIN_PROBE_Y (max(Y_MIN_POS, Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
803
-    #define MAX_PROBE_Y (min(Y_MAX_POS, Y_MAX_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
804
-  #endif
805
-
806 1083
   // Stepper pulse duration, in cycles
807 1084
   #define STEP_PULSE_CYCLES ((MINIMUM_STEPPER_PULSE) * CYCLES_PER_MICROSECOND)
808 1085
 
@@ -813,7 +1090,7 @@
813 1090
   // Updated G92 behavior shifts the workspace
814 1091
   #define HAS_POSITION_SHIFT DISABLED(NO_WORKSPACE_OFFSETS)
815 1092
   // The home offset also shifts the coordinate space
816
-  #define HAS_HOME_OFFSET (DISABLED(NO_WORKSPACE_OFFSETS) || ENABLED(DELTA))
1093
+  #define HAS_HOME_OFFSET (DISABLED(NO_WORKSPACE_OFFSETS) && DISABLED(DELTA))
817 1094
   // Either offset yields extra calculations on all moves
818 1095
   #define HAS_WORKSPACE_OFFSET (HAS_POSITION_SHIFT || HAS_HOME_OFFSET)
819 1096
   // M206 doesn't apply to DELTA
@@ -824,33 +1101,50 @@
824 1101
     #define LCD_TIMEOUT_TO_STATUS 15000
825 1102
   #endif
826 1103
 
827
-  /**
828
-   * DELTA_SEGMENT_MIN_LENGTH and DELTA_PROBEABLE_RADIUS for UBL_DELTA
829
-   */
830
-  #if UBL_DELTA
831
-    #ifndef DELTA_SEGMENT_MIN_LENGTH
832
-      #if IS_SCARA
833
-        #define DELTA_SEGMENT_MIN_LENGTH 0.25 // SCARA minimum segment size is 0.25mm
834
-      #elif ENABLED(DELTA)
835
-        #define DELTA_SEGMENT_MIN_LENGTH 0.10 // mm (still subject to DELTA_SEGMENTS_PER_SECOND)
836
-      #else // CARTESIAN
837
-        #define DELTA_SEGMENT_MIN_LENGTH 1.00 // mm (similar to G2/G3 arc segmentation)
838
-      #endif
839
-    #endif
840
-    #ifndef DELTA_PROBEABLE_RADIUS
841
-      #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
842
-    #endif
843
-  #endif
844
-
845 1104
   // Shorthand
846 1105
   #define GRID_MAX_POINTS ((GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y))
847 1106
 
848 1107
   // Add commands that need sub-codes to this list
849
-  #define USE_GCODE_SUBCODES ENABLED(G38_PROBE_TARGET)
1108
+  #define USE_GCODE_SUBCODES ENABLED(G38_PROBE_TARGET) || ENABLED(CNC_COORDINATE_SYSTEMS)
850 1109
 
851
-  // MESH_BED_LEVELING overrides PROBE_MANUALLY
852
-  #if ENABLED(MESH_BED_LEVELING)
853
-    #undef PROBE_MANUALLY
1110
+  // Parking Extruder
1111
+  #if ENABLED(PARKING_EXTRUDER)
1112
+    #ifndef PARKING_EXTRUDER_GRAB_DISTANCE
1113
+      #define PARKING_EXTRUDER_GRAB_DISTANCE 0
1114
+    #endif
1115
+    #ifndef PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE
1116
+      #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE HIGH
1117
+    #endif
1118
+  #endif
1119
+
1120
+  // Number of VFAT entries used. Each entry has 13 UTF-16 characters
1121
+  #if ENABLED(SCROLL_LONG_FILENAMES)
1122
+    #define MAX_VFAT_ENTRIES (5)
1123
+  #else
1124
+    #define MAX_VFAT_ENTRIES (2)
1125
+  #endif
1126
+
1127
+  // Set defaults for unspecified LED user colors
1128
+  #if ENABLED(LED_CONTROL_MENU)
1129
+    #ifndef LED_USER_PRESET_RED
1130
+      #define LED_USER_PRESET_RED       255
1131
+    #endif
1132
+    #ifndef LED_USER_PRESET_GREEN
1133
+      #define LED_USER_PRESET_GREEN     255
1134
+    #endif
1135
+    #ifndef LED_USER_PRESET_BLUE
1136
+      #define LED_USER_PRESET_BLUE      255
1137
+    #endif
1138
+    #ifndef LED_USER_PRESET_WHITE
1139
+      #define LED_USER_PRESET_WHITE     0
1140
+    #endif
1141
+    #ifndef LED_USER_PRESET_BRIGHTNESS
1142
+      #ifdef NEOPIXEL_BRIGHTNESS
1143
+        #define LED_USER_PRESET_BRIGHTNESS NEOPIXEL_BRIGHTNESS
1144
+      #else
1145
+        #define LED_USER_PRESET_BRIGHTNESS 255
1146
+      #endif
1147
+    #endif
854 1148
   #endif
855 1149
 
856 1150
 #endif // CONDITIONALS_POST_H

+ 248
- 107
Marlin/Configuration.h 파일 보기

@@ -37,7 +37,7 @@
37 37
  */
38 38
 #ifndef CONFIGURATION_H
39 39
 #define CONFIGURATION_H
40
-#define CONFIGURATION_H_VERSION 010100
40
+#define CONFIGURATION_H_VERSION 010107
41 41
 
42 42
 //===========================================================================
43 43
 //============================= Getting Started =============================
@@ -107,8 +107,9 @@
107 107
  *
108 108
  * 250000 works in most cases, but you might try a lower speed if
109 109
  * you commonly experience drop-outs during host printing.
110
+ * You may try up to 1000000 to speed up SD file transfer.
110 111
  *
111
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
112
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
112 113
  */
113 114
 #define BAUDRATE 115200
114 115
 
@@ -135,6 +136,9 @@
135 136
 // :[1, 2, 3, 4, 5]
136 137
 #define EXTRUDERS 1
137 138
 
139
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
140
+#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75
141
+
138 142
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
139 143
 //#define SINGLENOZZLE
140 144
 
@@ -176,6 +180,21 @@
176 180
 #endif
177 181
 
178 182
 /**
183
+ * Two separate X-carriages with extruders that connect to a moving part
184
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
185
+ */
186
+//#define PARKING_EXTRUDER
187
+#if ENABLED(PARKING_EXTRUDER)
188
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
189
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
190
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
191
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
192
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
193
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
194
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
195
+#endif
196
+
197
+/**
179 198
  * "Mixing Extruder"
180 199
  *   - Adds a new code, M165, to set the current mix factors.
181 200
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -319,8 +338,9 @@
319 338
 
320 339
 // Comment the following line to disable PID and enable bang-bang.
321 340
 #define PIDTEMP
322
-#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
323
-#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
341
+#define BANG_MAX 255     // Limits current to nozzle while in bang-bang mode; 255=full current
342
+#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
343
+#define PID_K1 0.95      // Smoothing factor within the PID
324 344
 #if ENABLED(PIDTEMP)
325 345
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
326 346
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -330,7 +350,6 @@
330 350
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
331 351
   #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
332 352
                                   // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
333
-  #define K1 0.95 //smoothing factor within the PID
334 353
 
335 354
   // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
336 355
 
@@ -399,24 +418,25 @@
399 418
 // or to allow moving the extruder regardless of the hotend temperature.
400 419
 // *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
401 420
 #define PREVENT_COLD_EXTRUSION
402
-#define EXTRUDE_MINTEMP 170
421
+#define EXTRUDE_MINTEMP 180
403 422
 
404 423
 // This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
405 424
 // Note that for Bowden Extruders a too-small value here may prevent loading.
406 425
 #define PREVENT_LENGTHY_EXTRUDE
407
-#define EXTRUDE_MAXLENGTH 200
426
+#define EXTRUDE_MAXLENGTH 500
408 427
 
409 428
 //===========================================================================
410 429
 //======================== Thermal Runaway Protection =======================
411 430
 //===========================================================================
412 431
 
413 432
 /**
414
- * Thermal Protection protects your printer from damage and fire if a
415
- * thermistor falls out or temperature sensors fail in any way.
433
+ * Thermal Protection provides additional protection to your printer from damage
434
+ * and fire. Marlin always includes safe min and max temperature ranges which
435
+ * protect against a broken or disconnected thermistor wire.
416 436
  *
417
- * The issue: If a thermistor falls out or a temperature sensor fails,
418
- * Marlin can no longer sense the actual temperature. Since a disconnected
419
- * thermistor reads as a low temperature, the firmware will keep the heater on.
437
+ * The issue: If a thermistor falls out, it will report the much lower
438
+ * temperature of the air in the room, and the the firmware will keep
439
+ * the heater on.
420 440
  *
421 441
  * If you get "Thermal Runaway" or "Heating failed" errors the
422 442
  * details can be tuned in Configuration_adv.h
@@ -545,19 +565,18 @@
545 565
  * When changing speed and direction, if the difference is less than the
546 566
  * value set here, it may happen instantaneously.
547 567
  */
548
-#define DEFAULT_XJERK                 20.0
549
-#define DEFAULT_YJERK                 20.0
568
+#define DEFAULT_XJERK                 15.0
569
+#define DEFAULT_YJERK                 15.0
550 570
 #define DEFAULT_ZJERK                  0.4
551 571
 #define DEFAULT_EJERK                  5.0
552 572
 
553
-
554 573
 //===========================================================================
555 574
 //============================= Z Probe Options =============================
556 575
 //===========================================================================
557 576
 // @section probes
558 577
 
559 578
 //
560
-// See http://marlinfw.org/configuration/probes.html
579
+// See http://marlinfw.org/docs/configuration/probes.html
561 580
 //
562 581
 
563 582
 /**
@@ -592,7 +611,7 @@
592 611
  * Probe Type
593 612
  *
594 613
  * Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
595
- * You must activate one of these to use Auto Bed Leveling below.
614
+ * Activate one of these to use Auto Bed Leveling below.
596 615
  */
597 616
 
598 617
 /**
@@ -623,14 +642,15 @@
623 642
 #endif
624 643
 
625 644
 /**
626
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
627
- * options selected below - will be disabled during probing so as to minimize
628
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
629
- * in current flowing through the wires).  This is likely most useful to users of the
630
- * BLTouch probe, but may also help those with inductive or other probe types.
645
+ * Enable one or more of the following if probing seems unreliable.
646
+ * Heaters and/or fans can be disabled during probing to minimize electrical
647
+ * noise. A delay can also be added to allow noise and vibration to settle.
648
+ * These options are most useful for the BLTouch probe, but may also improve
649
+ * readings with inductive probes and piezo sensors.
631 650
  */
632 651
 //#define PROBING_HEATERS_OFF       // Turn heaters off when probing
633 652
 //#define PROBING_FANS_OFF          // Turn fans off when probing
653
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
634 654
 
635 655
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
636 656
 //#define SOLENOID_PROBE
@@ -669,14 +689,16 @@
669 689
 // X and Y axis travel speed (mm/m) between probes
670 690
 #define XY_PROBE_SPEED 8000
671 691
 
672
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
692
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
673 693
 #define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
674 694
 
675 695
 // Speed for the "accurate" probe of each point
676 696
 #define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
677 697
 
678
-// Use double touch for probing
679
-//#define PROBE_DOUBLE_TOUCH
698
+// The number of probes to perform at each point.
699
+//   Set to 2 for a fast/slow probe, using the second probe result.
700
+//   Set to 3 or more for slow probes, averaging the results.
701
+//#define MULTIPLE_PROBING 2
680 702
 
681 703
 /**
682 704
  * Z probes require clearance when deploying, stowing, and moving between
@@ -743,7 +765,9 @@
743 765
 
744 766
 // @section homing
745 767
 
746
-#define Z_HOMING_HEIGHT 0  // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
768
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
769
+
770
+//#define Z_HOMING_HEIGHT 4  // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
747 771
                              // Be sure you have this distance over your Z_MAX_POS in case.
748 772
 
749 773
 // Direction of endstops when homing; 1=MAX, -1=MIN
@@ -754,18 +778,42 @@
754 778
 
755 779
 // @section machine
756 780
 
757
-// Travel limits after homing (units are in mm)
781
+// The size of the print bed
782
+#define X_BED_SIZE 80
783
+#define Y_BED_SIZE 80
784
+
785
+// Travel limits (mm) after homing, corresponding to endstop positions.
758 786
 #define X_MIN_POS 0
759 787
 #define Y_MIN_POS 0
760 788
 #define Z_MIN_POS 0
761
-#define X_MAX_POS 80
762
-#define Y_MAX_POS 80
789
+#define X_MAX_POS X_BED_SIZE
790
+#define Y_MAX_POS Y_BED_SIZE
763 791
 #define Z_MAX_POS 80
764 792
 
765
-// If enabled, axes won't move below MIN_POS in response to movement commands.
793
+/**
794
+ * Software Endstops
795
+ *
796
+ * - Prevent moves outside the set machine bounds.
797
+ * - Individual axes can be disabled, if desired.
798
+ * - X and Y only apply to Cartesian robots.
799
+ * - Use 'M211' to set software endstops on/off or report current state
800
+ */
801
+
802
+// Min software endstops curtail movement below minimum coordinate bounds
766 803
 #define MIN_SOFTWARE_ENDSTOPS
767
-// If enabled, axes won't move above MAX_POS in response to movement commands.
804
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
805
+  #define MIN_SOFTWARE_ENDSTOP_X
806
+  #define MIN_SOFTWARE_ENDSTOP_Y
807
+  #define MIN_SOFTWARE_ENDSTOP_Z
808
+#endif
809
+
810
+// Max software endstops curtail movement above maximum coordinate bounds
768 811
 #define MAX_SOFTWARE_ENDSTOPS
812
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
813
+  #define MAX_SOFTWARE_ENDSTOP_X
814
+  #define MAX_SOFTWARE_ENDSTOP_Y
815
+  #define MAX_SOFTWARE_ENDSTOP_Z
816
+#endif
769 817
 
770 818
 /**
771 819
  * Filament Runout Sensor
@@ -785,7 +833,7 @@
785 833
 //===========================================================================
786 834
 //=============================== Bed Leveling ==============================
787 835
 //===========================================================================
788
-// @section bedlevel
836
+// @section calibrate
789 837
 
790 838
 /**
791 839
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -811,12 +859,7 @@
811 859
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
812 860
  *   A comprehensive bed leveling system combining the features and benefits
813 861
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
814
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
815
- *   for Cartesian Printers. That said, it was primarily designed to correct
816
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
817
- *   please post an issue if something doesn't work correctly. Initially,
818
- *   you will need to set a reduced bed size so you have a rectangular area
819
- *   to test on.
862
+ *   Validation and Mesh Editing systems.
820 863
  *
821 864
  * - MESH_BED_LEVELING
822 865
  *   Probe a grid manually
@@ -843,6 +886,24 @@
843 886
   // at which point movement will be level to the machine's XY plane.
844 887
   // The height can be set with M420 Z<height>
845 888
   #define ENABLE_LEVELING_FADE_HEIGHT
889
+
890
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
891
+  // split up moves into short segments like a Delta. This follows the
892
+  // contours of the bed more closely than edge-to-edge straight moves.
893
+  #define SEGMENT_LEVELED_MOVES
894
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
895
+
896
+  /**
897
+   * Enable the G26 Mesh Validation Pattern tool.
898
+   */
899
+  #define G26_MESH_VALIDATION   // Enable G26 mesh validation
900
+  #if ENABLED(G26_MESH_VALIDATION)
901
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
902
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
903
+    #define MESH_TEST_HOTEND_TEMP   190.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
904
+    #define MESH_TEST_BED_TEMP       65.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
905
+  #endif
906
+
846 907
 #endif
847 908
 
848 909
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -898,7 +959,9 @@
898 959
   //========================= Unified Bed Leveling ============================
899 960
   //===========================================================================
900 961
 
901
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
962
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
963
+
964
+  #define MESH_INSET 1              // Mesh inset margin on print area
902 965
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
903 966
   #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
904 967
 
@@ -909,8 +972,8 @@
909 972
   #define UBL_PROBE_PT_3_X 180
910 973
   #define UBL_PROBE_PT_3_Y 20
911 974
 
912
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
913 975
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
976
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
914 977
 
915 978
 #elif ENABLED(MESH_BED_LEVELING)
916 979
 
@@ -937,6 +1000,9 @@
937 1000
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
938 1001
 #endif
939 1002
 
1003
+// Add a menu item to move between bed corners for manual bed adjustment
1004
+#define LEVEL_BED_CORNERS
1005
+
940 1006
 /**
941 1007
  * Commands to execute at the end of G29 probing.
942 1008
  * Useful to retract or move the Z probe out of the way.
@@ -967,14 +1033,71 @@
967 1033
 #define Z_SAFE_HOMING
968 1034
 
969 1035
 #if ENABLED(Z_SAFE_HOMING)
970
-  #define Z_SAFE_HOMING_X_POINT (30)    // X point for Z homing when homing all axis (G28).
971
-  #define Z_SAFE_HOMING_Y_POINT (MANUAL_Y_HOME_POS)    // Y point for Z homing when homing all axis (G28).
1036
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1037
+  #define Z_SAFE_HOMING_Y_POINT (MANUAL_Y_HOME_POS)    // Y point for Z homing when homing all axes (G28).
972 1038
 #endif
973 1039
 
974 1040
 // Homing speeds (mm/m)
975 1041
 #define HOMING_FEEDRATE_XY (10*60)
976 1042
 #define HOMING_FEEDRATE_Z  (2*60)
977 1043
 
1044
+// @section calibrate
1045
+
1046
+/**
1047
+ * Bed Skew Compensation
1048
+ *
1049
+ * This feature corrects for misalignment in the XYZ axes.
1050
+ *
1051
+ * Take the following steps to get the bed skew in the XY plane:
1052
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1053
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1054
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1055
+ *  4. For XY_SIDE_AD measure the edge A to D
1056
+ *
1057
+ * Marlin automatically computes skew factors from these measurements.
1058
+ * Skew factors may also be computed and set manually:
1059
+ *
1060
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1061
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1062
+ *
1063
+ * If desired, follow the same procedure for XZ and YZ.
1064
+ * Use these diagrams for reference:
1065
+ *
1066
+ *    Y                     Z                     Z
1067
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1068
+ *    |    /       /        |    /       /        |    /       /
1069
+ *    |   /       /         |   /       /         |   /       /
1070
+ *    |  A-------D          |  A-------D          |  A-------D
1071
+ *    +-------------->X     +-------------->X     +-------------->Y
1072
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1073
+ */
1074
+//#define SKEW_CORRECTION
1075
+
1076
+#if ENABLED(SKEW_CORRECTION)
1077
+  // Input all length measurements here:
1078
+  #define XY_DIAG_AC 282.8427124746
1079
+  #define XY_DIAG_BD 282.8427124746
1080
+  #define XY_SIDE_AD 200
1081
+
1082
+  // Or, set the default skew factors directly here
1083
+  // to override the above measurements:
1084
+  #define XY_SKEW_FACTOR 0.0
1085
+
1086
+  //#define SKEW_CORRECTION_FOR_Z
1087
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1088
+    #define XZ_DIAG_AC 282.8427124746
1089
+    #define XZ_DIAG_BD 282.8427124746
1090
+    #define YZ_DIAG_AC 282.8427124746
1091
+    #define YZ_DIAG_BD 282.8427124746
1092
+    #define YZ_SIDE_AD 200
1093
+    #define XZ_SKEW_FACTOR 0.0
1094
+    #define YZ_SKEW_FACTOR 0.0
1095
+  #endif
1096
+
1097
+  // Enable this option for M852 to set skew at runtime
1098
+  //#define SKEW_CORRECTION_GCODE
1099
+#endif
1100
+
978 1101
 //=============================================================================
979 1102
 //============================= Additional Features ===========================
980 1103
 //=============================================================================
@@ -1001,11 +1124,12 @@
1001 1124
 //
1002 1125
 #define HOST_KEEPALIVE_FEATURE        // Disable this if your host doesn't like keepalive messages
1003 1126
 #define DEFAULT_KEEPALIVE_INTERVAL 2  // Number of seconds between "busy" messages. Set with M113.
1127
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
1004 1128
 
1005 1129
 //
1006 1130
 // M100 Free Memory Watcher
1007 1131
 //
1008
-//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1132
+//#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
1009 1133
 
1010 1134
 //
1011 1135
 // G20/G21 Inch mode support
@@ -1022,11 +1146,11 @@
1022 1146
 // Preheat Constants
1023 1147
 #define PREHEAT_1_TEMP_HOTEND 190
1024 1148
 #define PREHEAT_1_TEMP_BED 65
1025
-#define PREHEAT_1_FAN_SPEED 255   // Insert Value between 0 and 255
1149
+#define PREHEAT_1_FAN_SPEED 100   // Insert Value between 0 and 255
1026 1150
 
1027 1151
 #define PREHEAT_2_TEMP_HOTEND 200
1028 1152
 #define PREHEAT_2_TEMP_BED    80
1029
-#define PREHEAT_2_FAN_SPEED     255 // Value from 0 to 255
1153
+#define PREHEAT_2_FAN_SPEED     100 // Value from 0 to 255
1030 1154
 
1031 1155
 /**
1032 1156
  * Nozzle Park -- EXPERIMENTAL
@@ -1150,11 +1274,11 @@
1150 1274
  *
1151 1275
  * Select the language to display on the LCD. These languages are available:
1152 1276
  *
1153
- *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
1154
- *    it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
1155
- *    zh_CN, zh_TW, test
1277
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1278
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1279
+ *    tr, uk, zh_CN, zh_TW, test
1156 1280
  *
1157
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1281
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1158 1282
  */
1159 1283
 #define LCD_LANGUAGE en
1160 1284
 
@@ -1176,7 +1300,7 @@
1176 1300
  *  - Click the controller to view the LCD menu
1177 1301
  *  - The LCD will display Japanese, Western, or Cyrillic text
1178 1302
  *
1179
- * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1303
+ * See http://marlinfw.org/docs/development/lcd_language.html
1180 1304
  *
1181 1305
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1182 1306
  */
@@ -1303,12 +1427,6 @@
1303 1427
 //#define ULTIPANEL
1304 1428
 
1305 1429
 //
1306
-// Cartesio UI
1307
-// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
1308
-//
1309
-//#define CARTESIO_UI
1310
-
1311
-//
1312 1430
 // PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
1313 1431
 // http://reprap.org/wiki/PanelOne
1314 1432
 //
@@ -1391,11 +1509,19 @@
1391 1509
 //#define BQ_LCD_SMART_CONTROLLER
1392 1510
 
1393 1511
 //
1394
-// ANET_10 Controller supported displays.
1512
+// Cartesio UI
1513
+// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
1514
+//
1515
+//#define CARTESIO_UI
1516
+
1395 1517
 //
1396
-//#define ANET_KEYPAD_LCD         // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1518
+// ANET and Tronxy Controller supported displays.
1519
+//
1520
+//#define ZONESTAR_LCD            // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1397 1521
                                   // This LCD is known to be susceptible to electrical interference
1398 1522
                                   // which scrambles the display.  Pressing any button clears it up.
1523
+                                  // This is a LCD2004 display with 5 analog buttons.
1524
+
1399 1525
 //#define ANET_FULL_GRAPHICS_LCD  // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1400 1526
                                   // A clone of the RepRapDiscount full graphics display but with
1401 1527
                                   // different pins/wiring (see pins_ANET_10.h).
@@ -1476,6 +1602,40 @@
1476 1602
 //
1477 1603
 //#define OLED_PANEL_TINYBOY2
1478 1604
 
1605
+//
1606
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1607
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1608
+//
1609
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1610
+
1611
+//
1612
+// MKS MINI12864 with graphic controller and SD support
1613
+// http://reprap.org/wiki/MKS_MINI_12864
1614
+//
1615
+//#define MKS_MINI_12864
1616
+
1617
+//
1618
+// Factory display for Creality CR-10
1619
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1620
+//
1621
+// This is RAMPS-compatible using a single 10-pin connector.
1622
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1623
+//
1624
+//#define CR10_STOCKDISPLAY
1625
+
1626
+//
1627
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1628
+// http://reprap.org/wiki/MKS_12864OLED
1629
+//
1630
+// Tiny, but very sharp OLED display
1631
+//
1632
+//#define MKS_12864OLED
1633
+
1634
+// Silvergate GLCD controller
1635
+// http://github.com/android444/Silvergate
1636
+//
1637
+//#define SILVER_GATE_GLCD_CONTROLLER
1638
+
1479 1639
 //=============================================================================
1480 1640
 //=============================== Extra Features ==============================
1481 1641
 //=============================================================================
@@ -1532,16 +1692,22 @@
1532 1692
  * Adds the M150 command to set the LED (or LED strip) color.
1533 1693
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1534 1694
  * luminance values can be set from 0 to 255.
1695
+ * For Neopixel LED an overall brightness parameter is also available.
1535 1696
  *
1536 1697
  * *** CAUTION ***
1537 1698
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1538 1699
  *  as the Arduino cannot handle the current the LEDs will require.
1539 1700
  *  Failure to follow this precaution can destroy your Arduino!
1701
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1702
+ *  more current than the Arduino 5V linear regulator can produce.
1540 1703
  * *** CAUTION ***
1541 1704
  *
1705
+ * LED Type. Enable only one of the following two options.
1706
+ *
1542 1707
  */
1543 1708
 //#define RGB_LED
1544 1709
 //#define RGBW_LED
1710
+
1545 1711
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1546 1712
   #define RGB_LED_R_PIN 34
1547 1713
   #define RGB_LED_G_PIN 43
@@ -1549,6 +1715,17 @@
1549 1715
   #define RGB_LED_W_PIN -1
1550 1716
 #endif
1551 1717
 
1718
+// Support for Adafruit Neopixel LED driver
1719
+//#define NEOPIXEL_LED
1720
+#if ENABLED(NEOPIXEL_LED)
1721
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1722
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1723
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1724
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1725
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1726
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1727
+#endif
1728
+
1552 1729
 /**
1553 1730
  * Printer Event LEDs
1554 1731
  *
@@ -1560,68 +1737,32 @@
1560 1737
  *  - Change to green once print has finished
1561 1738
  *  - Turn off after the print has finished and the user has pushed a button
1562 1739
  */
1563
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)
1740
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1564 1741
   #define PRINTER_EVENT_LEDS
1565 1742
 #endif
1566 1743
 
1567
-/*********************************************************************\
1568
-* R/C SERVO support
1569
-* Sponsored by TrinityLabs, Reworked by codexmas
1570
-**********************************************************************/
1744
+/**
1745
+ * R/C SERVO support
1746
+ * Sponsored by TrinityLabs, Reworked by codexmas
1747
+ */
1571 1748
 
1572
-// Number of servos
1573
-//
1574
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1575
-// set it manually if you have more servos than extruders and wish to manually control some
1576
-// leaving it undefined or defining as 0 will disable the servo subsystem
1577
-// If unsure, leave commented / disabled
1578
-//
1749
+/**
1750
+ * Number of servos
1751
+ *
1752
+ * For some servo-related options NUM_SERVOS will be set automatically.
1753
+ * Set this manually if there are extra servos needing manual control.
1754
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1755
+ */
1579 1756
 //#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
1580 1757
 
1581 1758
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1582 1759
 // 300ms is a good value but you can try less delay.
1583 1760
 // If the servo can't reach the requested position, increase it.
1584
-#define SERVO_DELAY 300
1761
+#define SERVO_DELAY { 300 }
1585 1762
 
1586 1763
 // Servo deactivation
1587 1764
 //
1588 1765
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1589 1766
 //#define DEACTIVATE_SERVOS_AFTER_MOVE
1590 1767
 
1591
-/**
1592
- * Filament Width Sensor
1593
- *
1594
- * Measures the filament width in real-time and adjusts
1595
- * flow rate to compensate for any irregularities.
1596
- *
1597
- * Also allows the measured filament diameter to set the
1598
- * extrusion rate, so the slicer only has to specify the
1599
- * volume.
1600
- *
1601
- * Only a single extruder is supported at this time.
1602
- *
1603
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1604
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1605
- * 301 RAMBO       : Analog input 3
1606
- *
1607
- * Note: May require analog pins to be defined for other boards.
1608
- */
1609
-//#define FILAMENT_WIDTH_SENSOR
1610
-
1611
-#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75  //Enter the diameter (in mm) of the filament generally used (3.0 mm or 1.75 mm) - this is then used in the slicer software.  Used for sensor reading validation
1612
-
1613
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1614
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1615
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1616
-
1617
-  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1618
-  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1619
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1620
-
1621
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1622
-
1623
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1624
-  //#define FILAMENT_LCD_DISPLAY
1625
-#endif
1626
-
1627 1768
 #endif // CONFIGURATION_H

+ 372
- 167
Marlin/Configuration_adv.h 파일 보기

@@ -32,7 +32,7 @@
32 32
  */
33 33
 #ifndef CONFIGURATION_ADV_H
34 34
 #define CONFIGURATION_ADV_H
35
-#define CONFIGURATION_ADV_H_VERSION 010100
35
+#define CONFIGURATION_ADV_H_VERSION 010107
36 36
 
37 37
 // @section temperature
38 38
 
@@ -48,31 +48,36 @@
48 48
 #endif
49 49
 
50 50
 /**
51
- * Thermal Protection protects your printer from damage and fire if a
52
- * thermistor falls out or temperature sensors fail in any way.
51
+ * Thermal Protection provides additional protection to your printer from damage
52
+ * and fire. Marlin always includes safe min and max temperature ranges which
53
+ * protect against a broken or disconnected thermistor wire.
53 54
  *
54
- * The issue: If a thermistor falls out or a temperature sensor fails,
55
- * Marlin can no longer sense the actual temperature. Since a disconnected
56
- * thermistor reads as a low temperature, the firmware will keep the heater on.
55
+ * The issue: If a thermistor falls out, it will report the much lower
56
+ * temperature of the air in the room, and the the firmware will keep
57
+ * the heater on.
57 58
  *
58 59
  * The solution: Once the temperature reaches the target, start observing.
59
- * If the temperature stays too far below the target (hysteresis) for too long (period),
60
- * the firmware will halt the machine as a safety precaution.
60
+ * If the temperature stays too far below the target (hysteresis) for too
61
+ * long (period), the firmware will halt the machine as a safety precaution.
61 62
  *
62
- * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63
+ * If you get false positives for "Thermal Runaway", increase
64
+ * THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63 65
  */
64 66
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
65 67
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
66 68
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
67 69
 
68 70
   /**
69
-   * Whenever an M104 or M109 increases the target temperature the firmware will wait for the
70
-   * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
71
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
72
-   * but only if the current temperature is far enough below the target for a reliable test.
71
+   * Whenever an M104, M109, or M303 increases the target temperature, the
72
+   * firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
73
+   * hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
74
+   * requires a hard reset. This test restarts with any M104/M109/M303, but only
75
+   * if the current temperature is far enough below the target for a reliable
76
+   * test.
73 77
    *
74
-   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
75
-   * WATCH_TEMP_INCREASE should not be below 2.
78
+   * If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
79
+   * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
80
+   * below 2.
76 81
    */
77 82
   #define WATCH_TEMP_PERIOD 20                // Seconds
78 83
   #define WATCH_TEMP_INCREASE 2               // Degrees Celsius
@@ -86,13 +91,7 @@
86 91
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
87 92
 
88 93
   /**
89
-   * Whenever an M140 or M190 increases the target temperature the firmware will wait for the
90
-   * WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
91
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
92
-   * but only if the current temperature is far enough below the target for a reliable test.
93
-   *
94
-   * If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
95
-   * WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
94
+   * As described above, except for the bed (M140/M190/M303).
96 95
    */
97 96
   #define WATCH_BED_TEMP_PERIOD 60                // Seconds
98 97
   #define WATCH_BED_TEMP_INCREASE 2               // Degrees Celsius
@@ -123,6 +122,9 @@
123 122
   #define AUTOTEMP_OLDWEIGHT 0.98
124 123
 #endif
125 124
 
125
+// Show extra position information in M114
126
+//#define M114_DETAIL
127
+
126 128
 // Show Temperature ADC value
127 129
 // Enable for M105 to include ADC values read from temperature sensors.
128 130
 //#define SHOW_TEMP_ADC_VALUES
@@ -221,6 +223,17 @@
221 223
 #define EXTRUDER_AUTO_FAN_SPEED   255  // == full speed
222 224
 
223 225
 /**
226
+ * Part-Cooling Fan Multiplexer
227
+ *
228
+ * This feature allows you to digitally multiplex the fan output.
229
+ * The multiplexer is automatically switched at tool-change.
230
+ * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans.
231
+ */
232
+#define FANMUX0_PIN -1
233
+#define FANMUX1_PIN -1
234
+#define FANMUX2_PIN -1
235
+
236
+/**
224 237
  * M355 Case Light on-off / brightness
225 238
  */
226 239
 //#define CASE_LIGHT_ENABLE
@@ -246,48 +259,49 @@
246 259
 
247 260
 //#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
248 261
 
249
-// Dual X Steppers
250
-// Uncomment this option to drive two X axis motors.
251
-// The next unused E driver will be assigned to the second X stepper.
262
+/**
263
+ * Dual Steppers / Dual Endstops
264
+ *
265
+ * This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
266
+ *
267
+ * For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
268
+ * spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
269
+ * set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
270
+ * that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
271
+ *
272
+ * Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
273
+ * this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
274
+ * in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
275
+ */
276
+
252 277
 //#define X_DUAL_STEPPER_DRIVERS
253 278
 #if ENABLED(X_DUAL_STEPPER_DRIVERS)
254
-  // Set true if the two X motors need to rotate in opposite directions
255
-  #define INVERT_X2_VS_X_DIR true
279
+  #define INVERT_X2_VS_X_DIR true   // Set 'true' if X motors should rotate in opposite directions
280
+  //#define X_DUAL_ENDSTOPS
281
+  #if ENABLED(X_DUAL_ENDSTOPS)
282
+    #define X2_USE_ENDSTOP _XMAX_
283
+    #define X_DUAL_ENDSTOPS_ADJUSTMENT  0
284
+  #endif
256 285
 #endif
257 286
 
258
-// Dual Y Steppers
259
-// Uncomment this option to drive two Y axis motors.
260
-// The next unused E driver will be assigned to the second Y stepper.
261 287
 //#define Y_DUAL_STEPPER_DRIVERS
262 288
 #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
263
-  // Set true if the two Y motors need to rotate in opposite directions
264
-  #define INVERT_Y2_VS_Y_DIR true
289
+  #define INVERT_Y2_VS_Y_DIR true   // Set 'true' if Y motors should rotate in opposite directions
290
+  //#define Y_DUAL_ENDSTOPS
291
+  #if ENABLED(Y_DUAL_ENDSTOPS)
292
+    #define Y2_USE_ENDSTOP _YMAX_
293
+    #define Y_DUAL_ENDSTOPS_ADJUSTMENT  0
294
+  #endif
265 295
 #endif
266 296
 
267
-// A single Z stepper driver is usually used to drive 2 stepper motors.
268
-// Uncomment this option to use a separate stepper driver for each Z axis motor.
269
-// The next unused E driver will be assigned to the second Z stepper.
270 297
 //#define Z_DUAL_STEPPER_DRIVERS
271
-
272 298
 #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
273
-
274
-  // Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper.
275
-  // That way the machine is capable to align the bed during home, since both Z steppers are homed.
276
-  // There is also an implementation of M666 (software endstops adjustment) to this feature.
277
-  // After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
278
-  // One just need to home the Z axis and measure the distance difference between both Z axis and apply the math: Z adjust = Z - Z2.
279
-  // If the Z stepper axis is closer to the bed, the measure Z > Z2 (yes, it is.. think about it) and the Z adjust would be positive.
280
-  // Play a little bit with small adjustments (0.5mm) and check the behaviour.
281
-  // The M119 (endstops report) will start reporting the Z2 Endstop as well.
282
-
283 299
   //#define Z_DUAL_ENDSTOPS
284
-
285 300
   #if ENABLED(Z_DUAL_ENDSTOPS)
286 301
     #define Z2_USE_ENDSTOP _XMAX_
287
-    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0  // use M666 command to determine/test this value
302
+    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0
288 303
   #endif
289
-
290
-#endif // Z_DUAL_STEPPER_DRIVERS
304
+#endif
291 305
 
292 306
 // Enable this for dual x-carriage printers.
293 307
 // A dual x-carriage design has the advantage that the inactive extruder can be parked which
@@ -334,12 +348,12 @@
334 348
 
335 349
 // @section homing
336 350
 
337
-//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
351
+// Homing hits each endstop, retracts by these distances, then does a slower bump.
338 352
 #define X_HOME_BUMP_MM 5
339 353
 #define Y_HOME_BUMP_MM 5
340 354
 #define Z_HOME_BUMP_MM 2
341
-#define HOMING_BUMP_DIVISOR {2, 2, 4}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
342
-#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
355
+#define HOMING_BUMP_DIVISOR { 2, 2, 4 }  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
356
+#define QUICK_HOME                     // If homing includes X and Y, do a diagonal move initially
343 357
 
344 358
 // When G28 is called, this option will make Y home before X
345 359
 #define HOME_Y_BEFORE_X
@@ -369,12 +383,12 @@
369 383
 #define DEFAULT_MINIMUMFEEDRATE       0.0     // minimum feedrate
370 384
 #define DEFAULT_MINTRAVELFEEDRATE     0.0
371 385
 
372
-//#define HOME_AFTER_DEACTIVATE  // Require rehoming after steppers are deactivated
386
+#define HOME_AFTER_DEACTIVATE  // Require rehoming after steppers are deactivated
373 387
 
374 388
 // @section lcd
375 389
 
376 390
 #if ENABLED(ULTIPANEL)
377
-  #define MANUAL_FEEDRATE {10*60, 10*60, 2*60, 60} // Feedrates for manual moves along X, Y, Z, E from panel
391
+  #define MANUAL_FEEDRATE {10*60, 10*60, 2*60, 5*60} // Feedrates for manual moves along X, Y, Z, E from panel
378 392
   #define ULTIPANEL_FEEDMULTIPLY  // Comment to disable setting feedrate multiplier via encoder
379 393
 #endif
380 394
 
@@ -394,7 +408,7 @@
394 408
 // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
395 409
 // of the buffer and all stops. This should not be much greater than zero and should only be changed
396 410
 // if unwanted behavior is observed on a user's machine when running at very slow speeds.
397
-#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
411
+#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
398 412
 
399 413
 // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
400 414
 #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
@@ -423,8 +437,21 @@
423 437
 //#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 }   // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
424 438
 //#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 }    // Default drive percent - X, Y, Z, E axis
425 439
 
426
-// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
440
+// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
427 441
 //#define DIGIPOT_I2C
442
+#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
443
+  /**
444
+   * Common slave addresses:
445
+   *
446
+   *                    A   (A shifted)   B   (B shifted)  IC
447
+   * Smoothie          0x2C (0x58)       0x2D (0x5A)       MCP4451
448
+   * AZTEEG_X3_PRO     0x2C (0x58)       0x2E (0x5C)       MCP4451
449
+   * MIGHTYBOARD_REVE  0x2F (0x5E)                         MCP4018
450
+   */
451
+  #define DIGIPOT_I2C_ADDRESS_A 0x2C  // unshifted slave address for first DIGIPOT
452
+  #define DIGIPOT_I2C_ADDRESS_B 0x2D  // unshifted slave address for second DIGIPOT
453
+#endif
454
+
428 455
 //#define DIGIPOT_MCP4018          // Requires library from https://github.com/stawel/SlowSoftI2CMaster
429 456
 #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4     AZTEEG_X3_PRO: 8
430 457
 // Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
@@ -444,16 +471,33 @@
444 471
 // @section lcd
445 472
 
446 473
 // Include a page of printer information in the LCD Main Menu
447
-//#define LCD_INFO_MENU
474
+#define LCD_INFO_MENU
448 475
 
449 476
 // Scroll a longer status message into view
450
-//#define STATUS_MESSAGE_SCROLLING
477
+#define STATUS_MESSAGE_SCROLLING
451 478
 
452 479
 // On the Info Screen, display XY with one decimal place when possible
453 480
 //#define LCD_DECIMAL_SMALL_XY
454 481
 
455 482
 // The timeout (in ms) to return to the status screen from sub-menus
456
-//#define LCD_TIMEOUT_TO_STATUS 15000
483
+#define LCD_TIMEOUT_TO_STATUS 30000
484
+
485
+/**
486
+ * LED Control Menu
487
+ * Enable this feature to add LED Control to the LCD menu
488
+ */
489
+//#define LED_CONTROL_MENU
490
+#if ENABLED(LED_CONTROL_MENU)
491
+  #define LED_COLOR_PRESETS                 // Enable the Preset Color menu option
492
+  #if ENABLED(LED_COLOR_PRESETS)
493
+    #define LED_USER_PRESET_RED        255  // User defined RED value
494
+    #define LED_USER_PRESET_GREEN      128  // User defined GREEN value
495
+    #define LED_USER_PRESET_BLUE         0  // User defined BLUE value
496
+    #define LED_USER_PRESET_WHITE      255  // User defined WHITE value
497
+    #define LED_USER_PRESET_BRIGHTNESS 255  // User defined intensity
498
+    //#define LED_USER_PRESET_STARTUP       // Have the printer display the user preset color on startup
499
+  #endif
500
+#endif // LED_CONTROL_MENU
457 501
 
458 502
 #if ENABLED(SDSUPPORT)
459 503
 
@@ -464,12 +508,14 @@
464 508
   // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
465 509
   #define SD_DETECT_INVERTED
466 510
 
467
-  #define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
511
+  #define SD_FINISHED_STEPPERRELEASE true          // Disable steppers when SD Print is finished
468 512
   #define SD_FINISHED_RELEASECOMMAND "M84 Y Z E" // You might want to keep the z enabled so your bed stays in place.
469 513
 
470
-  #define SDCARD_RATHERRECENTFIRST  //reverse file order of sd card menu display. Its sorted practically after the file system block order.
471
-  // if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that.
472
-  // using:
514
+  // Reverse SD sort to show "more recent" files first, according to the card's FAT.
515
+  // Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
516
+  #define SDCARD_RATHERRECENTFIRST
517
+
518
+  // Add an option in the menu to run all auto#.g files
473 519
   //#define MENU_ADDAUTOSTART
474 520
 
475 521
   /**
@@ -499,13 +545,15 @@
499 545
 
500 546
   // SD Card Sorting options
501 547
   #if ENABLED(SDCARD_SORT_ALPHA)
502
-    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256).
548
+    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256). Costs 27 bytes each.
503 549
     #define FOLDER_SORTING     -1     // -1=above  0=none  1=below
504 550
     #define SDSORT_GCODE       false  // Allow turning sorting on/off with LCD and M34 g-code.
505 551
     #define SDSORT_USES_RAM    false  // Pre-allocate a static array for faster pre-sorting.
506 552
     #define SDSORT_USES_STACK  false  // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
507 553
     #define SDSORT_CACHE_NAMES false  // Keep sorted items in RAM longer for speedy performance. Most expensive option.
508 554
     #define SDSORT_DYNAMIC_RAM false  // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
555
+    #define SDSORT_CACHE_VFATS 2      // Maximum number of 13-byte VFAT entries to use for sorting.
556
+                                      // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
509 557
   #endif
510 558
 
511 559
   // Show a progress bar on HD44780 LCDs for SD printing
@@ -524,14 +572,29 @@
524 572
     //#define LCD_PROGRESS_BAR_TEST
525 573
   #endif
526 574
 
575
+  // Add an 'M73' G-code to set the current percentage
576
+  //#define LCD_SET_PROGRESS_MANUALLY
577
+
527 578
   // This allows hosts to request long names for files and folders with M33
528
-  //#define LONG_FILENAME_HOST_SUPPORT
579
+  #define LONG_FILENAME_HOST_SUPPORT
580
+
581
+  // Enable this option to scroll long filenames in the SD card menu
582
+  #define SCROLL_LONG_FILENAMES
529 583
 
530
-  // This option allows you to abort SD printing when any endstop is triggered.
531
-  // This feature must be enabled with "M540 S1" or from the LCD menu.
532
-  // To have any effect, endstops must be enabled during SD printing.
584
+  /**
585
+   * This option allows you to abort SD printing when any endstop is triggered.
586
+   * This feature must be enabled with "M540 S1" or from the LCD menu.
587
+   * To have any effect, endstops must be enabled during SD printing.
588
+   */
533 589
   //#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
534 590
 
591
+  /**
592
+   * This option makes it easier to print the same SD Card file again.
593
+   * On print completion the LCD Menu will open with the file selected.
594
+   * You can just click to start the print, or navigate elsewhere.
595
+   */
596
+  #define SD_REPRINT_LAST_SELECTED_FILE
597
+
535 598
 #endif // SDSUPPORT
536 599
 
537 600
 /**
@@ -564,6 +627,10 @@
564 627
   // Enable this option and reduce the value to optimize screen updates.
565 628
   // The normal delay is 10µs. Use the lowest value that still gives a reliable display.
566 629
   //#define DOGM_SPI_DELAY_US 5
630
+
631
+  // Swap the CW/CCW indicators in the graphics overlay
632
+  //#define OVERLAY_GFX_REVERSE
633
+
567 634
 #endif // DOGLCD
568 635
 
569 636
 // @section safety
@@ -590,31 +657,18 @@
590 657
  */
591 658
 //#define BABYSTEPPING
592 659
 #if ENABLED(BABYSTEPPING)
593
-  #define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
594
-  #define BABYSTEP_INVERT_Z false  // Change if Z babysteps should go the other way
595
-  #define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
596
-  //#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
660
+  //#define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
661
+  #define BABYSTEP_INVERT_Z false    // Change if Z babysteps should go the other way
662
+  #define BABYSTEP_MULTIPLICATOR 1   // Babysteps are very small. Increase for faster motion.
663
+  //#define BABYSTEP_ZPROBE_OFFSET   // Enable to combine M851 and Babystepping
597 664
   //#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
598 665
   #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
599 666
                                         // Note: Extra time may be added to mitigate controller latency.
667
+  //#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
600 668
 #endif
601 669
 
602 670
 // @section extruder
603 671
 
604
-// extruder advance constant (s2/mm3)
605
-//
606
-// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
607
-//
608
-// Hooke's law says:    force = k * distance
609
-// Bernoulli's principle says:  v ^ 2 / 2 + g . h + pressure / density = constant
610
-// so: v ^ 2 is proportional to number of steps we advance the extruder
611
-//#define ADVANCE
612
-
613
-#if ENABLED(ADVANCE)
614
-  #define EXTRUDER_ADVANCE_K .0
615
-  #define D_FILAMENT 2.85
616
-#endif
617
-
618 672
 /**
619 673
  * Implementation of linear pressure control
620 674
  *
@@ -648,7 +702,7 @@
648 702
    *
649 703
    * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
650 704
    *
651
-   * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode.
705
+   * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
652 706
    * Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
653 707
    */
654 708
   #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
@@ -657,23 +711,18 @@
657 711
 
658 712
 // @section leveling
659 713
 
660
-// Default mesh area is an area with an inset margin on the print area.
661
-// Below are the macros that are used to define the borders for the mesh area,
662
-// made available here for specialized needs, ie dual extruder setup.
663
-#if ENABLED(MESH_BED_LEVELING)
664
-  #define MESH_MIN_X (X_MIN_POS + MESH_INSET)
665
-  #define MESH_MAX_X (X_MAX_POS - (MESH_INSET))
666
-  #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET)
667
-  #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET))
668
-#elif ENABLED(AUTO_BED_LEVELING_UBL)
669
-  #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET)
670
-  #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET))
671
-  #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET)
672
-  #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET))
673
-
674
-  // If this is defined, the currently active mesh will be saved in the
675
-  // current slot on M500.
676
-  #define UBL_SAVE_ACTIVE_ON_M500
714
+#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
715
+  #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
716
+#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
717
+  #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
718
+#endif
719
+
720
+#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
721
+  // Override the mesh area if the automatic (max) area is too large
722
+  //#define MESH_MIN_X MESH_INSET
723
+  //#define MESH_MIN_Y MESH_INSET
724
+  //#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
725
+  //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
677 726
 #endif
678 727
 
679 728
 // @section extras
@@ -693,7 +742,7 @@
693 742
 //#define BEZIER_CURVE_SUPPORT
694 743
 
695 744
 // G38.2 and G38.3 Probe Target
696
-// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
745
+// Set MULTIPLE_PROBING if you want G38 to double touch
697 746
 //#define G38_PROBE_TARGET
698 747
 #if ENABLED(G38_PROBE_TARGET)
699 748
   #define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
@@ -718,7 +767,7 @@
718 767
 // @section hidden
719 768
 
720 769
 // The number of linear motions that can be in the plan at any give time.
721
-// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
770
+// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
722 771
 #if ENABLED(SDSUPPORT)
723 772
   #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
724 773
 #else
@@ -731,7 +780,7 @@
731 780
 #define MAX_CMD_SIZE 96
732 781
 #define BUFSIZE 4
733 782
 
734
-// Transfer Buffer Size
783
+// Transmission to Host Buffer Size
735 784
 // To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0.
736 785
 // To buffer a simple "ok" you need 4 bytes.
737 786
 // For ADVANCED_OK (M105) you need 32 bytes.
@@ -740,6 +789,28 @@
740 789
 // :[0, 2, 4, 8, 16, 32, 64, 128, 256]
741 790
 #define TX_BUFFER_SIZE 0
742 791
 
792
+// Host Receive Buffer Size
793
+// Without XON/XOFF flow control (see SERIAL_XON_XOFF below) 32 bytes should be enough.
794
+// To use flow control, set this buffer size to at least 1024 bytes.
795
+// :[0, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048]
796
+//#define RX_BUFFER_SIZE 1024
797
+
798
+#if RX_BUFFER_SIZE >= 1024
799
+  // Enable to have the controller send XON/XOFF control characters to
800
+  // the host to signal the RX buffer is becoming full.
801
+  //#define SERIAL_XON_XOFF
802
+#endif
803
+
804
+#if ENABLED(SDSUPPORT)
805
+  // Enable this option to collect and display the maximum
806
+  // RX queue usage after transferring a file to SD.
807
+  //#define SERIAL_STATS_MAX_RX_QUEUED
808
+
809
+  // Enable this option to collect and display the number
810
+  // of dropped bytes after a file transfer to SD.
811
+  //#define SERIAL_STATS_DROPPED_RX
812
+#endif
813
+
743 814
 // Enable an emergency-command parser to intercept certain commands as they
744 815
 // enter the serial receive buffer, so they cannot be blocked.
745 816
 // Currently handles M108, M112, M410
@@ -755,27 +826,47 @@
755 826
 // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary.
756 827
 //#define ADVANCED_OK
757 828
 
758
-// @section fwretract
759
-
760
-// Firmware based and LCD controlled retract
761
-// M207 and M208 can be used to define parameters for the retraction.
762
-// The retraction can be called by the slicer using G10 and G11
763
-// until then, intended retractions can be detected by moves that only extrude and the direction.
764
-// the moves are than replaced by the firmware controlled ones.
829
+// @section extras
765 830
 
766
-//#define FWRETRACT  //ONLY PARTIALLY TESTED
831
+/**
832
+ * Firmware-based and LCD-controlled retract
833
+ *
834
+ * Add G10 / G11 commands for automatic firmware-based retract / recover.
835
+ * Use M207 and M208 to define parameters for retract / recover.
836
+ *
837
+ * Use M209 to enable or disable auto-retract.
838
+ * With auto-retract enabled, all G1 E moves within the set range
839
+ * will be converted to firmware-based retract/recover moves.
840
+ *
841
+ * Be sure to turn off auto-retract during filament change.
842
+ *
843
+ * Note that M207 / M208 / M209 settings are saved to EEPROM.
844
+ *
845
+ */
846
+//#define FWRETRACT  // ONLY PARTIALLY TESTED
767 847
 #if ENABLED(FWRETRACT)
768
-  #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
769
-  #define RETRACT_LENGTH 3               //default retract length (positive mm)
770
-  #define RETRACT_LENGTH_SWAP 13         //default swap retract length (positive mm), for extruder change
771
-  #define RETRACT_FEEDRATE 45            //default feedrate for retracting (mm/s)
772
-  #define RETRACT_ZLIFT 0                //default retract Z-lift
773
-  #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
774
-  #define RETRACT_RECOVER_LENGTH_SWAP 0  //default additional swap recover length (mm, added to retract length when recovering from extruder change)
775
-  #define RETRACT_RECOVER_FEEDRATE 8     //default feedrate for recovering from retraction (mm/s)
848
+  #define MIN_AUTORETRACT 0.1             // When auto-retract is on, convert E moves of this length and over
849
+  #define MAX_AUTORETRACT 10.0            // Upper limit for auto-retract conversion
850
+  #define RETRACT_LENGTH 3                // Default retract length (positive mm)
851
+  #define RETRACT_LENGTH_SWAP 13          // Default swap retract length (positive mm), for extruder change
852
+  #define RETRACT_FEEDRATE 45             // Default feedrate for retracting (mm/s)
853
+  #define RETRACT_ZLIFT 0                 // Default retract Z-lift
854
+  #define RETRACT_RECOVER_LENGTH 0        // Default additional recover length (mm, added to retract length when recovering)
855
+  #define RETRACT_RECOVER_LENGTH_SWAP 0   // Default additional swap recover length (mm, added to retract length when recovering from extruder change)
856
+  #define RETRACT_RECOVER_FEEDRATE 8      // Default feedrate for recovering from retraction (mm/s)
857
+  #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
776 858
 #endif
777 859
 
778 860
 /**
861
+ * Extra Fan Speed
862
+ * Adds a secondary fan speed for each print-cooling fan.
863
+ *   'M106 P<fan> T3-255' : Set a secondary speed for <fan>
864
+ *   'M106 P<fan> T2'     : Use the set secondary speed
865
+ *   'M106 P<fan> T1'     : Restore the previous fan speed
866
+ */
867
+//#define EXTRA_FAN_SPEED
868
+
869
+/**
779 870
  * Advanced Pause
780 871
  * Experimental feature for filament change support and for parking the nozzle when paused.
781 872
  * Adds the GCode M600 for initiating filament change.
@@ -885,7 +976,7 @@
885 976
 
886 977
 #endif
887 978
 
888
-// @section TMC2130
979
+// @section TMC2130, TMC2208
889 980
 
890 981
 /**
891 982
  * Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
@@ -899,7 +990,19 @@
899 990
  */
900 991
 //#define HAVE_TMC2130
901 992
 
902
-#if ENABLED(HAVE_TMC2130)
993
+/**
994
+ * Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
995
+ * Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
996
+ * To use the reading capabilities, also connect #_SERIAL_RX_PIN
997
+ * to #_SERIAL_TX_PIN with a 1K resistor.
998
+ * The drivers can also be used with hardware serial.
999
+ *
1000
+ * You'll also need the TMC2208Stepper Arduino library
1001
+ * (https://github.com/teemuatlut/TMC2208Stepper).
1002
+ */
1003
+//#define HAVE_TMC2208
1004
+
1005
+#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
903 1006
 
904 1007
   // CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
905 1008
   //#define X_IS_TMC2130
@@ -914,46 +1017,58 @@
914 1017
   //#define E3_IS_TMC2130
915 1018
   //#define E4_IS_TMC2130
916 1019
 
1020
+  //#define X_IS_TMC2208
1021
+  //#define X2_IS_TMC2208
1022
+  //#define Y_IS_TMC2208
1023
+  //#define Y2_IS_TMC2208
1024
+  //#define Z_IS_TMC2208
1025
+  //#define Z2_IS_TMC2208
1026
+  //#define E0_IS_TMC2208
1027
+  //#define E1_IS_TMC2208
1028
+  //#define E2_IS_TMC2208
1029
+  //#define E3_IS_TMC2208
1030
+  //#define E4_IS_TMC2208
1031
+
917 1032
   /**
918 1033
    * Stepper driver settings
919 1034
    */
920 1035
 
921 1036
   #define R_SENSE           0.11  // R_sense resistor for SilentStepStick2130
922 1037
   #define HOLD_MULTIPLIER    0.5  // Scales down the holding current from run current
923
-  #define INTERPOLATE          1  // Interpolate X/Y/Z_MICROSTEPS to 256
1038
+  #define INTERPOLATE       true  // Interpolate X/Y/Z_MICROSTEPS to 256
924 1039
 
925
-  #define X_CURRENT         1000  // rms current in mA. Multiply by 1.41 for peak current.
1040
+  #define X_CURRENT          800  // rms current in mA. Multiply by 1.41 for peak current.
926 1041
   #define X_MICROSTEPS        16  // 0..256
927 1042
 
928
-  #define Y_CURRENT         1000
1043
+  #define Y_CURRENT          800
929 1044
   #define Y_MICROSTEPS        16
930 1045
 
931
-  #define Z_CURRENT         1000
1046
+  #define Z_CURRENT          800
932 1047
   #define Z_MICROSTEPS        16
933 1048
 
934
-  //#define X2_CURRENT      1000
935
-  //#define X2_MICROSTEPS     16
1049
+  #define X2_CURRENT         800
1050
+  #define X2_MICROSTEPS       16
936 1051
 
937
-  //#define Y2_CURRENT      1000
938
-  //#define Y2_MICROSTEPS     16
1052
+  #define Y2_CURRENT         800
1053
+  #define Y2_MICROSTEPS       16
939 1054
 
940
-  //#define Z2_CURRENT      1000
941
-  //#define Z2_MICROSTEPS     16
1055
+  #define Z2_CURRENT         800
1056
+  #define Z2_MICROSTEPS       16
942 1057
 
943
-  //#define E0_CURRENT      1000
944
-  //#define E0_MICROSTEPS     16
1058
+  #define E0_CURRENT         800
1059
+  #define E0_MICROSTEPS       16
945 1060
 
946
-  //#define E1_CURRENT      1000
947
-  //#define E1_MICROSTEPS     16
1061
+  #define E1_CURRENT         800
1062
+  #define E1_MICROSTEPS       16
948 1063
 
949
-  //#define E2_CURRENT      1000
950
-  //#define E2_MICROSTEPS     16
1064
+  #define E2_CURRENT         800
1065
+  #define E2_MICROSTEPS       16
951 1066
 
952
-  //#define E3_CURRENT      1000
953
-  //#define E3_MICROSTEPS     16
1067
+  #define E3_CURRENT         800
1068
+  #define E3_MICROSTEPS       16
954 1069
 
955
-  //#define E4_CURRENT      1000
956
-  //#define E4_MICROSTEPS     16
1070
+  #define E4_CURRENT         800
1071
+  #define E4_MICROSTEPS       16
957 1072
 
958 1073
   /**
959 1074
    * Use Trinamic's ultra quiet stepping mode.
@@ -962,24 +1077,22 @@
962 1077
   #define STEALTHCHOP
963 1078
 
964 1079
   /**
965
-   * Let Marlin automatically control stepper current.
966
-   * This is still an experimental feature.
967
-   * Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
968
-   * then decrease current by CURRENT_STEP until temperature prewarn is cleared.
969
-   * Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
1080
+   * Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
1081
+   * like overtemperature and short to ground. TMC2208 requires hardware serial.
1082
+   * In the case of overtemperature Marlin can decrease the driver current until error condition clears.
1083
+   * Other detected conditions can be used to stop the current print.
970 1084
    * Relevant g-codes:
971 1085
    * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
972
-   * M906 S1 - Start adjusting current
973
-   * M906 S0 - Stop adjusting current
974 1086
    * M911 - Report stepper driver overtemperature pre-warn condition.
975 1087
    * M912 - Clear stepper driver overtemperature pre-warn condition flag.
1088
+   * M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
976 1089
    */
977
-  //#define AUTOMATIC_CURRENT_CONTROL
1090
+  //#define MONITOR_DRIVER_STATUS
978 1091
 
979
-  #if ENABLED(AUTOMATIC_CURRENT_CONTROL)
980
-    #define CURRENT_STEP          50  // [mA]
981
-    #define AUTO_ADJUST_MAX     1300  // [mA], 1300mA_rms = 1840mA_peak
1092
+  #if ENABLED(MONITOR_DRIVER_STATUS)
1093
+    #define CURRENT_STEP_DOWN     50  // [mA]
982 1094
     #define REPORT_CURRENT_CHANGE
1095
+    #define STOP_ON_ERROR
983 1096
   #endif
984 1097
 
985 1098
   /**
@@ -994,8 +1107,8 @@
994 1107
   #define X2_HYBRID_THRESHOLD    100
995 1108
   #define Y_HYBRID_THRESHOLD     100
996 1109
   #define Y2_HYBRID_THRESHOLD    100
997
-  #define Z_HYBRID_THRESHOLD       4
998
-  #define Z2_HYBRID_THRESHOLD      4
1110
+  #define Z_HYBRID_THRESHOLD       3
1111
+  #define Z2_HYBRID_THRESHOLD      3
999 1112
   #define E0_HYBRID_THRESHOLD     30
1000 1113
   #define E1_HYBRID_THRESHOLD     30
1001 1114
   #define E2_HYBRID_THRESHOLD     30
@@ -1005,7 +1118,7 @@
1005 1118
   /**
1006 1119
    * Use stallGuard2 to sense an obstacle and trigger an endstop.
1007 1120
    * You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
1008
-   * If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
1121
+   * X and Y homing will always be done in spreadCycle mode.
1009 1122
    *
1010 1123
    * X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
1011 1124
    * Higher values make the system LESS sensitive.
@@ -1014,27 +1127,34 @@
1014 1127
    * It is advised to set X/Y_HOME_BUMP_MM to 0.
1015 1128
    * M914 X/Y to live tune the setting
1016 1129
    */
1017
-  //#define SENSORLESS_HOMING
1130
+  //#define SENSORLESS_HOMING // TMC2130 only
1018 1131
 
1019 1132
   #if ENABLED(SENSORLESS_HOMING)
1020
-    #define X_HOMING_SENSITIVITY  19
1021
-    #define Y_HOMING_SENSITIVITY  19
1133
+    #define X_HOMING_SENSITIVITY  8
1134
+    #define Y_HOMING_SENSITIVITY  8
1022 1135
   #endif
1023 1136
 
1024 1137
   /**
1138
+   * Enable M122 debugging command for TMC stepper drivers.
1139
+   * M122 S0/1 will enable continous reporting.
1140
+   */
1141
+  //#define TMC_DEBUG
1142
+
1143
+  /**
1025 1144
    * You can set your own advanced settings by filling in predefined functions.
1026 1145
    * A list of available functions can be found on the library github page
1027 1146
    * https://github.com/teemuatlut/TMC2130Stepper
1147
+   * https://github.com/teemuatlut/TMC2208Stepper
1028 1148
    *
1029 1149
    * Example:
1030
-   * #define TMC2130_ADV() { \
1150
+   * #define TMC_ADV() { \
1031 1151
    *   stepperX.diag0_temp_prewarn(1); \
1032
-   *   stepperX.interpolate(0); \
1152
+   *   stepperY.interpolate(0); \
1033 1153
    * }
1034 1154
    */
1035
-  #define  TMC2130_ADV() {  }
1155
+  #define  TMC_ADV() {  }
1036 1156
 
1037
-#endif // HAVE_TMC2130
1157
+#endif // TMC2130 || TMC2208
1038 1158
 
1039 1159
 // @section L6470
1040 1160
 
@@ -1199,6 +1319,48 @@
1199 1319
 #endif
1200 1320
 
1201 1321
 /**
1322
+ * Filament Width Sensor
1323
+ *
1324
+ * Measures the filament width in real-time and adjusts
1325
+ * flow rate to compensate for any irregularities.
1326
+ *
1327
+ * Also allows the measured filament diameter to set the
1328
+ * extrusion rate, so the slicer only has to specify the
1329
+ * volume.
1330
+ *
1331
+ * Only a single extruder is supported at this time.
1332
+ *
1333
+ *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1334
+ *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1335
+ * 301 RAMBO       : Analog input 3
1336
+ *
1337
+ * Note: May require analog pins to be defined for other boards.
1338
+ */
1339
+//#define FILAMENT_WIDTH_SENSOR
1340
+
1341
+#if ENABLED(FILAMENT_WIDTH_SENSOR)
1342
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
1343
+  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1344
+
1345
+  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1346
+  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1347
+  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1348
+
1349
+  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1350
+
1351
+  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1352
+  //#define FILAMENT_LCD_DISPLAY
1353
+#endif
1354
+
1355
+/**
1356
+ * CNC Coordinate Systems
1357
+ *
1358
+ * Enables G53 and G54-G59.3 commands to select coordinate systems
1359
+ * and G92.1 to reset the workspace to native machine space.
1360
+ */
1361
+//#define CNC_COORDINATE_SYSTEMS
1362
+
1363
+/**
1202 1364
  * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
1203 1365
  */
1204 1366
 //#define PINS_DEBUGGING
@@ -1251,6 +1413,8 @@
1251 1413
 //#define CUSTOM_USER_MENUS
1252 1414
 #if ENABLED(CUSTOM_USER_MENUS)
1253 1415
   #define USER_SCRIPT_DONE "M117 User Script Done"
1416
+  #define USER_SCRIPT_AUDIBLE_FEEDBACK
1417
+  //#define USER_SCRIPT_RETURN  // Return to status screen after a script
1254 1418
 
1255 1419
   #define USER_DESC_1 "Home & UBL Info"
1256 1420
   #define USER_GCODE_1 "G28\nG29 W"
@@ -1359,4 +1523,45 @@
1359 1523
 
1360 1524
 #endif // I2C_POSITION_ENCODERS
1361 1525
 
1526
+/**
1527
+ * MAX7219 Debug Matrix
1528
+ *
1529
+ * Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
1530
+ * display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
1531
+ *
1532
+ * Fully assembled MAX7219 boards can be found on the internet for under $2(US).
1533
+ * For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
1534
+ */
1535
+//#define MAX7219_DEBUG
1536
+#if ENABLED(MAX7219_DEBUG)
1537
+  #define MAX7219_CLK_PIN   64  // 77 on Re-ARM       // Configuration of the 3 pins to control the display
1538
+  #define MAX7219_DIN_PIN   57  // 78 on Re-ARM
1539
+  #define MAX7219_LOAD_PIN  44  // 79 on Re-ARM
1540
+
1541
+  /**
1542
+   * Sample debug features
1543
+   * If you add more debug displays, be careful to avoid conflicts!
1544
+   */
1545
+  #define MAX7219_DEBUG_PRINTER_ALIVE    // Blink corner LED of 8x8 matrix to show that the firmware is functioning
1546
+  #define MAX7219_DEBUG_STEPPER_HEAD  3  // Show the stepper queue head position on this and the next LED matrix row
1547
+  #define MAX7219_DEBUG_STEPPER_TAIL  5  // Show the stepper queue tail position on this and the next LED matrix row
1548
+
1549
+  #define MAX7219_DEBUG_STEPPER_QUEUE 0  // Show the current stepper queue depth on this and the next LED matrix row
1550
+                                         // If you experience stuttering, reboots, etc. this option can reveal how
1551
+                                         // tweaks made to the configuration are affecting the printer in real-time.
1552
+#endif
1553
+
1554
+/**
1555
+ * NanoDLP Sync support
1556
+ *
1557
+ * Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
1558
+ * string to enable synchronization with DLP projector exposure. This change will allow to use
1559
+ * [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
1560
+ */
1561
+//#define NANODLP_Z_SYNC
1562
+#if ENABLED(NANODLP_Z_SYNC)
1563
+  //#define NANODLP_ALL_AXIS  // Enables "Z_move_comp" output on any axis move.
1564
+                              // Default behaviour is limited to Z axis only.
1565
+#endif
1566
+
1362 1567
 #endif // CONFIGURATION_ADV_H

+ 465
- 500
Marlin/G26_Mesh_Validation_Tool.cpp
파일 크기가 너무 크기때문에 변경 상태를 표시하지 않습니다.
파일 보기


+ 2
- 15
Marlin/I2CPositionEncoder.h 파일 보기

@@ -127,10 +127,7 @@
127 127
               invert              = false,
128 128
               ec                  = true;
129 129
 
130
-    float     axisOffset          = 0;
131
-
132
-    int32_t   axisOffsetTicks     = 0,
133
-              zeroOffset          = 0,
130
+    int32_t   zeroOffset          = 0,
134 131
               lastPosition        = 0,
135 132
               position;
136 133
 
@@ -168,7 +165,7 @@
168 165
     }
169 166
 
170 167
     FORCE_INLINE float get_position_mm() { return mm_from_count(get_position()); }
171
-    FORCE_INLINE int32_t get_position() { return get_raw_count() - zeroOffset - axisOffsetTicks; }
168
+    FORCE_INLINE int32_t get_position() { return get_raw_count() - zeroOffset; }
172 169
 
173 170
     int32_t get_axis_error_steps(const bool report);
174 171
     float get_axis_error_mm(const bool report);
@@ -219,16 +216,6 @@
219 216
 
220 217
     FORCE_INLINE int get_stepper_ticks() { return stepperTicks; }
221 218
     FORCE_INLINE void set_stepper_ticks(const int ticks) { stepperTicks = ticks; }
222
-
223
-    FORCE_INLINE float get_axis_offset() { return axisOffset; }
224
-    FORCE_INLINE void set_axis_offset(const float newOffset) {
225
-      axisOffset = newOffset;
226
-      axisOffsetTicks = int32_t(axisOffset * get_encoder_ticks_mm());
227
-    }
228
-
229
-    FORCE_INLINE void set_current_position(const float newPositionMm) {
230
-      set_axis_offset(get_position_mm() - newPositionMm + axisOffset);
231
-    }
232 219
   };
233 220
 
234 221
   class I2CPositionEncodersMgr {

+ 29
- 3
Marlin/Makefile 파일 보기

@@ -82,6 +82,13 @@ LIQUID_TWI2        ?= 0
82 82
 # this defines if Wire is needed
83 83
 WIRE               ?= 0
84 84
 
85
+# this defines if U8GLIB is needed (may require RELOC_WORKAROUND)
86
+U8GLIB             ?= 1
87
+
88
+# this defines whether to add a workaround for the avr-gcc relocation bug
89
+#	  https://www.stix.id.au/wiki/AVR_relocation_truncations_workaround
90
+RELOC_WORKAROUND   ?= 1
91
+
85 92
 ############################################################################
86 93
 # Below here nothing should be changed...
87 94
 
@@ -270,6 +277,13 @@ ifeq ($(WIRE), 1)
270 277
 VPATH += $(ARDUINO_INSTALL_DIR)/libraries/Wire
271 278
 VPATH += $(ARDUINO_INSTALL_DIR)/libraries/Wire/utility
272 279
 endif
280
+ifeq ($(NEOPIXEL), 1)
281
+VPATH += $(ARDUINO_INSTALL_DIR)/libraries/Adafruit_NeoPixel
282
+endif
283
+ifeq ($(U8GLIB), 1)
284
+VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib
285
+VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib/utility
286
+endif
273 287
 
274 288
 ifeq ($(HARDWARE_VARIANT), arduino)
275 289
 HARDWARE_SUB_VARIANT ?= mega
@@ -295,8 +309,11 @@ CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp \
295 309
 	SdFile.cpp SdVolume.cpp planner.cpp stepper.cpp \
296 310
 	temperature.cpp cardreader.cpp configuration_store.cpp \
297 311
 	watchdog.cpp SPI.cpp servo.cpp Tone.cpp ultralcd.cpp digipot_mcp4451.cpp \
298
-	dac_mcp4728.cpp vector_3.cpp qr_solve.cpp endstops.cpp stopwatch.cpp utility.cpp \
299
-	printcounter.cpp nozzle.cpp serial.cpp
312
+	dac_mcp4728.cpp vector_3.cpp least_squares_fit.cpp endstops.cpp stopwatch.cpp utility.cpp \
313
+	printcounter.cpp nozzle.cpp serial.cpp gcode.cpp Max7219_Debug_LEDs.cpp
314
+ifeq ($(NEOPIXEL), 1)
315
+CXXSRC += Adafruit_NeoPixel.cpp
316
+endif
300 317
 ifeq ($(LIQUID_TWI2), 0)
301 318
 CXXSRC += LiquidCrystal.cpp
302 319
 else
@@ -309,6 +326,15 @@ SRC += twi.c
309 326
 CXXSRC += Wire.cpp
310 327
 endif
311 328
 
329
+ifeq ($(U8GLIB), 1)
330
+SRC += u8g_ll_api.c u8g_bitmap.c u8g_clip.c u8g_com_null.c u8g_delay.c u8g_page.c u8g_pb.c u8g_pb16h1.c u8g_rect.c u8g_state.c u8g_font.c u8g_font_data.c
331
+endif
332
+
333
+ifeq ($(RELOC_WORKAROUND), 1)
334
+LD_PREFIX=-nodefaultlibs
335
+LD_SUFFIX=-lm -lgcc -lc -lgcc -L$(ARDUINO_INSTALL_DIR)/hardware/tools/avr/avr/lib/avr6 -l$(MCU)
336
+endif
337
+
312 338
 #Check for Arduino 1.0.0 or higher and use the correct source files for that version
313 339
 ifeq ($(shell [ $(ARDUINO_VERSION) -ge 100 ] && echo true), true)
314 340
 CXXSRC += main.cpp
@@ -487,7 +513,7 @@ extcoff: $(TARGET).elf
487 513
 	# Link: create ELF output file from library.
488 514
 $(BUILD_DIR)/$(TARGET).elf: $(OBJ) Configuration.h
489 515
 	$(Pecho) "  CXX   $@"
490
-	$P $(CC) $(ALL_CXXFLAGS) -Wl,--gc-sections,--relax -o $@ -L. $(OBJ) $(LDFLAGS)
516
+	$P $(CC) $(LD_PREFIX) $(ALL_CXXFLAGS) -Wl,--gc-sections,--relax -o $@ -L. $(OBJ) $(LDFLAGS) $(LD_SUFFIX)
491 517
 
492 518
 $(BUILD_DIR)/%.o: %.c Configuration.h Configuration_adv.h $(MAKEFILE)
493 519
 	$(Pecho) "  CC    $<"

+ 109
- 50
Marlin/Marlin.h 파일 보기

@@ -210,17 +210,12 @@ inline void refresh_cmd_timeout() { previous_cmd_ms = millis(); }
210 210
 /**
211 211
  * Feedrate scaling and conversion
212 212
  */
213
+extern float feedrate_mm_s;
213 214
 extern int16_t feedrate_percentage;
214 215
 
215
-#define MMM_TO_MMS(MM_M) ((MM_M)/60.0)
216
-#define MMS_TO_MMM(MM_S) ((MM_S)*60.0)
217 216
 #define MMS_SCALED(MM_S) ((MM_S)*feedrate_percentage*0.01)
218 217
 
219 218
 extern bool axis_relative_modes[];
220
-extern bool volumetric_enabled;
221
-extern int16_t flow_percentage[EXTRUDERS]; // Extrusion factor for each extruder
222
-extern float filament_size[EXTRUDERS]; // cross-sectional area of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder.
223
-extern float volumetric_multiplier[EXTRUDERS]; // reciprocal of cross-sectional area of filament (in square millimeters), stored this way to reduce computational burden in planner
224 219
 extern bool axis_known_position[XYZ];
225 220
 extern bool axis_homed[XYZ];
226 221
 extern volatile bool wait_for_heatup;
@@ -229,7 +224,7 @@ extern volatile bool wait_for_heatup;
229 224
   extern volatile bool wait_for_user;
230 225
 #endif
231 226
 
232
-extern float current_position[NUM_AXIS];
227
+extern float current_position[XYZE], destination[XYZE];
233 228
 
234 229
 // Workspace offsets
235 230
 #if HAS_WORKSPACE_OFFSET
@@ -252,14 +247,14 @@ extern float current_position[NUM_AXIS];
252 247
   #define WORKSPACE_OFFSET(AXIS) 0
253 248
 #endif
254 249
 
255
-#define LOGICAL_POSITION(POS, AXIS) ((POS) + WORKSPACE_OFFSET(AXIS))
256
-#define RAW_POSITION(POS, AXIS)     ((POS) - WORKSPACE_OFFSET(AXIS))
250
+#define NATIVE_TO_LOGICAL(POS, AXIS) ((POS) + WORKSPACE_OFFSET(AXIS))
251
+#define LOGICAL_TO_NATIVE(POS, AXIS) ((POS) - WORKSPACE_OFFSET(AXIS))
257 252
 
258 253
 #if HAS_POSITION_SHIFT || DISABLED(DELTA)
259
-  #define LOGICAL_X_POSITION(POS)   LOGICAL_POSITION(POS, X_AXIS)
260
-  #define LOGICAL_Y_POSITION(POS)   LOGICAL_POSITION(POS, Y_AXIS)
261
-  #define RAW_X_POSITION(POS)       RAW_POSITION(POS, X_AXIS)
262
-  #define RAW_Y_POSITION(POS)       RAW_POSITION(POS, Y_AXIS)
254
+  #define LOGICAL_X_POSITION(POS)   NATIVE_TO_LOGICAL(POS, X_AXIS)
255
+  #define LOGICAL_Y_POSITION(POS)   NATIVE_TO_LOGICAL(POS, Y_AXIS)
256
+  #define RAW_X_POSITION(POS)       LOGICAL_TO_NATIVE(POS, X_AXIS)
257
+  #define RAW_Y_POSITION(POS)       LOGICAL_TO_NATIVE(POS, Y_AXIS)
263 258
 #else
264 259
   #define LOGICAL_X_POSITION(POS)   (POS)
265 260
   #define LOGICAL_Y_POSITION(POS)   (POS)
@@ -267,9 +262,8 @@ extern float current_position[NUM_AXIS];
267 262
   #define RAW_Y_POSITION(POS)       (POS)
268 263
 #endif
269 264
 
270
-#define LOGICAL_Z_POSITION(POS)     LOGICAL_POSITION(POS, Z_AXIS)
271
-#define RAW_Z_POSITION(POS)         RAW_POSITION(POS, Z_AXIS)
272
-#define RAW_CURRENT_POSITION(A)     RAW_##A##_POSITION(current_position[A##_AXIS])
265
+#define LOGICAL_Z_POSITION(POS)     NATIVE_TO_LOGICAL(POS, Z_AXIS)
266
+#define RAW_Z_POSITION(POS)         LOGICAL_TO_NATIVE(POS, Z_AXIS)
273 267
 
274 268
 // Hotend Offsets
275 269
 #if HOTENDS > 1
@@ -291,29 +285,81 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
291 285
   void update_software_endstops(const AxisEnum axis);
292 286
 #endif
293 287
 
288
+#if ENABLED(CNC_COORDINATE_SYSTEMS)
289
+  #define MAX_COORDINATE_SYSTEMS 9
290
+  extern float coordinate_system[MAX_COORDINATE_SYSTEMS][XYZ];
291
+  bool select_coordinate_system(const int8_t _new);
292
+#endif
293
+
294
+void report_current_position();
295
+
294 296
 #if IS_KINEMATIC
295 297
   extern float delta[ABC];
296
-  void inverse_kinematics(const float logical[XYZ]);
298
+  void inverse_kinematics(const float raw[XYZ]);
297 299
 #endif
298 300
 
299 301
 #if ENABLED(DELTA)
300
-  extern float endstop_adj[ABC],
302
+  extern float delta_height,
303
+               delta_endstop_adj[ABC],
301 304
                delta_radius,
305
+               delta_tower_angle_trim[ABC],
306
+               delta_tower[ABC][2],
302 307
                delta_diagonal_rod,
303 308
                delta_calibration_radius,
309
+               delta_diagonal_rod_2_tower[ABC],
304 310
                delta_segments_per_second,
305
-               delta_tower_angle_trim[2],
306 311
                delta_clip_start_height;
307
-  void recalc_delta_settings(float radius, float diagonal_rod);
312
+
313
+  void recalc_delta_settings();
314
+  float delta_safe_distance_from_top();
315
+
316
+  #if ENABLED(DELTA_FAST_SQRT)
317
+    float Q_rsqrt(const float number);
318
+    #define _SQRT(n) (1.0f / Q_rsqrt(n))
319
+  #else
320
+    #define _SQRT(n) SQRT(n)
321
+  #endif
322
+
323
+  // Macro to obtain the Z position of an individual tower
324
+  #define DELTA_Z(T) raw[Z_AXIS] + _SQRT(     \
325
+    delta_diagonal_rod_2_tower[T] - HYPOT2(   \
326
+        delta_tower[T][X_AXIS] - raw[X_AXIS], \
327
+        delta_tower[T][Y_AXIS] - raw[Y_AXIS]  \
328
+      )                                       \
329
+    )
330
+
331
+  #define DELTA_RAW_IK() do {        \
332
+    delta[A_AXIS] = DELTA_Z(A_AXIS); \
333
+    delta[B_AXIS] = DELTA_Z(B_AXIS); \
334
+    delta[C_AXIS] = DELTA_Z(C_AXIS); \
335
+  }while(0)
336
+
308 337
 #elif IS_SCARA
309 338
   void forward_kinematics_SCARA(const float &a, const float &b);
310 339
 #endif
311 340
 
341
+#if ENABLED(G26_MESH_VALIDATION)
342
+  extern bool g26_debug_flag;
343
+#elif ENABLED(AUTO_BED_LEVELING_UBL)
344
+  constexpr bool g26_debug_flag = false;
345
+#endif
346
+
347
+#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
348
+  #define _GET_MESH_X(I) (bilinear_start[X_AXIS] + (I) * bilinear_grid_spacing[X_AXIS])
349
+  #define _GET_MESH_Y(J) (bilinear_start[Y_AXIS] + (J) * bilinear_grid_spacing[Y_AXIS])
350
+#elif ENABLED(AUTO_BED_LEVELING_UBL)
351
+  #define _GET_MESH_X(I) ubl.mesh_index_to_xpos(I)
352
+  #define _GET_MESH_Y(J) ubl.mesh_index_to_ypos(J)
353
+#elif ENABLED(MESH_BED_LEVELING)
354
+  #define _GET_MESH_X(I) mbl.index_to_xpos[I]
355
+  #define _GET_MESH_Y(J) mbl.index_to_ypos[J]
356
+#endif
357
+
312 358
 #if ENABLED(AUTO_BED_LEVELING_BILINEAR)
313 359
   extern int bilinear_grid_spacing[2], bilinear_start[2];
314 360
   extern float bilinear_grid_factor[2],
315 361
                z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y];
316
-  float bilinear_z_offset(const float logical[XYZ]);
362
+  float bilinear_z_offset(const float raw[XYZ]);
317 363
 #endif
318 364
 
319 365
 #if ENABLED(AUTO_BED_LEVELING_UBL)
@@ -323,22 +369,26 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
323 369
 
324 370
 #if HAS_LEVELING
325 371
   bool leveling_is_valid();
326
-  bool leveling_is_active();
327 372
   void set_bed_leveling_enabled(const bool enable=true);
328 373
   void reset_bed_level();
329 374
 #endif
330 375
 
331 376
 #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
332
-  void set_z_fade_height(const float zfh);
377
+  void set_z_fade_height(const float zfh, const bool do_report=true);
333 378
 #endif
334 379
 
380
+#if ENABLED(X_DUAL_ENDSTOPS)
381
+  extern float x_endstop_adj;
382
+#endif
383
+#if ENABLED(Y_DUAL_ENDSTOPS)
384
+  extern float y_endstop_adj;
385
+#endif
335 386
 #if ENABLED(Z_DUAL_ENDSTOPS)
336 387
   extern float z_endstop_adj;
337 388
 #endif
338 389
 
339 390
 #if HAS_BED_PROBE
340 391
   extern float zprobe_zoffset;
341
-  void refresh_zprobe_zoffset(const bool no_babystep=false);
342 392
   #define DEPLOY_PROBE() set_probe_deployed(true)
343 393
   #define STOW_PROBE() set_probe_deployed(false)
344 394
 #else
@@ -355,6 +405,10 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
355 405
 
356 406
 #if FAN_COUNT > 0
357 407
   extern int16_t fanSpeeds[FAN_COUNT];
408
+  #if ENABLED(EXTRA_FAN_SPEED)
409
+    extern int16_t old_fanSpeeds[FAN_COUNT],
410
+                   new_fanSpeeds[FAN_COUNT];
411
+  #endif
358 412
   #if ENABLED(PROBING_FANS_OFF)
359 413
     extern bool fans_paused;
360 414
     extern int16_t paused_fanSpeeds[FAN_COUNT];
@@ -362,8 +416,7 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
362 416
 #endif
363 417
 
364 418
 #if ENABLED(BARICUDA)
365
-  extern int baricuda_valve_pressure;
366
-  extern int baricuda_e_to_p_pressure;
419
+  extern uint8_t baricuda_valve_pressure, baricuda_e_to_p_pressure;
367 420
 #endif
368 421
 
369 422
 #if ENABLED(FILAMENT_WIDTH_SENSOR)
@@ -384,10 +437,15 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
384 437
 #endif
385 438
 
386 439
 #if ENABLED(FWRETRACT)
387
-  extern bool autoretract_enabled;
388
-  extern bool retracted[EXTRUDERS]; // extruder[n].retracted
389
-  extern float retract_length, retract_length_swap, retract_feedrate_mm_s, retract_zlift;
390
-  extern float retract_recover_length, retract_recover_length_swap, retract_recover_feedrate_mm_s;
440
+  extern bool autoretract_enabled;                 // M209 S - Autoretract switch
441
+  extern float retract_length,                     // M207 S - G10 Retract length
442
+               retract_feedrate_mm_s,              // M207 F - G10 Retract feedrate
443
+               retract_zlift,                      // M207 Z - G10 Retract hop size
444
+               retract_recover_length,             // M208 S - G11 Recover length
445
+               retract_recover_feedrate_mm_s,      // M208 F - G11 Recover feedrate
446
+               swap_retract_length,                // M207 W - G10 Swap Retract length
447
+               swap_retract_recover_length,        // M208 W - G11 Swap Recover length
448
+               swap_retract_recover_feedrate_mm_s; // M208 R - G11 Swap Recover feedrate
391 449
 #endif
392 450
 
393 451
 // Print job timer
@@ -400,15 +458,13 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
400 458
 // Handling multiple extruders pins
401 459
 extern uint8_t active_extruder;
402 460
 
403
-#if HAS_TEMP_HOTEND || HAS_TEMP_BED
404
-  void print_heaterstates();
405
-#endif
406
-
407 461
 #if ENABLED(MIXING_EXTRUDER)
408 462
   extern float mixing_factor[MIXING_STEPPERS];
409 463
 #endif
410 464
 
411
-void calculate_volumetric_multipliers();
465
+inline void set_current_from_destination() { COPY(current_position, destination); }
466
+inline void set_destination_from_current() { COPY(destination, current_position); }
467
+void prepare_move_to_destination();
412 468
 
413 469
 /**
414 470
  * Blocking movement and shorthand functions
@@ -418,7 +474,18 @@ void do_blocking_move_to_x(const float &x, const float &fr_mm_s=0.0);
418 474
 void do_blocking_move_to_z(const float &z, const float &fr_mm_s=0.0);
419 475
 void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s=0.0);
420 476
 
421
-#if ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED) || HAS_PROBING_PROCEDURE || HOTENDS > 1 || ENABLED(NOZZLE_CLEAN_FEATURE) || ENABLED(NOZZLE_PARK_FEATURE)
477
+#define HAS_AXIS_UNHOMED_ERR (                                                     \
478
+         ENABLED(Z_PROBE_ALLEN_KEY)                                                \
479
+      || ENABLED(Z_PROBE_SLED)                                                     \
480
+      || HAS_PROBING_PROCEDURE                                                     \
481
+      || HOTENDS > 1                                                               \
482
+      || ENABLED(NOZZLE_CLEAN_FEATURE)                                             \
483
+      || ENABLED(NOZZLE_PARK_FEATURE)                                              \
484
+      || (ENABLED(ADVANCED_PAUSE_FEATURE) && ENABLED(HOME_BEFORE_FILAMENT_CHANGE)) \
485
+      || HAS_M206_COMMAND                                                          \
486
+    ) || ENABLED(NO_MOTION_BEFORE_HOMING)
487
+
488
+#if HAS_AXIS_UNHOMED_ERR
422 489
   bool axis_unhomed_error(const bool x=true, const bool y=true, const bool z=true);
423 490
 #endif
424 491
 
@@ -432,7 +499,7 @@ void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s
432 499
     extern const float L1, L2;
433 500
   #endif
434 501
 
435
-  inline bool position_is_reachable_raw_xy(const float &rx, const float &ry) {
502
+  inline bool position_is_reachable(const float &rx, const float &ry) {
436 503
     #if ENABLED(DELTA)
437 504
       return HYPOT2(rx, ry) <= sq(DELTA_PRINTABLE_RADIUS);
438 505
     #elif IS_SCARA
@@ -447,24 +514,24 @@ void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s
447 514
     #endif
448 515
   }
449 516
 
450
-  inline bool position_is_reachable_by_probe_raw_xy(const float &rx, const float &ry) {
517
+  inline bool position_is_reachable_by_probe(const float &rx, const float &ry) {
451 518
 
452 519
     // Both the nozzle and the probe must be able to reach the point.
453 520
     // This won't work on SCARA since the probe offset rotates with the arm.
454 521
 
455
-    return position_is_reachable_raw_xy(rx, ry)
456
-        && position_is_reachable_raw_xy(rx - X_PROBE_OFFSET_FROM_EXTRUDER, ry - Y_PROBE_OFFSET_FROM_EXTRUDER);
522
+    return position_is_reachable(rx, ry)
523
+        && position_is_reachable(rx - (X_PROBE_OFFSET_FROM_EXTRUDER), ry - (Y_PROBE_OFFSET_FROM_EXTRUDER));
457 524
   }
458 525
 
459 526
 #else // CARTESIAN
460 527
 
461
-  inline bool position_is_reachable_raw_xy(const float &rx, const float &ry) {
528
+  inline bool position_is_reachable(const float &rx, const float &ry) {
462 529
       // Add 0.001 margin to deal with float imprecision
463 530
       return WITHIN(rx, X_MIN_POS - 0.001, X_MAX_POS + 0.001)
464 531
           && WITHIN(ry, Y_MIN_POS - 0.001, Y_MAX_POS + 0.001);
465 532
   }
466 533
 
467
-  inline bool position_is_reachable_by_probe_raw_xy(const float &rx, const float &ry) {
534
+  inline bool position_is_reachable_by_probe(const float &rx, const float &ry) {
468 535
       // Add 0.001 margin to deal with float imprecision
469 536
       return WITHIN(rx, MIN_PROBE_X - 0.001, MAX_PROBE_X + 0.001)
470 537
           && WITHIN(ry, MIN_PROBE_Y - 0.001, MAX_PROBE_Y + 0.001);
@@ -472,12 +539,4 @@ void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s
472 539
 
473 540
 #endif // CARTESIAN
474 541
 
475
-FORCE_INLINE bool position_is_reachable_by_probe_xy(const float &lx, const float &ly) {
476
-  return position_is_reachable_by_probe_raw_xy(RAW_X_POSITION(lx), RAW_Y_POSITION(ly));
477
-}
478
-
479
-FORCE_INLINE bool position_is_reachable_xy(const float &lx, const float &ly) {
480
-  return position_is_reachable_raw_xy(RAW_X_POSITION(lx), RAW_Y_POSITION(ly));
481
-}
482
-
483 542
 #endif // MARLIN_H

+ 1
- 0
Marlin/MarlinConfig.h 파일 보기

@@ -29,6 +29,7 @@
29 29
 #include "Version.h"
30 30
 #include "Configuration.h"
31 31
 #include "Conditionals_LCD.h"
32
+#include "tmc_macros.h"
32 33
 #include "Configuration_adv.h"
33 34
 #include "pins.h"
34 35
 #ifndef USBCON

Marlin/spi.h → Marlin/MarlinSPI.h 파일 보기

@@ -20,8 +20,8 @@
20 20
  *
21 21
  */
22 22
 
23
-#ifndef __SPI_H__
24
-#define __SPI_H__
23
+#ifndef __MARLIN_SPI_H__
24
+#define __MARLIN_SPI_H__
25 25
 
26 26
 #include <stdint.h>
27 27
 #include "softspi.h"
@@ -54,4 +54,4 @@ class SPI<MISO_PIN, MOSI_PIN, SCK_PIN> {
54 54
 
55 55
 };
56 56
 
57
-#endif // __SPI_H__
57
+#endif // __MARLIN_SPI_H__

+ 197
- 60
Marlin/MarlinSerial.cpp 파일 보기

@@ -27,15 +27,30 @@
27 27
  * Modified 23 November 2006 by David A. Mellis
28 28
  * Modified 28 September 2010 by Mark Sproul
29 29
  * Modified 14 February 2016 by Andreas Hardtung (added tx buffer)
30
+ * Modified 01 October 2017 by Eduardo José Tagle (added XON/XOFF)
30 31
  */
31 32
 
32
-#include "MarlinSerial.h"
33
-#include "Marlin.h"
34
-
35 33
 // Disable HardwareSerial.cpp to support chips without a UART (Attiny, etc.)
36 34
 
35
+#include "MarlinConfig.h"
36
+
37 37
 #if !defined(USBCON) && (defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H))
38 38
 
39
+  #include "MarlinSerial.h"
40
+  #include "Marlin.h"
41
+
42
+  struct ring_buffer_r {
43
+    unsigned char buffer[RX_BUFFER_SIZE];
44
+    volatile ring_buffer_pos_t head, tail;
45
+  };
46
+
47
+  #if TX_BUFFER_SIZE > 0
48
+    struct ring_buffer_t {
49
+      unsigned char buffer[TX_BUFFER_SIZE];
50
+      volatile uint8_t head, tail;
51
+    };
52
+  #endif
53
+
39 54
   #if UART_PRESENT(SERIAL_PORT)
40 55
     ring_buffer_r rx_buffer = { { 0 }, 0, 0 };
41 56
     #if TX_BUFFER_SIZE > 0
@@ -44,6 +59,23 @@
44 59
     #endif
45 60
   #endif
46 61
 
62
+  #if ENABLED(SERIAL_XON_XOFF)
63
+    constexpr uint8_t XON_XOFF_CHAR_SENT = 0x80;  // XON / XOFF Character was sent
64
+    constexpr uint8_t XON_XOFF_CHAR_MASK = 0x1F;  // XON / XOFF character to send
65
+    // XON / XOFF character definitions
66
+    constexpr uint8_t XON_CHAR  = 17;
67
+    constexpr uint8_t XOFF_CHAR = 19;
68
+    uint8_t xon_xoff_state = XON_XOFF_CHAR_SENT | XON_CHAR;
69
+  #endif
70
+
71
+  #if ENABLED(SERIAL_STATS_DROPPED_RX)
72
+    uint8_t rx_dropped_bytes = 0;
73
+  #endif
74
+
75
+  #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
76
+    ring_buffer_pos_t rx_max_enqueued = 0;
77
+  #endif
78
+
47 79
   #if ENABLED(EMERGENCY_PARSER)
48 80
 
49 81
     #include "stepper.h"
@@ -136,20 +168,78 @@
136 168
 
137 169
   #endif // EMERGENCY_PARSER
138 170
 
139
-  FORCE_INLINE void store_char(unsigned char c) {
140
-    CRITICAL_SECTION_START;
141
-      const uint8_t h = rx_buffer.head,
142
-                    i = (uint8_t)(h + 1) & (RX_BUFFER_SIZE - 1);
143
-
144
-      // if we should be storing the received character into the location
145
-      // just before the tail (meaning that the head would advance to the
146
-      // current location of the tail), we're about to overflow the buffer
147
-      // and so we don't write the character or advance the head.
148
-      if (i != rx_buffer.tail) {
149
-        rx_buffer.buffer[h] = c;
150
-        rx_buffer.head = i;
171
+  FORCE_INLINE void store_rxd_char() {
172
+    const ring_buffer_pos_t h = rx_buffer.head,
173
+                            i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
174
+
175
+    // If the character is to be stored at the index just before the tail
176
+    // (such that the head would advance to the current tail), the buffer is
177
+    // critical, so don't write the character or advance the head.
178
+    const char c = M_UDRx;
179
+    if (i != rx_buffer.tail) {
180
+      rx_buffer.buffer[h] = c;
181
+      rx_buffer.head = i;
182
+    }
183
+    else {
184
+      #if ENABLED(SERIAL_STATS_DROPPED_RX)
185
+        if (!++rx_dropped_bytes) ++rx_dropped_bytes;
186
+      #endif
187
+    }
188
+
189
+    #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
190
+      // calculate count of bytes stored into the RX buffer
191
+      ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(rx_buffer.head - rx_buffer.tail) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
192
+      // Keep track of the maximum count of enqueued bytes
193
+      NOLESS(rx_max_enqueued, rx_count);
194
+    #endif
195
+
196
+    #if ENABLED(SERIAL_XON_XOFF)
197
+
198
+      // for high speed transfers, we can use XON/XOFF protocol to do
199
+      // software handshake and avoid overruns.
200
+      if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XON_CHAR) {
201
+
202
+        // calculate count of bytes stored into the RX buffer
203
+        ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(rx_buffer.head - rx_buffer.tail) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
204
+
205
+        // if we are above 12.5% of RX buffer capacity, send XOFF before
206
+        // we run out of RX buffer space .. We need 325 bytes @ 250kbits/s to
207
+        // let the host react and stop sending bytes. This translates to 13mS
208
+        // propagation time.
209
+        if (rx_count >= (RX_BUFFER_SIZE) / 8) {
210
+          // If TX interrupts are disabled and data register is empty,
211
+          // just write the byte to the data register and be done. This
212
+          // shortcut helps significantly improve the effective datarate
213
+          // at high (>500kbit/s) bitrates, where interrupt overhead
214
+          // becomes a slowdown.
215
+          if (!TEST(M_UCSRxB, M_UDRIEx) && TEST(M_UCSRxA, M_UDREx)) {
216
+            // Send an XOFF character
217
+            M_UDRx = XOFF_CHAR;
218
+            // clear the TXC bit -- "can be cleared by writing a one to its bit
219
+            // location". This makes sure flush() won't return until the bytes
220
+            // actually got written
221
+            SBI(M_UCSRxA, M_TXCx);
222
+            // And remember it was sent
223
+            xon_xoff_state = XOFF_CHAR | XON_XOFF_CHAR_SENT;
224
+          }
225
+          else {
226
+            // TX interrupts disabled, but buffer still not empty ... or
227
+            // TX interrupts enabled. Reenable TX ints and schedule XOFF
228
+            // character to be sent
229
+            #if TX_BUFFER_SIZE > 0
230
+              SBI(M_UCSRxB, M_UDRIEx);
231
+              xon_xoff_state = XOFF_CHAR;
232
+            #else
233
+              // We are not using TX interrupts, we will have to send this manually
234
+              while (!TEST(M_UCSRxA, M_UDREx)) {/* nada */}
235
+              M_UDRx = XOFF_CHAR;
236
+              // And remember we already sent it
237
+              xon_xoff_state = XOFF_CHAR | XON_XOFF_CHAR_SENT;
238
+            #endif
239
+          }
240
+        }
151 241
       }
152
-    CRITICAL_SECTION_END;
242
+    #endif // SERIAL_XON_XOFF
153 243
 
154 244
     #if ENABLED(EMERGENCY_PARSER)
155 245
       emergency_parser(c);
@@ -160,37 +250,41 @@
160 250
 
161 251
     FORCE_INLINE void _tx_udr_empty_irq(void) {
162 252
       // If interrupts are enabled, there must be more data in the output
163
-      // buffer. Send the next byte
164
-      const uint8_t t = tx_buffer.tail,
165
-                    c = tx_buffer.buffer[t];
166
-      tx_buffer.tail = (t + 1) & (TX_BUFFER_SIZE - 1);
167
-
168
-      M_UDRx = c;
253
+      // buffer.
254
+
255
+      #if ENABLED(SERIAL_XON_XOFF)
256
+        // Do a priority insertion of an XON/XOFF char, if needed.
257
+        const uint8_t state = xon_xoff_state;
258
+        if (!(state & XON_XOFF_CHAR_SENT)) {
259
+          M_UDRx = state & XON_XOFF_CHAR_MASK;
260
+          xon_xoff_state = state | XON_XOFF_CHAR_SENT;
261
+        }
262
+        else
263
+      #endif
264
+      { // Send the next byte
265
+        const uint8_t t = tx_buffer.tail, c = tx_buffer.buffer[t];
266
+        tx_buffer.tail = (t + 1) & (TX_BUFFER_SIZE - 1);
267
+        M_UDRx = c;
268
+      }
169 269
 
170 270
       // clear the TXC bit -- "can be cleared by writing a one to its bit
171 271
       // location". This makes sure flush() won't return until the bytes
172 272
       // actually got written
173 273
       SBI(M_UCSRxA, M_TXCx);
174 274
 
175
-      if (tx_buffer.head == tx_buffer.tail) {
176
-        // Buffer empty, so disable interrupts
275
+      // Disable interrupts if the buffer is empty
276
+      if (tx_buffer.head == tx_buffer.tail)
177 277
         CBI(M_UCSRxB, M_UDRIEx);
178
-      }
179 278
     }
180 279
 
181 280
     #ifdef M_USARTx_UDRE_vect
182
-      ISR(M_USARTx_UDRE_vect) {
183
-        _tx_udr_empty_irq();
184
-      }
281
+      ISR(M_USARTx_UDRE_vect) { _tx_udr_empty_irq(); }
185 282
     #endif
186 283
 
187 284
   #endif // TX_BUFFER_SIZE
188 285
 
189 286
   #ifdef M_USARTx_RX_vect
190
-    ISR(M_USARTx_RX_vect) {
191
-      const unsigned char c = M_UDRx;
192
-      store_char(c);
193
-    }
287
+    ISR(M_USARTx_RX_vect) { store_rxd_char(); }
194 288
   #endif
195 289
 
196 290
   // Public Methods
@@ -200,9 +294,9 @@
200 294
     bool useU2X = true;
201 295
 
202 296
     #if F_CPU == 16000000UL && SERIAL_PORT == 0
203
-      // hard-coded exception for compatibility with the bootloader shipped
204
-      // with the Duemilanove and previous boards and the firmware on the 8U2
205
-      // on the Uno and Mega 2560.
297
+      // Hard-coded exception for compatibility with the bootloader shipped
298
+      // with the Duemilanove and previous boards, and the firmware on the
299
+      // 8U2 on the Uno and Mega 2560.
206 300
       if (baud == 57600) useU2X = false;
207 301
     #endif
208 302
 
@@ -237,8 +331,9 @@
237 331
 
238 332
   void MarlinSerial::checkRx(void) {
239 333
     if (TEST(M_UCSRxA, M_RXCx)) {
240
-      const uint8_t c = M_UDRx;
241
-      store_char(c);
334
+      CRITICAL_SECTION_START;
335
+        store_rxd_char();
336
+      CRITICAL_SECTION_END;
242 337
     }
243 338
   }
244 339
 
@@ -252,51 +347,81 @@
252 347
   int MarlinSerial::read(void) {
253 348
     int v;
254 349
     CRITICAL_SECTION_START;
255
-      const uint8_t t = rx_buffer.tail;
350
+      const ring_buffer_pos_t t = rx_buffer.tail;
256 351
       if (rx_buffer.head == t)
257 352
         v = -1;
258 353
       else {
259 354
         v = rx_buffer.buffer[t];
260
-        rx_buffer.tail = (uint8_t)(t + 1) & (RX_BUFFER_SIZE - 1);
355
+        rx_buffer.tail = (ring_buffer_pos_t)(t + 1) & (RX_BUFFER_SIZE - 1);
356
+
357
+        #if ENABLED(SERIAL_XON_XOFF)
358
+          if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XOFF_CHAR) {
359
+            // Get count of bytes in the RX buffer
360
+            ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(rx_buffer.head - rx_buffer.tail) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
361
+            // When below 10% of RX buffer capacity, send XON before
362
+            // running out of RX buffer bytes
363
+            if (rx_count < (RX_BUFFER_SIZE) / 10) {
364
+              xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT;
365
+              CRITICAL_SECTION_END;       // End critical section before returning!
366
+              writeNoHandshake(XON_CHAR);
367
+              return v;
368
+            }
369
+          }
370
+        #endif
261 371
       }
262 372
     CRITICAL_SECTION_END;
263 373
     return v;
264 374
   }
265 375
 
266
-  uint8_t MarlinSerial::available(void) {
376
+  ring_buffer_pos_t MarlinSerial::available(void) {
267 377
     CRITICAL_SECTION_START;
268
-      const uint8_t h = rx_buffer.head,
269
-                    t = rx_buffer.tail;
378
+      const ring_buffer_pos_t h = rx_buffer.head, t = rx_buffer.tail;
270 379
     CRITICAL_SECTION_END;
271
-    return (uint8_t)(RX_BUFFER_SIZE + h - t) & (RX_BUFFER_SIZE - 1);
380
+    return (ring_buffer_pos_t)(RX_BUFFER_SIZE + h - t) & (RX_BUFFER_SIZE - 1);
272 381
   }
273 382
 
274 383
   void MarlinSerial::flush(void) {
275
-    // RX
276
-    // don't reverse this or there may be problems if the RX interrupt
277
-    // occurs after reading the value of rx_buffer_head but before writing
278
-    // the value to rx_buffer_tail; the previous value of rx_buffer_head
279
-    // may be written to rx_buffer_tail, making it appear as if the buffer
280
-    // were full, not empty.
384
+    // Don't change this order of operations. If the RX interrupt occurs between
385
+    // reading rx_buffer_head and updating rx_buffer_tail, the previous rx_buffer_head
386
+    // may be written to rx_buffer_tail, making the buffer appear full rather than empty.
281 387
     CRITICAL_SECTION_START;
282 388
       rx_buffer.head = rx_buffer.tail;
283 389
     CRITICAL_SECTION_END;
390
+
391
+    #if ENABLED(SERIAL_XON_XOFF)
392
+      if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XOFF_CHAR) {
393
+        xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT;
394
+        writeNoHandshake(XON_CHAR);
395
+      }
396
+    #endif
284 397
   }
285 398
 
286 399
   #if TX_BUFFER_SIZE > 0
287 400
     uint8_t MarlinSerial::availableForWrite(void) {
288 401
       CRITICAL_SECTION_START;
289
-        const uint8_t h = tx_buffer.head,
290
-                      t = tx_buffer.tail;
402
+        const uint8_t h = tx_buffer.head, t = tx_buffer.tail;
291 403
       CRITICAL_SECTION_END;
292 404
       return (uint8_t)(TX_BUFFER_SIZE + h - t) & (TX_BUFFER_SIZE - 1);
293 405
     }
294 406
 
295 407
     void MarlinSerial::write(const uint8_t c) {
408
+      #if ENABLED(SERIAL_XON_XOFF)
409
+        const uint8_t state = xon_xoff_state;
410
+        if (!(state & XON_XOFF_CHAR_SENT)) {
411
+          // Send 2 chars: XON/XOFF, then a user-specified char
412
+          writeNoHandshake(state & XON_XOFF_CHAR_MASK);
413
+          xon_xoff_state = state | XON_XOFF_CHAR_SENT;
414
+        }
415
+      #endif
416
+      writeNoHandshake(c);
417
+    }
418
+
419
+    void MarlinSerial::writeNoHandshake(const uint8_t c) {
296 420
       _written = true;
297 421
       CRITICAL_SECTION_START;
298 422
         bool emty = (tx_buffer.head == tx_buffer.tail);
299 423
       CRITICAL_SECTION_END;
424
+
300 425
       // If the buffer and the data register is empty, just write the byte
301 426
       // to the data register and be done. This shortcut helps
302 427
       // significantly improve the effective datarate at high (>
@@ -353,20 +478,32 @@
353 478
       }
354 479
       // If we get here, nothing is queued anymore (DRIE is disabled) and
355 480
       // the hardware finished tranmission (TXC is set).
356
-  }
481
+    }
357 482
 
358
-  #else
359
-    void MarlinSerial::write(uint8_t c) {
360
-      while (!TEST(M_UCSRxA, M_UDREx))
361
-        ;
362
-      M_UDRx = c;
483
+  #else // TX_BUFFER_SIZE == 0
484
+
485
+    void MarlinSerial::write(const uint8_t c) {
486
+      #if ENABLED(SERIAL_XON_XOFF)
487
+        // Do a priority insertion of an XON/XOFF char, if needed.
488
+        const uint8_t state = xon_xoff_state;
489
+        if (!(state & XON_XOFF_CHAR_SENT)) {
490
+          writeNoHandshake(state & XON_XOFF_CHAR_MASK);
491
+          xon_xoff_state = state | XON_XOFF_CHAR_SENT;
492
+        }
493
+      #endif
494
+      writeNoHandshake(c);
363 495
     }
364
-  #endif
365 496
 
366
-  // end NEW
497
+    void MarlinSerial::writeNoHandshake(uint8_t c) {
498
+      while (!TEST(M_UCSRxA, M_UDREx)) {/* nada */}
499
+      M_UDRx = c;
500
+    }
367 501
 
368
-  /// imports from print.h
502
+  #endif // TX_BUFFER_SIZE == 0
369 503
 
504
+  /**
505
+   * Imports from print.h
506
+   */
370 507
 
371 508
   void MarlinSerial::print(char c, int base) {
372 509
     print((long)c, base);

+ 42
- 35
Marlin/MarlinSerial.h 파일 보기

@@ -75,44 +75,42 @@
75 75
 #define BIN 2
76 76
 #define BYTE 0
77 77
 
78
+// Define constants and variables for buffering serial data.
79
+// Use only 0 or powers of 2 greater than 1
80
+// : [0, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048, ...]
81
+#ifndef RX_BUFFER_SIZE
82
+  #define RX_BUFFER_SIZE 128
83
+#endif
84
+// 256 is the max TX buffer limit due to uint8_t head and tail.
85
+#ifndef TX_BUFFER_SIZE
86
+  #define TX_BUFFER_SIZE 32
87
+#endif
88
+
78 89
 #ifndef USBCON
79
-  // Define constants and variables for buffering incoming serial data.  We're
80
-  // using a ring buffer (I think), in which rx_buffer_head is the index of the
81
-  // location to which to write the next incoming character and rx_buffer_tail
82
-  // is the index of the location from which to read.
83
-  // 256 is the max limit due to uint8_t head and tail. Use only powers of 2. (...,16,32,64,128,256)
84
-  #ifndef RX_BUFFER_SIZE
85
-    #define RX_BUFFER_SIZE 128
90
+  #if ENABLED(SERIAL_XON_XOFF) && RX_BUFFER_SIZE < 1024
91
+    #error "SERIAL_XON_XOFF requires RX_BUFFER_SIZE >= 1024 for reliable transfers without drops."
86 92
   #endif
87
-  #ifndef TX_BUFFER_SIZE
88
-    #define TX_BUFFER_SIZE 32
89
-  #endif
90
-  #if !((RX_BUFFER_SIZE == 256) ||(RX_BUFFER_SIZE == 128) ||(RX_BUFFER_SIZE == 64) ||(RX_BUFFER_SIZE == 32) ||(RX_BUFFER_SIZE == 16) ||(RX_BUFFER_SIZE == 8) ||(RX_BUFFER_SIZE == 4) ||(RX_BUFFER_SIZE == 2))
91
-    #error "RX_BUFFER_SIZE has to be a power of 2 and >= 2"
93
+
94
+  #if !IS_POWER_OF_2(RX_BUFFER_SIZE) || RX_BUFFER_SIZE < 2
95
+    #error "RX_BUFFER_SIZE must be a power of 2 greater than 1."
92 96
   #endif
93
-  #if !((TX_BUFFER_SIZE == 256) ||(TX_BUFFER_SIZE == 128) ||(TX_BUFFER_SIZE == 64) ||(TX_BUFFER_SIZE == 32) ||(TX_BUFFER_SIZE == 16) ||(TX_BUFFER_SIZE == 8) ||(TX_BUFFER_SIZE == 4) ||(TX_BUFFER_SIZE == 2) ||(TX_BUFFER_SIZE == 0))
94
-    #error TX_BUFFER_SIZE has to be a power of 2 or 0
97
+
98
+  #if TX_BUFFER_SIZE && (TX_BUFFER_SIZE < 2 || TX_BUFFER_SIZE > 256 || !IS_POWER_OF_2(TX_BUFFER_SIZE))
99
+    #error "TX_BUFFER_SIZE must be 0, a power of 2 greater than 1, and no greater than 256."
95 100
   #endif
96 101
 
97
-  struct ring_buffer_r {
98
-    unsigned char buffer[RX_BUFFER_SIZE];
99
-    volatile uint8_t head;
100
-    volatile uint8_t tail;
101
-  };
102
+  #if RX_BUFFER_SIZE > 256
103
+    typedef uint16_t ring_buffer_pos_t;
104
+  #else
105
+    typedef uint8_t ring_buffer_pos_t;
106
+  #endif
102 107
 
103
-  #if TX_BUFFER_SIZE > 0
104
-    struct ring_buffer_t {
105
-      unsigned char buffer[TX_BUFFER_SIZE];
106
-      volatile uint8_t head;
107
-      volatile uint8_t tail;
108
-    };
108
+  #if ENABLED(SERIAL_STATS_DROPPED_RX)
109
+    extern uint8_t rx_dropped_bytes;
109 110
   #endif
110 111
 
111
-  #if UART_PRESENT(SERIAL_PORT)
112
-    extern ring_buffer_r rx_buffer;
113
-    #if TX_BUFFER_SIZE > 0
114
-      extern ring_buffer_t tx_buffer;
115
-    #endif
112
+  #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
113
+    extern ring_buffer_pos_t rx_max_enqueued;
116 114
   #endif
117 115
 
118 116
   class MarlinSerial { //: public Stream
@@ -124,23 +122,32 @@
124 122
       static int peek(void);
125 123
       static int read(void);
126 124
       static void flush(void);
127
-      static uint8_t available(void);
125
+      static ring_buffer_pos_t available(void);
128 126
       static void checkRx(void);
129 127
       static void write(const uint8_t c);
130 128
       #if TX_BUFFER_SIZE > 0
131 129
         static uint8_t availableForWrite(void);
132 130
         static void flushTX(void);
133 131
       #endif
132
+      static void writeNoHandshake(const uint8_t c);
133
+
134
+      #if ENABLED(SERIAL_STATS_DROPPED_RX)
135
+        FORCE_INLINE static uint32_t dropped() { return rx_dropped_bytes; }
136
+      #endif
137
+
138
+      #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
139
+        FORCE_INLINE static ring_buffer_pos_t rxMaxEnqueued() { return rx_max_enqueued; }
140
+      #endif
134 141
 
135 142
     private:
136 143
       static void printNumber(unsigned long, const uint8_t);
137 144
       static void printFloat(double, uint8_t);
138 145
 
139 146
     public:
140
-      static FORCE_INLINE void write(const char* str) { while (*str) write(*str++); }
141
-      static FORCE_INLINE void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); }
142
-      static FORCE_INLINE void print(const String& s) { for (int i = 0; i < (int)s.length(); i++) write(s[i]); }
143
-      static FORCE_INLINE void print(const char* str) { write(str); }
147
+      FORCE_INLINE static void write(const char* str) { while (*str) write(*str++); }
148
+      FORCE_INLINE static void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); }
149
+      FORCE_INLINE static void print(const String& s) { for (int i = 0; i < (int)s.length(); i++) write(s[i]); }
150
+      FORCE_INLINE static void print(const char* str) { write(str); }
144 151
 
145 152
       static void print(char, int = BYTE);
146 153
       static void print(unsigned char, int = BYTE);

+ 3660
- 2249
Marlin/Marlin_main.cpp
파일 크기가 너무 크기때문에 변경 상태를 표시하지 않습니다.
파일 보기


+ 349
- 0
Marlin/Max7219_Debug_LEDs.cpp 파일 보기

@@ -0,0 +1,349 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 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
+/**
24
+ * This module is off by default, but can be enabled to facilitate the display of
25
+ * extra debug information during code development. It assumes the existence of a
26
+ * Max7219 LED Matrix. A suitable device can be obtained on eBay similar to this:
27
+ * http://www.ebay.com/itm/191781645249 for under $2.00 including shipping.
28
+ *
29
+ * Just connect up +5v and GND to give it power, then connect up the pins assigned
30
+ * in Configuration_adv.h. For example, on the Re-ARM you could use:
31
+ *
32
+ *   #define MAX7219_CLK_PIN   77
33
+ *   #define MAX7219_DIN_PIN   78
34
+ *   #define MAX7219_LOAD_PIN  79
35
+ *
36
+ * Max7219_init() is called automatically at startup, and then there are a number of
37
+ * support functions available to control the LEDs in the 8x8 grid.
38
+ *
39
+ * void Max7219_init();
40
+ * void Max7219_PutByte(uint8_t data);
41
+ * void Max7219(uint8_t reg, uint8_t data);
42
+ * void Max7219_LED_On(uint8_t col, uint8_t row);
43
+ * void Max7219_LED_Off(uint8_t col, uint8_t row);
44
+ * void Max7219_LED_Toggle(uint8_t col, uint8_t row);
45
+ * void Max7219_Clear_Row(uint8_t row);
46
+ * void Max7219_Clear_Column(uint8_t col);
47
+ * void Max7219_Set_Row(uint8_t row, uint8_t val);
48
+ * void Max7219_Set_2_Rows(uint8_t row, uint16_t val);
49
+ * void Max7219_Set_4_Rows(uint8_t row, uint32_t val);
50
+ * void Max7219_Set_Column(uint8_t col, uint8_t val);
51
+ * void Max7219_idle_tasks();
52
+ */
53
+
54
+#include "MarlinConfig.h"
55
+
56
+#if ENABLED(MAX7219_DEBUG)
57
+
58
+#include "Max7219_Debug_LEDs.h"
59
+
60
+#include "planner.h"
61
+#include "stepper.h"
62
+#include "Marlin.h"
63
+
64
+static uint8_t LEDs[8] = { 0 };
65
+
66
+#ifdef CPU_32_BIT
67
+  #define MS_DELAY() delayMicroseconds(5)  // 32-bit processors need a delay to stabilize the signal
68
+#else
69
+  #define MS_DELAY() NOOP
70
+#endif
71
+
72
+void Max7219_PutByte(uint8_t data) {
73
+  CRITICAL_SECTION_START
74
+  for (uint8_t i = 8; i--;) {
75
+    MS_DELAY();
76
+    WRITE(MAX7219_CLK_PIN, LOW);       // tick
77
+    MS_DELAY();
78
+    WRITE(MAX7219_DIN_PIN, (data & 0x80) ? HIGH : LOW);  // send 1 or 0 based on data bit
79
+    MS_DELAY();
80
+    WRITE(MAX7219_CLK_PIN, HIGH);      // tock
81
+    MS_DELAY();
82
+    data <<= 1;
83
+  }
84
+  CRITICAL_SECTION_END
85
+}
86
+
87
+void Max7219(const uint8_t reg, const uint8_t data) {
88
+  MS_DELAY();
89
+  CRITICAL_SECTION_START
90
+  WRITE(MAX7219_LOAD_PIN, LOW);  // begin
91
+  MS_DELAY();
92
+  Max7219_PutByte(reg);          // specify register
93
+  MS_DELAY();
94
+  Max7219_PutByte(data);         // put data
95
+  MS_DELAY();
96
+  WRITE(MAX7219_LOAD_PIN, LOW);  // and tell the chip to load the data
97
+  MS_DELAY();
98
+  WRITE(MAX7219_LOAD_PIN, HIGH);
99
+  CRITICAL_SECTION_END
100
+  MS_DELAY();
101
+}
102
+
103
+void Max7219_LED_Set(const uint8_t row, const uint8_t col, const bool on) {
104
+  if (row > 7 || col > 7) {
105
+    SERIAL_ECHOPAIR("??? Max7219_LED_Set(", (int)row);
106
+    SERIAL_ECHOPAIR(",", (int)col);
107
+    SERIAL_ECHOLNPGM(")");
108
+    return;
109
+  }
110
+  if (TEST(LEDs[row], col) == on) return; // if LED is already on/off, leave alone
111
+  if (on) SBI(LEDs[row], col); else CBI(LEDs[row], col);
112
+  Max7219(8 - row, LEDs[row]);
113
+}
114
+
115
+void Max7219_LED_On(const uint8_t col, const uint8_t row) {
116
+  if (row > 7 || col > 7) {
117
+    SERIAL_ECHOPAIR("??? Max7219_LED_On(", (int)col);
118
+    SERIAL_ECHOPAIR(",", (int)row);
119
+    SERIAL_ECHOLNPGM(")");
120
+    return;
121
+  }
122
+  Max7219_LED_Set(col, row, true);
123
+}
124
+
125
+void Max7219_LED_Off(const uint8_t col, const uint8_t row) {
126
+  if (row > 7 || col > 7) {
127
+    SERIAL_ECHOPAIR("??? Max7219_LED_Off(", (int)row);
128
+    SERIAL_ECHOPAIR(",", (int)col);
129
+    SERIAL_ECHOLNPGM(")");
130
+    return;
131
+  }
132
+  Max7219_LED_Set(col, row, false);
133
+}
134
+
135
+void Max7219_LED_Toggle(const uint8_t col, const uint8_t row) {
136
+  if (row > 7 || col > 7) {
137
+    SERIAL_ECHOPAIR("??? Max7219_LED_Toggle(", (int)row);
138
+    SERIAL_ECHOPAIR(",", (int)col);
139
+    SERIAL_ECHOLNPGM(")");
140
+    return;
141
+  }
142
+  if (TEST(LEDs[row], col))
143
+    Max7219_LED_Off(col, row);
144
+  else
145
+    Max7219_LED_On(col, row);
146
+}
147
+
148
+void Max7219_Clear_Column(const uint8_t col) {
149
+  if (col > 7) {
150
+    SERIAL_ECHOPAIR("??? Max7219_Clear_Column(", (int)col);
151
+    SERIAL_ECHOLNPGM(")");
152
+    return;
153
+  }
154
+  LEDs[col] = 0;
155
+  Max7219(8 - col, LEDs[col]);
156
+}
157
+
158
+void Max7219_Clear_Row(const uint8_t row) {
159
+  if (row > 7) {
160
+    SERIAL_ECHOPAIR("??? Max7219_Clear_Row(", (int)row);
161
+    SERIAL_ECHOLNPGM(")");
162
+    return;
163
+  }
164
+  for (uint8_t c = 0; c <= 7; c++)
165
+    Max7219_LED_Off(c, row);
166
+}
167
+
168
+void Max7219_Set_Row(const uint8_t row, const uint8_t val) {
169
+  if (row > 7) {
170
+    SERIAL_ECHOPAIR("??? Max7219_Set_Row(", (int)row);
171
+    SERIAL_ECHOPAIR(",", (int)val);
172
+    SERIAL_ECHOLNPGM(")");
173
+    return;
174
+  }
175
+  for (uint8_t b = 0; b <= 7; b++)
176
+    if (TEST(val, b))
177
+      Max7219_LED_On(7 - b, row);
178
+    else
179
+      Max7219_LED_Off(7 - b, row);
180
+}
181
+
182
+void Max7219_Set_2_Rows(const uint8_t row, const uint16_t val) {
183
+  if (row > 6) {
184
+    SERIAL_ECHOPAIR("??? Max7219_Set_2_Rows(", (int)row);
185
+    SERIAL_ECHOPAIR(",", (int)val);
186
+    SERIAL_ECHOLNPGM(")");
187
+    return;
188
+  }
189
+  Max7219_Set_Row(row + 1, (val >> 8) & 0xFF);
190
+  Max7219_Set_Row(row + 0, (val     ) & 0xFF);
191
+}
192
+
193
+void Max7219_Set_4_Rows(const uint8_t row, const uint32_t val) {
194
+  if (row > 4) {
195
+    SERIAL_ECHOPAIR("??? Max7219_Set_4_Rows(", (int)row);
196
+    SERIAL_ECHOPAIR(",", (long)val);
197
+    SERIAL_ECHOLNPGM(")");
198
+    return;
199
+  }
200
+  Max7219_Set_Row(row + 3, (val >> 24) & 0xFF);
201
+  Max7219_Set_Row(row + 2, (val >> 16) & 0xFF);
202
+  Max7219_Set_Row(row + 1, (val >>  8) & 0xFF);
203
+  Max7219_Set_Row(row + 0, (val      ) & 0xFF);
204
+}
205
+
206
+void Max7219_Set_Column(const uint8_t col, const uint8_t val) {
207
+  if (col > 7) {
208
+    SERIAL_ECHOPAIR("??? Max7219_Column(", (int)col);
209
+    SERIAL_ECHOPAIR(",", (int)val);
210
+    SERIAL_ECHOLNPGM(")");
211
+    return;
212
+  }
213
+  LEDs[col] = val;
214
+  Max7219(8 - col, LEDs[col]);
215
+}
216
+
217
+void Max7219_init() {
218
+  uint8_t i, x, y;
219
+
220
+  SET_OUTPUT(MAX7219_DIN_PIN);
221
+  SET_OUTPUT(MAX7219_CLK_PIN);
222
+
223
+  OUT_WRITE(MAX7219_LOAD_PIN, HIGH);
224
+  delay(1);
225
+
226
+  //initiation of the max 7219
227
+  Max7219(max7219_reg_scanLimit, 0x07);
228
+  Max7219(max7219_reg_decodeMode, 0x00);  // using an led matrix (not digits)
229
+  Max7219(max7219_reg_shutdown, 0x01);    // not in shutdown mode
230
+  Max7219(max7219_reg_displayTest, 0x00); // no display test
231
+  Max7219(max7219_reg_intensity, 0x01 & 0x0F); // the first 0x0F is the value you can set
232
+                                               // range: 0x00 to 0x0F
233
+  for (i = 0; i <= 7; i++) {      // empty registers, turn all LEDs off
234
+    LEDs[i] = 0x00;
235
+    Max7219(i + 1, 0);
236
+  }
237
+
238
+  for (x = 0; x <= 7; x++)        // Do an aesthetically pleasing pattern to fully test
239
+    for (y = 0; y <= 7; y++) {    // the Max7219 module and LEDs. First, turn them
240
+      Max7219_LED_On(x, y);       // all on.
241
+      delay(3);
242
+    }
243
+
244
+  for (x = 0; x <= 7; x++)        // Now, turn them all off.
245
+    for (y = 0; y <= 7; y++) {
246
+      Max7219_LED_Off(x, y);
247
+      delay(3);                   // delay() is OK here. Max7219_init() is only called from
248
+    }                             // setup() and nothing is running yet.
249
+
250
+  delay(150);
251
+
252
+  for (x = 8; x--;)               // Now, do the same thing from the opposite direction
253
+    for (y = 0; y <= 7; y++) {
254
+      Max7219_LED_On(x, y);
255
+      delay(2);
256
+    }
257
+
258
+  for (x = 8; x--;)
259
+    for (y = 0; y <= 7; y++) {
260
+      Max7219_LED_Off(x, y);
261
+      delay(2);
262
+    }
263
+}
264
+
265
+/**
266
+* These are sample debug features to demonstrate the usage of the 8x8 LED Matrix for debug purposes.
267
+* There is very little CPU burden added to the system by displaying information within the idle()
268
+* task.
269
+*
270
+* But with that said, if your debugging can be facilitated by making calls into the library from
271
+* other places in the code, feel free to do it.  The CPU burden for a few calls to toggle an LED
272
+* or clear a row is not very significant.
273
+*/
274
+void Max7219_idle_tasks() {
275
+#if MAX7219_DEBUG_STEPPER_HEAD || MAX7219_DEBUG_STEPPER_TAIL || MAX7219_DEBUG_STEPPER_QUEUE
276
+  CRITICAL_SECTION_START
277
+  #if MAX7219_DEBUG_STEPPER_HEAD || MAX7219_DEBUG_STEPPER_QUEUE
278
+    const uint8_t head = planner.block_buffer_head;
279
+  #endif
280
+  #if MAX7219_DEBUG_STEPPER_TAIL || MAX7219_DEBUG_STEPPER_QUEUE
281
+    const uint8_t tail = planner.block_buffer_tail;
282
+  #endif
283
+  CRITICAL_SECTION_END
284
+#endif
285
+
286
+  #if ENABLED(MAX7219_DEBUG_PRINTER_ALIVE)
287
+    static millis_t next_blink = 0;
288
+    if (ELAPSED(millis(), next_blink)) {
289
+      Max7219_LED_Toggle(7, 7);
290
+      next_blink = millis() + 750;
291
+    }
292
+  #endif
293
+
294
+  #ifdef MAX7219_DEBUG_STEPPER_HEAD
295
+    static int16_t last_head_cnt = 0;
296
+    if (last_head_cnt != head) {
297
+      if (last_head_cnt < 8)
298
+        Max7219_LED_Off(last_head_cnt, MAX7219_DEBUG_STEPPER_HEAD);
299
+      else
300
+        Max7219_LED_Off(last_head_cnt - 8, MAX7219_DEBUG_STEPPER_HEAD + 1);
301
+
302
+      last_head_cnt = head;
303
+      if (head < 8)
304
+        Max7219_LED_On(head, MAX7219_DEBUG_STEPPER_HEAD);
305
+      else
306
+        Max7219_LED_On(head - 8, MAX7219_DEBUG_STEPPER_HEAD + 1);
307
+    }
308
+  #endif
309
+
310
+  #ifdef MAX7219_DEBUG_STEPPER_TAIL
311
+    static int16_t last_tail_cnt = 0;
312
+    if (last_tail_cnt != tail) {
313
+      if (last_tail_cnt < 8)
314
+        Max7219_LED_Off(last_tail_cnt, MAX7219_DEBUG_STEPPER_TAIL);
315
+      else
316
+        Max7219_LED_Off(last_tail_cnt - 8, MAX7219_DEBUG_STEPPER_TAIL + 1);
317
+
318
+      last_tail_cnt = tail;
319
+      if (tail < 8)
320
+        Max7219_LED_On(tail, MAX7219_DEBUG_STEPPER_TAIL);
321
+      else
322
+        Max7219_LED_On(tail - 8, MAX7219_DEBUG_STEPPER_TAIL + 1);
323
+    }
324
+  #endif
325
+
326
+  #ifdef MAX7219_DEBUG_STEPPER_QUEUE
327
+    static int16_t last_depth = 0;
328
+    int16_t current_depth = head - tail;
329
+    if (current_depth != last_depth) {  // usually, no update will be needed.
330
+      if (current_depth < 0) current_depth += BLOCK_BUFFER_SIZE;
331
+      NOMORE(current_depth, BLOCK_BUFFER_SIZE);
332
+      NOMORE(current_depth, 16);        // if the BLOCK_BUFFER_SIZE is greater than 16, two lines
333
+                                        // of LEDs is enough to see if the buffer is draining
334
+
335
+      const uint8_t st = min(current_depth, last_depth),
336
+                    en = max(current_depth, last_depth);
337
+      if (current_depth < last_depth)
338
+        for (uint8_t i = st; i <= en; i++)   // clear the highest order LEDs
339
+          Max7219_LED_Off(i / 2, MAX7219_DEBUG_STEPPER_QUEUE + (i & 1));
340
+      else
341
+        for (uint8_t i = st; i <= en; i++)   // set the LEDs to current depth
342
+          Max7219_LED_On(i / 2, MAX7219_DEBUG_STEPPER_QUEUE + (i & 1));
343
+
344
+      last_depth = current_depth;
345
+    }
346
+  #endif
347
+}
348
+
349
+#endif // MAX7219_DEBUG

+ 90
- 0
Marlin/Max7219_Debug_LEDs.h 파일 보기

@@ -0,0 +1,90 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 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
+/**
24
+ * This module is off by default, but can be enabled to facilitate the display of
25
+ * extra debug information during code development. It assumes the existence of a
26
+ * Max7219 LED Matrix. A suitable device can be obtained on eBay similar to this:
27
+ * http://www.ebay.com/itm/191781645249 for under $2.00 including shipping.
28
+ *
29
+ * Just connect up +5v and GND to give it power, then connect up the pins assigned
30
+ * in Configuration_adv.h. For example, on the Re-ARM you could use:
31
+ *
32
+ *   #define MAX7219_CLK_PIN   77
33
+ *   #define MAX7219_DIN_PIN   78
34
+ *   #define MAX7219_LOAD_PIN  79
35
+ *
36
+ * Max7219_init() is called automatically at startup, and then there are a number of
37
+ * support functions available to control the LEDs in the 8x8 grid.
38
+ *
39
+ * void Max7219_init();
40
+ * void Max7219_PutByte(uint8_t data);
41
+ * void Max7219(uint8_t reg, uint8_t data);
42
+ * void Max7219_LED_Set(uint8_t row, uint8_t col, bool on);
43
+ * void Max7219_LED_On(uint8_t col, uint8_t row);
44
+ * void Max7219_LED_Off(uint8_t col, uint8_t row);
45
+ * void Max7219_LED_Toggle(uint8_t row, uint8_t col);
46
+ * void Max7219_Clear_Row(uint8_t row);
47
+ * void Max7219_Clear_Column(uint8_t col);
48
+ * void Max7219_Set_Row(uint8_t row, uint8_t val);
49
+ * void Max7219_Set_2_Rows(uint8_t row, uint16_t val);
50
+ * void Max7219_Set_4_Rows(uint8_t row, uint32_t val);
51
+ * void Max7219_Set_Column(uint8_t col, uint8_t val);
52
+ * void Max7219_idle_tasks();
53
+ */
54
+
55
+#ifndef __MAX7219_DEBUG_LEDS_H__
56
+#define __MAX7219_DEBUG_LEDS_H__
57
+
58
+//
59
+// define max7219 registers
60
+//
61
+#define max7219_reg_noop        0x00
62
+#define max7219_reg_digit0      0x01
63
+#define max7219_reg_digit1      0x02
64
+#define max7219_reg_digit2      0x03
65
+#define max7219_reg_digit3      0x04
66
+#define max7219_reg_digit4      0x05
67
+#define max7219_reg_digit5      0x06
68
+#define max7219_reg_digit6      0x07
69
+#define max7219_reg_digit7      0x08
70
+
71
+#define max7219_reg_intensity   0x0A
72
+#define max7219_reg_displayTest 0x0F
73
+#define max7219_reg_decodeMode  0x09
74
+#define max7219_reg_scanLimit   0x0B
75
+#define max7219_reg_shutdown    0x0C
76
+
77
+void Max7219_init();
78
+void Max7219_PutByte(uint8_t data);
79
+void Max7219(const uint8_t reg, const uint8_t data);
80
+void Max7219_LED_Set(const uint8_t row, const uint8_t col, const bool on);
81
+void Max7219_LED_On(const uint8_t row, const uint8_t col);
82
+void Max7219_LED_Off(const uint8_t row, const uint8_t col);
83
+void Max7219_LED_Toggle(const uint8_t row, const uint8_t col);
84
+void Max7219_Clear_Row(const uint8_t row);
85
+void Max7219_Clear_Column(const uint8_t col);
86
+void Max7219_Set_Row(const uint8_t row, const uint8_t val);
87
+void Max7219_Set_Column(const uint8_t col, const uint8_t val);
88
+void Max7219_idle_tasks();
89
+
90
+#endif // __MAX7219_DEBUG_LEDS_H__

+ 371
- 110
Marlin/SanityCheck.h 파일 보기

@@ -50,7 +50,9 @@
50 50
 /**
51 51
  * Warnings for old configurations
52 52
  */
53
-#if WATCH_TEMP_PERIOD > 500
53
+#if !defined(X_BED_SIZE) || !defined(Y_BED_SIZE)
54
+  #error "X_BED_SIZE and Y_BED_SIZE are now required! Please update your configuration."
55
+#elif WATCH_TEMP_PERIOD > 500
54 56
   #error "WATCH_TEMP_PERIOD now uses seconds instead of milliseconds."
55 57
 #elif DISABLED(THERMAL_PROTECTION_HOTENDS) && (defined(WATCH_TEMP_PERIOD) || defined(THERMAL_PROTECTION_PERIOD))
56 58
   #error "Thermal Runaway Protection for hotends is now enabled with THERMAL_PROTECTION_HOTENDS."
@@ -76,8 +78,6 @@
76 78
   #error "FILAMENT_SENSOR is deprecated. Use FILAMENT_WIDTH_SENSOR instead."
77 79
 #elif defined(DISABLE_MAX_ENDSTOPS) || defined(DISABLE_MIN_ENDSTOPS)
78 80
   #error "DISABLE_MAX_ENDSTOPS and DISABLE_MIN_ENDSTOPS deprecated. Use individual USE_*_PLUG options instead."
79
-#elif ENABLED(Z_DUAL_ENDSTOPS) && !defined(Z2_USE_ENDSTOP)
80
-  #error "Z_DUAL_ENDSTOPS settings are simplified. Just set Z2_USE_ENDSTOP to the endstop you want to repurpose for Z2."
81 81
 #elif defined(LANGUAGE_INCLUDE)
82 82
   #error "LANGUAGE_INCLUDE has been replaced by LCD_LANGUAGE. Please update your configuration."
83 83
 #elif defined(EXTRUDER_OFFSET_X) || defined(EXTRUDER_OFFSET_Y)
@@ -180,10 +180,12 @@
180 180
   #error "MESH_NUM_[XY]_POINTS is now GRID_MAX_POINTS_[XY]. Please update your configuration."
181 181
 #elif defined(UBL_MESH_NUM_X_POINTS) || defined(UBL_MESH_NUM_Y_POINTS)
182 182
   #error "UBL_MESH_NUM_[XY]_POINTS is now GRID_MAX_POINTS_[XY]. Please update your configuration."
183
+#elif defined(UBL_G26_MESH_VALIDATION)
184
+  #error "UBL_G26_MESH_VALIDATION is now G26_MESH_VALIDATION. Please update your configuration."
183 185
 #elif defined(UBL_MESH_EDIT_ENABLED)
184
-  #error "UBL_MESH_EDIT_ENABLED is now UBL_G26_MESH_VALIDATION. Please update your configuration."
186
+  #error "UBL_MESH_EDIT_ENABLED is now G26_MESH_VALIDATION. Please update your configuration."
185 187
 #elif defined(UBL_MESH_EDITING)
186
-  #error "UBL_MESH_EDITING is now UBL_G26_MESH_VALIDATION. Please update your configuration."
188
+  #error "UBL_MESH_EDITING is now G26_MESH_VALIDATION. Please update your configuration."
187 189
 #elif defined(BLTOUCH_HEATERS_OFF)
188 190
   #error "BLTOUCH_HEATERS_OFF is now PROBING_HEATERS_OFF. Please update your configuration."
189 191
 #elif defined(BEEPER)
@@ -204,6 +206,28 @@
204 206
   #error "Replace SLED_PIN with SOL1_PIN (applies to both Z_PROBE_SLED and SOLENOID_PROBE)."
205 207
 #elif defined(CONTROLLERFAN_PIN)
206 208
   #error "CONTROLLERFAN_PIN is now CONTROLLER_FAN_PIN, enabled with USE_CONTROLLER_FAN. Please update your Configuration_adv.h."
209
+#elif defined(MIN_RETRACT)
210
+  #error "MIN_RETRACT is now MIN_AUTORETRACT and MAX_AUTORETRACT. Please update your Configuration_adv.h."
211
+#elif defined(ADVANCE)
212
+  #error "ADVANCE was removed in Marlin 1.1.6. Please use LIN_ADVANCE."
213
+#elif defined(NEOPIXEL_RGBW_LED)
214
+  #error "NEOPIXEL_RGBW_LED is now NEOPIXEL_LED. Please update your configuration."
215
+#elif defined(UBL_MESH_INSET)
216
+  #error "UBL_MESH_INSET is now just MESH_INSET. Please update your configuration."
217
+#elif defined(UBL_MESH_MIN_X) || defined(UBL_MESH_MIN_Y) || defined(UBL_MESH_MAX_X)  || defined(UBL_MESH_MAX_Y)
218
+  #error "UBL_MESH_(MIN|MAX)_[XY] is now just MESH_(MIN|MAX)_[XY]. Please update your configuration."
219
+#elif defined(ENABLE_MESH_EDIT_GFX_OVERLAY)
220
+  #error "ENABLE_MESH_EDIT_GFX_OVERLAY is now MESH_EDIT_GFX_OVERLAY. Please update your configuration."
221
+#elif defined(BABYSTEP_ZPROBE_GFX_REVERSE)
222
+  #error "BABYSTEP_ZPROBE_GFX_REVERSE is now set by OVERLAY_GFX_REVERSE. Please update your configurations."
223
+#elif defined(UBL_GRANULAR_SEGMENTATION_FOR_CARTESIAN)
224
+  #error "UBL_GRANULAR_SEGMENTATION_FOR_CARTESIAN is now SEGMENT_LEVELED_MOVES. Please update your configuration."
225
+#elif HAS_PID_HEATING && (defined(K1) || !defined(PID_K1))
226
+  #error "K1 is now PID_K1. Please update your configuration."
227
+#elif defined(PROBE_DOUBLE_TOUCH)
228
+  #error "PROBE_DOUBLE_TOUCH is now MULTIPLE_PROBING. Please update your configuration."
229
+#elif defined(ANET_KEYPAD_LCD)
230
+  #error "ANET_KEYPAD_LCD is now ZONESTAR_LCD. Please update your configuration."
207 231
 #endif
208 232
 
209 233
 /**
@@ -228,6 +252,13 @@
228 252
 #endif
229 253
 
230 254
 /**
255
+ * Serial
256
+ */
257
+#if defined(USBCON) && ENABLED(SERIAL_XON_XOFF)
258
+  #error "SERIAL_XON_XOFF is not supported on USB-native AVR devices."
259
+#endif
260
+
261
+/**
231 262
  * Dual Stepper Drivers
232 263
  */
233 264
 #if ENABLED(X_DUAL_STEPPER_DRIVERS) && ENABLED(DUAL_X_CARRIAGE)
@@ -241,16 +272,45 @@
241 272
 #endif
242 273
 
243 274
 /**
275
+ * Validate that the bed size fits
276
+ */
277
+static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
278
+  "Movement bounds ([XY]_MIN_POS, [XY]_MAX_POS) are too narrow to contain [XY]_BED_SIZE.");
279
+
280
+/**
281
+ * Granular software endstops (Marlin >= 1.1.7)
282
+ */
283
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS) && DISABLED(MIN_SOFTWARE_ENDSTOP_Z)
284
+  #if IS_KINEMATIC
285
+    #error "MIN_SOFTWARE_ENDSTOPS on DELTA/SCARA also requires MIN_SOFTWARE_ENDSTOP_Z."
286
+  #elif DISABLED(MIN_SOFTWARE_ENDSTOP_X) && DISABLED(MIN_SOFTWARE_ENDSTOP_Y)
287
+    #error "MIN_SOFTWARE_ENDSTOPS requires at least one of the MIN_SOFTWARE_ENDSTOP_[XYZ] options."
288
+  #endif
289
+#endif
290
+
291
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS) && DISABLED(MAX_SOFTWARE_ENDSTOP_Z)
292
+  #if IS_KINEMATIC
293
+    #error "MAX_SOFTWARE_ENDSTOPS on DELTA/SCARA also requires MAX_SOFTWARE_ENDSTOP_Z."
294
+  #elif DISABLED(MAX_SOFTWARE_ENDSTOP_X) && DISABLED(MAX_SOFTWARE_ENDSTOP_Y)
295
+    #error "MAX_SOFTWARE_ENDSTOPS requires at least one of the MAX_SOFTWARE_ENDSTOP_[XYZ] options."
296
+  #endif
297
+#endif
298
+
299
+/**
244 300
  * Progress Bar
245 301
  */
246 302
 #if ENABLED(LCD_PROGRESS_BAR)
247 303
   #if DISABLED(SDSUPPORT)
248 304
     #error "LCD_PROGRESS_BAR requires SDSUPPORT."
305
+  #elif DISABLED(ULTRA_LCD)
306
+    #error "LCD_PROGRESS_BAR requires a character LCD."
249 307
   #elif ENABLED(DOGLCD)
250 308
     #error "LCD_PROGRESS_BAR does not apply to graphical displays."
251 309
   #elif ENABLED(FILAMENT_LCD_DISPLAY)
252 310
     #error "LCD_PROGRESS_BAR and FILAMENT_LCD_DISPLAY are not fully compatible. Comment out this line to use both."
253 311
   #endif
312
+#elif ENABLED(LCD_SET_PROGRESS_MANUALLY) && DISABLED(DOGLCD)
313
+  #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR or Graphical LCD."
254 314
 #endif
255 315
 
256 316
 /**
@@ -268,6 +328,16 @@
268 328
       #error "SDSORT_CACHE_NAMES requires SDSORT_USES_RAM (which reads the directory into RAM)."
269 329
     #endif
270 330
   #endif
331
+
332
+  #if ENABLED(SDSORT_CACHE_NAMES) && DISABLED(SDSORT_DYNAMIC_RAM)
333
+    #if SDSORT_CACHE_VFATS < 2
334
+      #error "SDSORT_CACHE_VFATS must be 2 or greater!"
335
+    #elif SDSORT_CACHE_VFATS > MAX_VFAT_ENTRIES
336
+      #undef SDSORT_CACHE_VFATS
337
+      #define SDSORT_CACHE_VFATS MAX_VFAT_ENTRIES
338
+      #warning "SDSORT_CACHE_VFATS was reduced to MAX_VFAT_ENTRIES!"
339
+    #endif
340
+  #endif
271 341
 #endif
272 342
 
273 343
 /**
@@ -291,10 +361,14 @@
291 361
     #error "BABYSTEPPING is not implemented for SCARA yet."
292 362
   #elif ENABLED(DELTA) && ENABLED(BABYSTEP_XY)
293 363
     #error "BABYSTEPPING only implemented for Z axis on deltabots."
294
-  #elif ENABLED(BABYSTEP_ZPROBE_OFFSET) &&  ENABLED(MESH_BED_LEVELING)
364
+  #elif ENABLED(BABYSTEP_ZPROBE_OFFSET) && ENABLED(MESH_BED_LEVELING)
295 365
     #error "MESH_BED_LEVELING and BABYSTEP_ZPROBE_OFFSET is not a valid combination"
296 366
   #elif ENABLED(BABYSTEP_ZPROBE_OFFSET) && !HAS_BED_PROBE
297 367
     #error "BABYSTEP_ZPROBE_OFFSET requires a probe."
368
+  #elif ENABLED(BABYSTEP_ZPROBE_GFX_OVERLAY) && !ENABLED(DOGLCD)
369
+    #error "BABYSTEP_ZPROBE_GFX_OVERLAY requires a DOGLCD."
370
+  #elif ENABLED(BABYSTEP_ZPROBE_GFX_OVERLAY) && !ENABLED(BABYSTEP_ZPROBE_OFFSET)
371
+    #error "BABYSTEP_ZPROBE_GFX_OVERLAY requires a BABYSTEP_ZPROBE_OFFSET."
298 372
   #endif
299 373
 #endif
300 374
 
@@ -407,6 +481,44 @@
407 481
 #endif
408 482
 
409 483
 /**
484
+ * Parking Extruder requirements
485
+ */
486
+#if ENABLED(PARKING_EXTRUDER)
487
+  #if ENABLED(DUAL_X_CARRIAGE)
488
+    #error "PARKING_EXTRUDER and DUAL_X_CARRIAGE are incompatible."
489
+  #elif ENABLED(SINGLENOZZLE)
490
+    #error "PARKING_EXTRUDER and SINGLENOZZLE are incompatible."
491
+  #elif ENABLED(EXT_SOLENOID)
492
+    #error "PARKING_EXTRUDER and EXT_SOLENOID are incompatible. (Pins are used twice.)"
493
+  #elif EXTRUDERS != 2
494
+    #error "PARKING_EXTRUDER requires exactly 2 EXTRUDERS."
495
+  #elif !PIN_EXISTS(SOL0) || !PIN_EXISTS(SOL1)
496
+    #error "PARKING_EXTRUDER requires SOL0_PIN and SOL1_PIN."
497
+  #elif !defined(PARKING_EXTRUDER_PARKING_X)
498
+    #error "PARKING_EXTRUDER requires PARKING_EXTRUDER_PARKING_X."
499
+  #elif !defined(PARKING_EXTRUDER_SECURITY_RAISE)
500
+    #error "PARKING_EXTRUDER requires PARKING_EXTRUDER_SECURITY_RAISE."
501
+  #elif PARKING_EXTRUDER_SECURITY_RAISE < 0
502
+    #error "PARKING_EXTRUDER_SECURITY_RAISE must be 0 or higher."
503
+  #elif !defined(PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE) || !WITHIN(PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE, LOW, HIGH)
504
+    #error "PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE must be defined as HIGH or LOW."
505
+  #elif !defined(PARKING_EXTRUDER_SOLENOIDS_DELAY) || !WITHIN(PARKING_EXTRUDER_SOLENOIDS_DELAY, 0, 2000)
506
+    #error "PARKING_EXTRUDER_SOLENOIDS_DELAY must be between 0 and 2000 (ms)."
507
+  #endif
508
+#endif
509
+
510
+/**
511
+ * Part-Cooling Fan Multiplexer requirements
512
+ */
513
+#if PIN_EXISTS(FANMUX1)
514
+  #if !HAS_FANMUX
515
+    #error "FANMUX0_PIN must be set before FANMUX1_PIN can be set."
516
+  #endif
517
+#elif PIN_EXISTS(FANMUX2)
518
+  #error "FANMUX0_PIN and FANMUX1_PIN must be set before FANMUX2_PIN can be set."
519
+#endif
520
+
521
+/**
410 522
  * Limited number of servos
411 523
  */
412 524
 #if NUM_SERVOS > 4
@@ -414,10 +526,10 @@
414 526
 #endif
415 527
 
416 528
 /**
417
- * Servo deactivation depends on servo endstops or switching nozzle
529
+ * Servo deactivation depends on servo endstops, switching nozzle, or switching extruder
418 530
  */
419
-#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) && !HAS_Z_SERVO_ENDSTOP && !defined(SWITCHING_NOZZLE_SERVO_NR)
420
-  #error "Z_ENDSTOP_SERVO_NR or switching nozzle is required for DEACTIVATE_SERVOS_AFTER_MOVE."
531
+#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) && !HAS_Z_SERVO_ENDSTOP && !defined(SWITCHING_NOZZLE_SERVO_NR) && !defined(SWITCHING_EXTRUDER_SERVO_NR)
532
+  #error "Z_ENDSTOP_SERVO_NR, switching nozzle, or switching extruder is required for DEACTIVATE_SERVOS_AFTER_MOVE."
421 533
 #endif
422 534
 
423 535
 /**
@@ -476,14 +588,14 @@ static_assert(1 >= 0
476 588
  * Delta requirements
477 589
  */
478 590
 #if ENABLED(DELTA)
479
-  #if DISABLED(USE_XMAX_PLUG) && DISABLED(USE_YMAX_PLUG) && DISABLED(USE_ZMAX_PLUG)
591
+  #if HAS_BED_PROBE && ENABLED(Z_MIN_PROBE_ENDSTOP)
592
+    #error "Delta probably shouldn't use Z_MIN_PROBE_ENDSTOP. Comment out this line to continue."
593
+  #elif DISABLED(USE_XMAX_PLUG) && DISABLED(USE_YMAX_PLUG) && DISABLED(USE_ZMAX_PLUG)
480 594
     #error "You probably want to use Max Endstops for DELTA!"
481
-  #elif ENABLED(ENABLE_LEVELING_FADE_HEIGHT) && DISABLED(AUTO_BED_LEVELING_BILINEAR) && !UBL_DELTA
595
+  #elif ENABLED(ENABLE_LEVELING_FADE_HEIGHT) && DISABLED(AUTO_BED_LEVELING_BILINEAR) && !UBL_SEGMENTED
482 596
     #error "ENABLE_LEVELING_FADE_HEIGHT on DELTA requires AUTO_BED_LEVELING_BILINEAR or AUTO_BED_LEVELING_UBL."
483
-  #elif ENABLED(DELTA_AUTO_CALIBRATION) && !PROBE_SELECTED
484
-    #error "DELTA_AUTO_CALIBRATION requires a probe: PROBE_MANUALLY, FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, Z Servo."
485
-  #elif ENABLED(DELTA_AUTO_CALIBRATION) && ENABLED(PROBE_MANUALLY) && DISABLED(ULTIPANEL)
486
-    #error "DELTA_AUTO_CALIBRATION requires an LCD controller with PROBE_MANUALLY."
597
+  #elif ENABLED(DELTA_AUTO_CALIBRATION) && !(HAS_BED_PROBE || ENABLED(ULTIPANEL))
598
+    #error "DELTA_AUTO_CALIBRATION requires either a probe or an LCD Controller."
487 599
   #elif ABL_GRID
488 600
     #if (GRID_MAX_POINTS_X & 1) == 0 || (GRID_MAX_POINTS_Y & 1) == 0
489 601
       #error "DELTA requires GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y to be odd numbers."
@@ -525,7 +637,7 @@ static_assert(1 >= 0
525 637
   , "Please enable only one probe option: PROBE_MANUALLY, FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or Z Servo."
526 638
 );
527 639
 
528
-#if PROBE_SELECTED
640
+#if HAS_BED_PROBE
529 641
 
530 642
   /**
531 643
    * Z_PROBE_SLED is incompatible with DELTA
@@ -573,14 +685,14 @@ static_assert(1 >= 0
573 685
     #if !HAS_Z_MIN_PROBE_PIN
574 686
       #error "Z_MIN_PROBE_ENDSTOP requires the Z_MIN_PROBE_PIN to be defined."
575 687
     #endif
576
-  #elif DISABLED(PROBE_MANUALLY)
688
+  #else
577 689
     #error "You must enable either Z_MIN_PROBE_ENDSTOP or Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use a probe."
578 690
   #endif
579 691
 
580 692
   /**
581 693
    * Make sure Z raise values are set
582 694
    */
583
-  #if !defined(Z_CLEARANCE_DEPLOY_PROBE)
695
+  #ifndef Z_CLEARANCE_DEPLOY_PROBE
584 696
     #error "You must define Z_CLEARANCE_DEPLOY_PROBE in your configuration."
585 697
   #elif !defined(Z_CLEARANCE_BETWEEN_PROBES)
586 698
     #error "You must define Z_CLEARANCE_BETWEEN_PROBES in your configuration."
@@ -590,23 +702,23 @@ static_assert(1 >= 0
590 702
     #error "Probes need Z_CLEARANCE_BETWEEN_PROBES >= 0."
591 703
   #endif
592 704
 
705
+  #if MULTIPLE_PROBING && MULTIPLE_PROBING < 2
706
+    #error "MULTIPLE_PROBING must be >= 2."
707
+  #endif
708
+
593 709
 #else
594 710
 
595 711
   /**
596 712
    * Require some kind of probe for bed leveling and probe testing
597 713
    */
598
-  #if HAS_ABL
599
-    #if ENABLED(AUTO_BED_LEVELING_UBL)
600
-      #error "Unified Bed Leveling requires a probe: FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or Z Servo."
601
-    #else
602
-      #error "Auto Bed Leveling requires one of these: PROBE_MANUALLY, FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or a Z Servo."
603
-    #endif
714
+  #if OLDSCHOOL_ABL && !PROBE_SELECTED
715
+    #error "Auto Bed Leveling requires one of these: PROBE_MANUALLY, FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or a Z Servo."
604 716
   #endif
605 717
 
606
-#endif
718
+  #if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST)
719
+    #error "Z_MIN_PROBE_REPEATABILITY_TEST requires a probe: FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or Z Servo."
720
+  #endif
607 721
 
608
-#if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) && !HAS_BED_PROBE
609
-  #error "Z_MIN_PROBE_REPEATABILITY_TEST requires a probe: FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or Z Servo."
610 722
 #endif
611 723
 
612 724
 /**
@@ -641,6 +753,9 @@ static_assert(1 >= 0
641 753
    * Unified Bed Leveling
642 754
    */
643 755
 
756
+  // Hide PROBE_MANUALLY from the rest of the code
757
+  #undef PROBE_MANUALLY
758
+
644 759
   #if IS_SCARA
645 760
     #error "AUTO_BED_LEVELING_UBL does not yet support SCARA printers."
646 761
   #elif DISABLED(EEPROM_SETTINGS)
@@ -656,7 +771,7 @@ static_assert(1 >= 0
656 771
     static_assert(WITHIN(UBL_PROBE_PT_3_Y, MIN_PROBE_Y, MAX_PROBE_Y), "UBL_PROBE_PT_3_Y can't be reached by the Z probe.");
657 772
   #endif
658 773
 
659
-#elif HAS_ABL
774
+#elif OLDSCHOOL_ABL
660 775
 
661 776
   /**
662 777
    * Auto Bed Leveling
@@ -705,26 +820,37 @@ static_assert(1 >= 0
705 820
 
706 821
 #elif ENABLED(MESH_BED_LEVELING)
707 822
 
823
+  // Hide PROBE_MANUALLY from the rest of the code
824
+  #undef PROBE_MANUALLY
825
+
708 826
   /**
709 827
    * Mesh Bed Leveling
710 828
    */
711 829
 
712 830
   #if ENABLED(DELTA)
713
-    #error "MESH_BED_LEVELING does not yet support DELTA printers."
831
+    #error "MESH_BED_LEVELING is not compatible with DELTA printers."
714 832
   #elif GRID_MAX_POINTS_X > 9 || GRID_MAX_POINTS_Y > 9
715 833
     #error "GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y must be less than 10 for MBL."
716 834
   #endif
717 835
 
718 836
 #endif
719 837
 
838
+#if !HAS_MESH && ENABLED(G26_MESH_VALIDATION)
839
+  #error "G26_MESH_VALIDATION requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_UBL."
840
+#endif
841
+
842
+#if ENABLED(MESH_EDIT_GFX_OVERLAY) && (DISABLED(AUTO_BED_LEVELING_UBL) || DISABLED(DOGLCD))
843
+  #error "MESH_EDIT_GFX_OVERLAY requires AUTO_BED_LEVELING_UBL and a Graphical LCD."
844
+#endif
845
+
720 846
 /**
721 847
  * LCD_BED_LEVELING requirements
722 848
  */
723 849
 #if ENABLED(LCD_BED_LEVELING)
724 850
   #if DISABLED(ULTIPANEL)
725 851
     #error "LCD_BED_LEVELING requires an LCD controller."
726
-  #elif DISABLED(MESH_BED_LEVELING) && !(HAS_ABL && ENABLED(PROBE_MANUALLY))
727
-    #error "LCD_BED_LEVELING requires MESH_BED_LEVELING or PROBE_MANUALLY."
852
+  #elif !(ENABLED(MESH_BED_LEVELING) || (OLDSCHOOL_ABL && ENABLED(PROBE_MANUALLY)))
853
+    #error "LCD_BED_LEVELING requires MESH_BED_LEVELING or ABL with PROBE_MANUALLY."
728 854
   #endif
729 855
 #endif
730 856
 
@@ -764,13 +890,6 @@ static_assert(1 >= 0
764 890
 #endif // DISABLE_[XYZ]
765 891
 
766 892
 /**
767
- * Advance Extrusion
768
- */
769
-#if ENABLED(ADVANCE) && ENABLED(LIN_ADVANCE)
770
-  #error "You can enable ADVANCE or LIN_ADVANCE, but not both."
771
-#endif
772
-
773
-/**
774 893
  * Filament Width Sensor
775 894
  */
776 895
 #if ENABLED(FILAMENT_WIDTH_SENSOR) && !HAS_FILAMENT_WIDTH_SENSOR
@@ -907,28 +1026,28 @@ static_assert(1 >= 0
907 1026
           #error "TEMP_4_PIN not defined for this board."
908 1027
         #endif
909 1028
       #elif TEMP_SENSOR_4 != 0
910
-        #error "TEMP_SENSOR_4 shouldn't be set with only 4 extruders."
1029
+        #error "TEMP_SENSOR_4 shouldn't be set with only 4 HOTENDS."
911 1030
       #endif
912 1031
     #elif TEMP_SENSOR_3 != 0
913
-      #error "TEMP_SENSOR_3 shouldn't be set with only 3 extruders."
1032
+      #error "TEMP_SENSOR_3 shouldn't be set with only 3 HOTENDS."
914 1033
     #elif TEMP_SENSOR_4 != 0
915
-      #error "TEMP_SENSOR_4 shouldn't be set with only 3 extruders."
1034
+      #error "TEMP_SENSOR_4 shouldn't be set with only 3 HOTENDS."
916 1035
     #endif
917 1036
   #elif TEMP_SENSOR_2 != 0
918
-    #error "TEMP_SENSOR_2 shouldn't be set with only 2 extruders."
1037
+    #error "TEMP_SENSOR_2 shouldn't be set with only 2 HOTENDS."
919 1038
   #elif TEMP_SENSOR_3 != 0
920
-    #error "TEMP_SENSOR_3 shouldn't be set with only 2 extruders."
1039
+    #error "TEMP_SENSOR_3 shouldn't be set with only 2 HOTENDS."
921 1040
   #elif TEMP_SENSOR_4 != 0
922
-    #error "TEMP_SENSOR_4 shouldn't be set with only 2 extruders."
1041
+    #error "TEMP_SENSOR_4 shouldn't be set with only 2 HOTENDS."
923 1042
   #endif
924 1043
 #elif TEMP_SENSOR_1 != 0 && DISABLED(TEMP_SENSOR_1_AS_REDUNDANT)
925
-  #error "TEMP_SENSOR_1 shouldn't be set with only 1 extruder."
1044
+  #error "TEMP_SENSOR_1 shouldn't be set with only 1 HOTEND."
926 1045
 #elif TEMP_SENSOR_2 != 0
927
-  #error "TEMP_SENSOR_2 shouldn't be set with only 1 extruder."
1046
+  #error "TEMP_SENSOR_2 shouldn't be set with only 1 HOTEND."
928 1047
 #elif TEMP_SENSOR_3 != 0
929
-  #error "TEMP_SENSOR_3 shouldn't be set with only 1 extruder."
1048
+  #error "TEMP_SENSOR_3 shouldn't be set with only 1 HOTEND."
930 1049
 #elif TEMP_SENSOR_4 != 0
931
-  #error "TEMP_SENSOR_4 shouldn't be set with only 1 extruder."
1050
+  #error "TEMP_SENSOR_4 shouldn't be set with only 1 HOTEND."
932 1051
 #endif
933 1052
 
934 1053
 #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) && TEMP_SENSOR_1 == 0
@@ -962,42 +1081,45 @@ static_assert(1 >= 0
962 1081
 /**
963 1082
  * Test Extruder Stepper Pins
964 1083
  */
965
-#if E_STEPPERS > 4
966
-  #if !PIN_EXISTS(E4_STEP) || !PIN_EXISTS(E4_DIR) || !PIN_EXISTS(E4_ENABLE)
967
-    #error "E4_STEP_PIN, E4_DIR_PIN, or E4_ENABLE_PIN not defined for this board."
968
-  #endif
969
-#elif E_STEPPERS > 3
970
-  #if !PIN_EXISTS(E3_STEP) || !PIN_EXISTS(E3_DIR) || !PIN_EXISTS(E3_ENABLE)
971
-    #error "E3_STEP_PIN, E3_DIR_PIN, or E3_ENABLE_PIN not defined for this board."
972
-  #endif
973
-#elif E_STEPPERS > 2
974
-  #if !PIN_EXISTS(E2_STEP) || !PIN_EXISTS(E2_DIR) || !PIN_EXISTS(E2_ENABLE)
975
-    #error "E2_STEP_PIN, E2_DIR_PIN, or E2_ENABLE_PIN not defined for this board."
976
-  #endif
977
-#elif E_STEPPERS > 1
978
-  #if !PIN_EXISTS(E1_STEP) || !PIN_EXISTS(E1_DIR) || !PIN_EXISTS(E1_ENABLE)
979
-    #error "E1_STEP_PIN, E1_DIR_PIN, or E1_ENABLE_PIN not defined for this board."
1084
+#if DISABLED(MK2_MULTIPLEXER) // MK2_MULTIPLEXER uses E0 stepper only
1085
+  #if E_STEPPERS > 4
1086
+    #if !PIN_EXISTS(E4_STEP) || !PIN_EXISTS(E4_DIR) || !PIN_EXISTS(E4_ENABLE)
1087
+      #error "E4_STEP_PIN, E4_DIR_PIN, or E4_ENABLE_PIN not defined for this board."
1088
+    #endif
1089
+  #elif E_STEPPERS > 3
1090
+    #if !PIN_EXISTS(E3_STEP) || !PIN_EXISTS(E3_DIR) || !PIN_EXISTS(E3_ENABLE)
1091
+      #error "E3_STEP_PIN, E3_DIR_PIN, or E3_ENABLE_PIN not defined for this board."
1092
+    #endif
1093
+  #elif E_STEPPERS > 2
1094
+    #if !PIN_EXISTS(E2_STEP) || !PIN_EXISTS(E2_DIR) || !PIN_EXISTS(E2_ENABLE)
1095
+      #error "E2_STEP_PIN, E2_DIR_PIN, or E2_ENABLE_PIN not defined for this board."
1096
+    #endif
1097
+  #elif E_STEPPERS > 1
1098
+    #if !PIN_EXISTS(E1_STEP) || !PIN_EXISTS(E1_DIR) || !PIN_EXISTS(E1_ENABLE)
1099
+      #error "E1_STEP_PIN, E1_DIR_PIN, or E1_ENABLE_PIN not defined for this board."
1100
+    #endif
980 1101
   #endif
981 1102
 #endif
982
-
983 1103
 /**
984
- * Endstops
1104
+ * Endstop Tests
985 1105
  */
986
-#if DISABLED(USE_XMIN_PLUG) && DISABLED(USE_XMAX_PLUG) && !(ENABLED(Z_DUAL_ENDSTOPS) && WITHIN(Z2_USE_ENDSTOP, _XMAX_, _XMIN_))
987
- #error "You must enable USE_XMIN_PLUG or USE_XMAX_PLUG."
988
-#elif DISABLED(USE_YMIN_PLUG) && DISABLED(USE_YMAX_PLUG) && !(ENABLED(Z_DUAL_ENDSTOPS) && WITHIN(Z2_USE_ENDSTOP, _YMAX_, _YMIN_))
989
- #error "You must enable USE_YMIN_PLUG or USE_YMAX_PLUG."
990
-#elif DISABLED(USE_ZMIN_PLUG) && DISABLED(USE_ZMAX_PLUG) && !(ENABLED(Z_DUAL_ENDSTOPS) && WITHIN(Z2_USE_ENDSTOP, _ZMAX_, _ZMIN_))
991
- #error "You must enable USE_ZMIN_PLUG or USE_ZMAX_PLUG."
992
-#elif ENABLED(Z_DUAL_ENDSTOPS)
993
-  #if !Z2_USE_ENDSTOP
994
-    #error "You must set Z2_USE_ENDSTOP with Z_DUAL_ENDSTOPS."
995
-  #elif Z2_MAX_PIN == 0 && Z2_MIN_PIN == 0
996
-    #error "Z2_USE_ENDSTOP has been assigned to a nonexistent endstop!"
997
-  #elif ENABLED(DELTA)
998
-    #error "Z_DUAL_ENDSTOPS is not compatible with DELTA."
999
-  #endif
1000
-#elif !IS_SCARA
1106
+
1107
+#define _PLUG_UNUSED_TEST(AXIS,PLUG) (DISABLED(USE_##PLUG##MIN_PLUG) && DISABLED(USE_##PLUG##MAX_PLUG) && !(ENABLED(AXIS##_DUAL_ENDSTOPS) && WITHIN(AXIS##2_USE_ENDSTOP, _##PLUG##MAX_, _##PLUG##MIN_)))
1108
+#define _AXIS_PLUG_UNUSED_TEST(AXIS) (_PLUG_UNUSED_TEST(AXIS,X) && _PLUG_UNUSED_TEST(AXIS,Y) && _PLUG_UNUSED_TEST(AXIS,Z))
1109
+
1110
+// At least 3 endstop plugs must be used
1111
+#if _AXIS_PLUG_UNUSED_TEST(X)
1112
+  #error "You must enable USE_XMIN_PLUG or USE_XMAX_PLUG."
1113
+#endif
1114
+#if _AXIS_PLUG_UNUSED_TEST(Y)
1115
+  #error "You must enable USE_YMIN_PLUG or USE_YMAX_PLUG."
1116
+#endif
1117
+#if _AXIS_PLUG_UNUSED_TEST(Z)
1118
+  #error "You must enable USE_ZMIN_PLUG or USE_ZMAX_PLUG."
1119
+#endif
1120
+
1121
+// Delta and Cartesian use 3 homing endstops
1122
+#if !IS_SCARA
1001 1123
   #if X_HOME_DIR < 0 && DISABLED(USE_XMIN_PLUG)
1002 1124
     #error "Enable USE_XMIN_PLUG when homing X to MIN."
1003 1125
   #elif X_HOME_DIR > 0 && DISABLED(USE_XMAX_PLUG)
@@ -1006,10 +1128,76 @@ static_assert(1 >= 0
1006 1128
     #error "Enable USE_YMIN_PLUG when homing Y to MIN."
1007 1129
   #elif Y_HOME_DIR > 0 && DISABLED(USE_YMAX_PLUG)
1008 1130
     #error "Enable USE_YMAX_PLUG when homing Y to MAX."
1009
-  #elif Z_HOME_DIR < 0 && DISABLED(USE_ZMIN_PLUG)
1010
-    #error "Enable USE_ZMIN_PLUG when homing Z to MIN."
1011
-  #elif Z_HOME_DIR > 0 && DISABLED(USE_ZMAX_PLUG)
1012
-    #error "Enable USE_ZMAX_PLUG when homing Z to MAX."
1131
+  #endif
1132
+#endif
1133
+#if Z_HOME_DIR < 0 && DISABLED(USE_ZMIN_PLUG)
1134
+  #error "Enable USE_ZMIN_PLUG when homing Z to MIN."
1135
+#elif Z_HOME_DIR > 0 && DISABLED(USE_ZMAX_PLUG)
1136
+  #error "Enable USE_ZMAX_PLUG when homing Z to MAX."
1137
+#endif
1138
+
1139
+// Dual endstops requirements
1140
+#if ENABLED(X_DUAL_ENDSTOPS)
1141
+  #if !X2_USE_ENDSTOP
1142
+    #error "You must set X2_USE_ENDSTOP with X_DUAL_ENDSTOPS."
1143
+  #elif X2_USE_ENDSTOP == _X_MIN_ && DISABLED(USE_XMIN_PLUG)
1144
+    #error "USE_XMIN_PLUG is required when X2_USE_ENDSTOP is _X_MIN_."
1145
+  #elif X2_USE_ENDSTOP == _X_MAX_ && DISABLED(USE_XMAX_PLUG)
1146
+    #error "USE_XMAX_PLUG is required when X2_USE_ENDSTOP is _X_MAX_."
1147
+  #elif X2_USE_ENDSTOP == _Y_MIN_ && DISABLED(USE_YMIN_PLUG)
1148
+    #error "USE_YMIN_PLUG is required when X2_USE_ENDSTOP is _Y_MIN_."
1149
+  #elif X2_USE_ENDSTOP == _Y_MAX_ && DISABLED(USE_YMAX_PLUG)
1150
+    #error "USE_YMAX_PLUG is required when X2_USE_ENDSTOP is _Y_MAX_."
1151
+  #elif X2_USE_ENDSTOP == _Z_MIN_ && DISABLED(USE_ZMIN_PLUG)
1152
+    #error "USE_ZMIN_PLUG is required when X2_USE_ENDSTOP is _Z_MIN_."
1153
+  #elif X2_USE_ENDSTOP == _Z_MAX_ && DISABLED(USE_ZMAX_PLUG)
1154
+    #error "USE_ZMAX_PLUG is required when X2_USE_ENDSTOP is _Z_MAX_."
1155
+  #elif !HAS_X2_MIN && !HAS_X2_MAX
1156
+    #error "X2_USE_ENDSTOP has been assigned to a nonexistent endstop!"
1157
+  #elif ENABLED(DELTA)
1158
+    #error "X_DUAL_ENDSTOPS is not compatible with DELTA."
1159
+  #endif
1160
+#endif
1161
+#if ENABLED(Y_DUAL_ENDSTOPS)
1162
+  #if !Y2_USE_ENDSTOP
1163
+    #error "You must set Y2_USE_ENDSTOP with Y_DUAL_ENDSTOPS."
1164
+  #elif Y2_USE_ENDSTOP == _X_MIN_ && DISABLED(USE_XMIN_PLUG)
1165
+    #error "USE_XMIN_PLUG is required when Y2_USE_ENDSTOP is _X_MIN_."
1166
+  #elif Y2_USE_ENDSTOP == _X_MAX_ && DISABLED(USE_XMAX_PLUG)
1167
+    #error "USE_XMAX_PLUG is required when Y2_USE_ENDSTOP is _X_MAX_."
1168
+  #elif Y2_USE_ENDSTOP == _Y_MIN_ && DISABLED(USE_YMIN_PLUG)
1169
+    #error "USE_YMIN_PLUG is required when Y2_USE_ENDSTOP is _Y_MIN_."
1170
+  #elif Y2_USE_ENDSTOP == _Y_MAX_ && DISABLED(USE_YMAX_PLUG)
1171
+    #error "USE_YMAX_PLUG is required when Y2_USE_ENDSTOP is _Y_MAX_."
1172
+  #elif Y2_USE_ENDSTOP == _Z_MIN_ && DISABLED(USE_ZMIN_PLUG)
1173
+    #error "USE_ZMIN_PLUG is required when Y2_USE_ENDSTOP is _Z_MIN_."
1174
+  #elif Y2_USE_ENDSTOP == _Z_MAX_ && DISABLED(USE_ZMAX_PLUG)
1175
+    #error "USE_ZMAX_PLUG is required when Y2_USE_ENDSTOP is _Z_MAX_."
1176
+  #elif !HAS_Y2_MIN && !HAS_Y2_MAX
1177
+    #error "Y2_USE_ENDSTOP has been assigned to a nonexistent endstop!"
1178
+  #elif ENABLED(DELTA)
1179
+    #error "Y_DUAL_ENDSTOPS is not compatible with DELTA."
1180
+  #endif
1181
+#endif
1182
+#if ENABLED(Z_DUAL_ENDSTOPS)
1183
+  #if !Z2_USE_ENDSTOP
1184
+    #error "You must set Z2_USE_ENDSTOP with Z_DUAL_ENDSTOPS."
1185
+  #elif Z2_USE_ENDSTOP == _X_MIN_ && DISABLED(USE_XMIN_PLUG)
1186
+    #error "USE_XMIN_PLUG is required when Z2_USE_ENDSTOP is _X_MIN_."
1187
+  #elif Z2_USE_ENDSTOP == _X_MAX_ && DISABLED(USE_XMAX_PLUG)
1188
+    #error "USE_XMAX_PLUG is required when Z2_USE_ENDSTOP is _X_MAX_."
1189
+  #elif Z2_USE_ENDSTOP == _Y_MIN_ && DISABLED(USE_YMIN_PLUG)
1190
+    #error "USE_YMIN_PLUG is required when Z2_USE_ENDSTOP is _Y_MIN_."
1191
+  #elif Z2_USE_ENDSTOP == _Y_MAX_ && DISABLED(USE_YMAX_PLUG)
1192
+    #error "USE_YMAX_PLUG is required when Z2_USE_ENDSTOP is _Y_MAX_."
1193
+  #elif Z2_USE_ENDSTOP == _Z_MIN_ && DISABLED(USE_ZMIN_PLUG)
1194
+    #error "USE_ZMIN_PLUG is required when Z2_USE_ENDSTOP is _Z_MIN_."
1195
+  #elif Z2_USE_ENDSTOP == _Z_MAX_ && DISABLED(USE_ZMAX_PLUG)
1196
+    #error "USE_ZMAX_PLUG is required when Z2_USE_ENDSTOP is _Z_MAX_."
1197
+  #elif !HAS_Z2_MIN && !HAS_Z2_MAX
1198
+    #error "Z2_USE_ENDSTOP has been assigned to a nonexistent endstop!"
1199
+  #elif ENABLED(DELTA)
1200
+    #error "Z_DUAL_ENDSTOPS is not compatible with DELTA."
1013 1201
   #endif
1014 1202
 #endif
1015 1203
 
@@ -1056,8 +1244,12 @@ static_assert(1 >= 0
1056 1244
   #if !(_RGB_TEST && PIN_EXISTS(RGB_LED_W))
1057 1245
     #error "RGBW_LED requires RGB_LED_R_PIN, RGB_LED_G_PIN, RGB_LED_B_PIN, and RGB_LED_W_PIN."
1058 1246
   #endif
1059
-#elif ENABLED(PRINTER_EVENT_LEDS) && DISABLED(BLINKM) && DISABLED(PCA9632)
1060
-  #error "PRINTER_EVENT_LEDS requires BLINKM, PCA9632, RGB_LED, or RGBW_LED."
1247
+#elif ENABLED(NEOPIXEL_LED)
1248
+  #if !(PIN_EXISTS(NEOPIXEL) && NEOPIXEL_PIXELS > 0)
1249
+    #error "NEOPIXEL_LED requires NEOPIXEL_PIN and NEOPIXEL_PIXELS."
1250
+  #endif
1251
+#elif ENABLED(PRINTER_EVENT_LEDS) && DISABLED(BLINKM) && DISABLED(PCA9632) && DISABLED(NEOPIXEL_LED)
1252
+  #error "PRINTER_EVENT_LEDS requires BLINKM, PCA9632, RGB_LED, RGBW_LED or NEOPIXEL_LED."
1061 1253
 #endif
1062 1254
 
1063 1255
 /**
@@ -1082,6 +1274,7 @@ static_assert(1 >= 0
1082 1274
  * Note: BQ_LCD_SMART_CONTROLLER => REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
1083 1275
  *       REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER => REPRAP_DISCOUNT_SMART_CONTROLLER
1084 1276
  *       SAV_3DGLCD => U8GLIB_SH1106 => ULTIMAKERCONTROLLER
1277
+ *       MKS_12864OLED => U8GLIB_SH1106 => ULTIMAKERCONTROLLER
1085 1278
  *       miniVIKI => ULTIMAKERCONTROLLER
1086 1279
  *       VIKI2 => ULTIMAKERCONTROLLER
1087 1280
  *       ELB_FULL_GRAPHIC_CONTROLLER => ULTIMAKERCONTROLLER
@@ -1089,19 +1282,34 @@ static_assert(1 >= 0
1089 1282
  */
1090 1283
 static_assert(1 >= 0
1091 1284
   #if ENABLED(ULTIMAKERCONTROLLER) \
1092
-      && DISABLED(SAV_3DGLCD) && DISABLED(miniVIKI) && DISABLED(VIKI2) \
1093
-      && DISABLED(ELB_FULL_GRAPHIC_CONTROLLER) && DISABLED(PANEL_ONE)
1285
+      && DISABLED(SAV_3DGLCD) \
1286
+      && DISABLED(miniVIKI) \
1287
+      && DISABLED(VIKI2) \
1288
+      && DISABLED(ELB_FULL_GRAPHIC_CONTROLLER) \
1289
+      && DISABLED(PANEL_ONE) \
1290
+      && DISABLED(MKS_12864OLED)
1094 1291
     + 1
1095 1292
   #endif
1096
-  #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) && DISABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
1293
+  #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) \
1294
+      && DISABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) \
1295
+      && DISABLED(LCD_FOR_MELZI) \
1296
+      && DISABLED(MAKEBOARD_MINI_2_LINE_DISPLAY_1602) \
1297
+      && DISABLED(MKS_12864OLED)
1097 1298
     + 1
1098 1299
   #endif
1099
-  #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) && DISABLED(BQ_LCD_SMART_CONTROLLER)
1300
+  #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) \
1301
+      && DISABLED(BQ_LCD_SMART_CONTROLLER)
1100 1302
     + 1
1101 1303
   #endif
1102 1304
   #if ENABLED(LCD_FOR_MELZI)
1103 1305
     + 1
1104 1306
   #endif
1307
+  #if ENABLED(MKS_12864OLED)
1308
+    + 1
1309
+  #endif
1310
+  #if ENABLED(MAKEBOARD_MINI_2_LINE_DISPLAY_1602)
1311
+    + 1
1312
+  #endif
1105 1313
   #if ENABLED(CARTESIO_UI)
1106 1314
     + 1
1107 1315
   #endif
@@ -1126,10 +1334,15 @@ static_assert(1 >= 0
1126 1334
   #if ENABLED(G3D_PANEL)
1127 1335
     + 1
1128 1336
   #endif
1129
-  #if ENABLED(MINIPANEL)
1337
+  #if ENABLED(MINIPANEL) && DISABLED(MKS_MINI_12864)
1130 1338
     + 1
1131 1339
   #endif
1132
-  #if ENABLED(REPRAPWORLD_KEYPAD) && DISABLED(CARTESIO_UI) && DISABLED(ANET_KEYPAD_LCD)
1340
+  #if ENABLED(MKS_MINI_12864)
1341
+    + 1
1342
+  #endif
1343
+  #if ENABLED(REPRAPWORLD_KEYPAD) \
1344
+      && DISABLED(CARTESIO_UI) \
1345
+      && DISABLED(ZONESTAR_LCD)
1133 1346
     + 1
1134 1347
   #endif
1135 1348
   #if ENABLED(RIGIDBOT_PANEL)
@@ -1165,7 +1378,7 @@ static_assert(1 >= 0
1165 1378
   #if ENABLED(OLED_PANEL_TINYBOY2)
1166 1379
     + 1
1167 1380
   #endif
1168
-  #if ENABLED(ANET_KEYPAD_LCD)
1381
+  #if ENABLED(ZONESTAR_LCD)
1169 1382
     + 1
1170 1383
   #endif
1171 1384
   , "Please select no more than one LCD controller option."
@@ -1193,23 +1406,45 @@ static_assert(1 >= 0
1193 1406
 /**
1194 1407
  * Make sure HAVE_TMC2130 is warranted
1195 1408
  */
1196
-#if ENABLED(HAVE_TMC2130)
1197
-  #if !( ENABLED(  X_IS_TMC2130 ) \
1198
-      || ENABLED( X2_IS_TMC2130 ) \
1199
-      || ENABLED(  Y_IS_TMC2130 ) \
1200
-      || ENABLED( Y2_IS_TMC2130 ) \
1201
-      || ENABLED(  Z_IS_TMC2130 ) \
1202
-      || ENABLED( Z2_IS_TMC2130 ) \
1203
-      || ENABLED( E0_IS_TMC2130 ) \
1204
-      || ENABLED( E1_IS_TMC2130 ) \
1205
-      || ENABLED( E2_IS_TMC2130 ) \
1206
-      || ENABLED( E3_IS_TMC2130 ) \
1207
-      || ENABLED( E4_IS_TMC2130 ) \
1208
-  )
1209
-    #error "HAVE_TMC2130 requires at least one TMC2130 stepper to be set."
1210
-  #elif ENABLED(HYBRID_THRESHOLD) && DISABLED(STEALTHCHOP)
1211
-    #error "Enable STEALTHCHOP to use HYBRID_THRESHOLD."
1212
-  #endif
1409
+#if ENABLED(HAVE_TMC2130) && !( \
1410
+       ENABLED(  X_IS_TMC2130 ) \
1411
+    || ENABLED( X2_IS_TMC2130 ) \
1412
+    || ENABLED(  Y_IS_TMC2130 ) \
1413
+    || ENABLED( Y2_IS_TMC2130 ) \
1414
+    || ENABLED(  Z_IS_TMC2130 ) \
1415
+    || ENABLED( Z2_IS_TMC2130 ) \
1416
+    || ENABLED( E0_IS_TMC2130 ) \
1417
+    || ENABLED( E1_IS_TMC2130 ) \
1418
+    || ENABLED( E2_IS_TMC2130 ) \
1419
+    || ENABLED( E3_IS_TMC2130 ) \
1420
+    || ENABLED( E4_IS_TMC2130 ) )
1421
+  #error "HAVE_TMC2130 requires at least one TMC2130 stepper to be set."
1422
+#elif ENABLED(SENSORLESS_HOMING) && DISABLED(HAVE_TMC2130)
1423
+  #error "Enable HAVE_TMC2130 to use SENSORLESS_HOMING."
1424
+#elif defined(AUTOMATIC_CURRENT_CONTROL)
1425
+  #error "AUTOMATIC_CURRENT_CONTROL is now MONITOR_DRIVER_STATUS. Please update your configuration."
1426
+#endif
1427
+
1428
+/**
1429
+ * Make sure HAVE_TMC2208 is warranted
1430
+ */
1431
+
1432
+#if ENABLED(HAVE_TMC2208) && !( \
1433
+       ENABLED(  X_IS_TMC2208 ) \
1434
+    || ENABLED( X2_IS_TMC2208 ) \
1435
+    || ENABLED(  Y_IS_TMC2208 ) \
1436
+    || ENABLED( Y2_IS_TMC2208 ) \
1437
+    || ENABLED(  Z_IS_TMC2208 ) \
1438
+    || ENABLED( Z2_IS_TMC2208 ) \
1439
+    || ENABLED( E0_IS_TMC2208 ) \
1440
+    || ENABLED( E1_IS_TMC2208 ) \
1441
+    || ENABLED( E2_IS_TMC2208 ) \
1442
+    || ENABLED( E3_IS_TMC2208 ) )
1443
+  #error "HAVE_TMC2208 requires at least one TMC2208 stepper to be set."
1444
+#endif
1445
+
1446
+#if ENABLED(HYBRID_THRESHOLD) && DISABLED(STEALTHCHOP)
1447
+  #error "Enable STEALTHCHOP to use HYBRID_THRESHOLD."
1213 1448
 #endif
1214 1449
 
1215 1450
 /**
@@ -1314,3 +1549,29 @@ static_assert(COUNT(sanity_arr_3) <= XYZE_N, "DEFAULT_MAX_ACCELERATION has too m
1314 1549
     #endif
1315 1550
   #endif
1316 1551
 #endif // SPINDLE_LASER_ENABLE
1552
+
1553
+#if ENABLED(CNC_COORDINATE_SYSTEMS) && ENABLED(NO_WORKSPACE_OFFSETS)
1554
+  #error "CNC_COORDINATE_SYSTEMS is incompatible with NO_WORKSPACE_OFFSETS."
1555
+#endif
1556
+
1557
+#if !BLOCK_BUFFER_SIZE || !IS_POWER_OF_2(BLOCK_BUFFER_SIZE)
1558
+  #error "BLOCK_BUFFER_SIZE must be a power of 2."
1559
+#endif
1560
+
1561
+#if ENABLED(LED_CONTROL_MENU) && DISABLED(ULTIPANEL)
1562
+  #error "LED_CONTROL_MENU requires an LCD controller."
1563
+#endif
1564
+
1565
+#if ENABLED(SKEW_CORRECTION)
1566
+  #if !defined(XY_SKEW_FACTOR) && !(defined(XY_DIAG_AC) && defined(XY_DIAG_BD) && defined(XY_SIDE_AD))
1567
+    #error "SKEW_CORRECTION requires XY_SKEW_FACTOR or XY_DIAG_AC, XY_DIAG_BD, XY_SIDE_AD."
1568
+  #endif
1569
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1570
+    #if !defined(XZ_SKEW_FACTOR) && !(defined(XZ_DIAG_AC) && defined(XZ_DIAG_BD) && defined(XZ_SIDE_AD))
1571
+      #error "SKEW_CORRECTION requires XZ_SKEW_FACTOR or XZ_DIAG_AC, XZ_DIAG_BD, XZ_SIDE_AD."
1572
+    #endif
1573
+    #if !defined(YZ_SKEW_FACTOR) && !(defined(YZ_DIAG_AC) && defined(YZ_DIAG_BD) && defined(YZ_SIDE_AD))
1574
+      #error "SKEW_CORRECTION requires YZ_SKEW_FACTOR or YZ_DIAG_AC, YZ_DIAG_BD, YZ_SIDE_AD."
1575
+    #endif
1576
+  #endif
1577
+#endif

+ 162
- 176
Marlin/Sd2Card.cpp 파일 보기

@@ -26,19 +26,19 @@
26 26
  *
27 27
  * This file is part of the Arduino Sd2Card Library
28 28
  */
29
-#include "Marlin.h"
29
+#include "MarlinConfig.h"
30 30
 
31 31
 #if ENABLED(SDSUPPORT)
32
+
32 33
 #include "Sd2Card.h"
33 34
 
34 35
 #if ENABLED(USE_WATCHDOG)
35 36
   #include "watchdog.h"
36 37
 #endif
37 38
 
38
-//------------------------------------------------------------------------------
39 39
 #if DISABLED(SOFTWARE_SPI)
40 40
   // functions for hardware SPI
41
-  //------------------------------------------------------------------------------
41
+
42 42
   // make sure SPCR rate is in expected bits
43 43
   #if (SPR0 != 0 || SPR1 != 1)
44 44
     #error "unexpected SPCR bits"
@@ -52,34 +52,34 @@
52 52
     SPCR = _BV(SPE) | _BV(MSTR) | (spiRate >> 1);
53 53
     SPSR = spiRate & 1 || spiRate == 6 ? 0 : _BV(SPI2X);
54 54
   }
55
-  //------------------------------------------------------------------------------
55
+
56 56
   /** SPI receive a byte */
57 57
   static uint8_t spiRec() {
58
-    SPDR = 0XFF;
58
+    SPDR = 0xFF;
59 59
     while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
60 60
     return SPDR;
61 61
   }
62
-  //------------------------------------------------------------------------------
62
+
63 63
   /** SPI read data - only one call so force inline */
64 64
   static inline __attribute__((always_inline))
65 65
   void spiRead(uint8_t* buf, uint16_t nbyte) {
66 66
     if (nbyte-- == 0) return;
67
-    SPDR = 0XFF;
67
+    SPDR = 0xFF;
68 68
     for (uint16_t i = 0; i < nbyte; i++) {
69 69
       while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
70 70
       buf[i] = SPDR;
71
-      SPDR = 0XFF;
71
+      SPDR = 0xFF;
72 72
     }
73 73
     while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
74 74
     buf[nbyte] = SPDR;
75 75
   }
76
-  //------------------------------------------------------------------------------
76
+
77 77
   /** SPI send a byte */
78 78
   static void spiSend(uint8_t b) {
79 79
     SPDR = b;
80 80
     while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
81 81
   }
82
-  //------------------------------------------------------------------------------
82
+
83 83
   /** SPI send block - only one call so force inline */
84 84
   static inline __attribute__((always_inline))
85 85
   void spiSendBlock(uint8_t token, const uint8_t* buf) {
@@ -95,15 +95,16 @@
95 95
        //------------------------------------------------------------------------------
96 96
 #else  // SOFTWARE_SPI
97 97
        //------------------------------------------------------------------------------
98
+
98 99
   /** nop to tune soft SPI timing */
99 100
   #define nop asm volatile ("nop\n\t")
100
-  //------------------------------------------------------------------------------
101
+
101 102
   /** Soft SPI receive byte */
102 103
   static uint8_t spiRec() {
103 104
     uint8_t data = 0;
104 105
     // no interrupts during byte receive - about 8 us
105 106
     cli();
106
-    // output pin high - like sending 0XFF
107
+    // output pin high - like sending 0xFF
107 108
     WRITE(SPI_MOSI_PIN, HIGH);
108 109
 
109 110
     for (uint8_t i = 0; i < 8; i++) {
@@ -123,13 +124,13 @@
123 124
     sei();
124 125
     return data;
125 126
   }
126
-  //------------------------------------------------------------------------------
127
+
127 128
   /** Soft SPI read data */
128 129
   static void spiRead(uint8_t* buf, uint16_t nbyte) {
129 130
     for (uint16_t i = 0; i < nbyte; i++)
130 131
       buf[i] = spiRec();
131 132
   }
132
-  //------------------------------------------------------------------------------
133
+
133 134
   /** Soft SPI send byte */
134 135
   static void spiSend(uint8_t data) {
135 136
     // no interrupts during byte send - about 8 us
@@ -137,7 +138,7 @@
137 138
     for (uint8_t i = 0; i < 8; i++) {
138 139
       WRITE(SPI_SCK_PIN, LOW);
139 140
 
140
-      WRITE(SPI_MOSI_PIN, data & 0X80);
141
+      WRITE(SPI_MOSI_PIN, data & 0x80);
141 142
 
142 143
       data <<= 1;
143 144
 
@@ -153,7 +154,7 @@
153 154
     // enable interrupts
154 155
     sei();
155 156
   }
156
-  //------------------------------------------------------------------------------
157
+
157 158
   /** Soft SPI send block */
158 159
   void spiSendBlock(uint8_t token, const uint8_t* buf) {
159 160
     spiSend(token);
@@ -161,7 +162,7 @@
161 162
       spiSend(buf[i]);
162 163
   }
163 164
 #endif  // SOFTWARE_SPI
164
-//------------------------------------------------------------------------------
165
+
165 166
 // send command and return error code.  Return zero for OK
166 167
 uint8_t Sd2Card::cardCommand(uint8_t cmd, uint32_t arg) {
167 168
   // select card
@@ -177,19 +178,19 @@ uint8_t Sd2Card::cardCommand(uint8_t cmd, uint32_t arg) {
177 178
   for (int8_t s = 24; s >= 0; s -= 8) spiSend(arg >> s);
178 179
 
179 180
   // send CRC
180
-  uint8_t crc = 0XFF;
181
-  if (cmd == CMD0) crc = 0X95;  // correct crc for CMD0 with arg 0
182
-  if (cmd == CMD8) crc = 0X87;  // correct crc for CMD8 with arg 0X1AA
181
+  uint8_t crc = 0xFF;
182
+  if (cmd == CMD0) crc = 0x95;  // correct crc for CMD0 with arg 0
183
+  if (cmd == CMD8) crc = 0x87;  // correct crc for CMD8 with arg 0x1AA
183 184
   spiSend(crc);
184 185
 
185 186
   // skip stuff byte for stop read
186 187
   if (cmd == CMD12) spiRec();
187 188
 
188 189
   // wait for response
189
-  for (uint8_t i = 0; ((status_ = spiRec()) & 0X80) && i != 0XFF; i++) { /* Intentionally left empty */ }
190
+  for (uint8_t i = 0; ((status_ = spiRec()) & 0x80) && i != 0xFF; i++) { /* Intentionally left empty */ }
190 191
   return status_;
191 192
 }
192
-//------------------------------------------------------------------------------
193
+
193 194
 /**
194 195
  * Determine the size of an SD flash memory card.
195 196
  *
@@ -217,19 +218,20 @@ uint32_t Sd2Card::cardSize() {
217 218
     return 0;
218 219
   }
219 220
 }
220
-//------------------------------------------------------------------------------
221
+
221 222
 void Sd2Card::chipSelectHigh() {
222 223
   digitalWrite(chipSelectPin_, HIGH);
223 224
 }
224
-//------------------------------------------------------------------------------
225
+
225 226
 void Sd2Card::chipSelectLow() {
226 227
   #if DISABLED(SOFTWARE_SPI)
227 228
     spiInit(spiRate_);
228 229
   #endif  // SOFTWARE_SPI
229 230
   digitalWrite(chipSelectPin_, LOW);
230 231
 }
231
-//------------------------------------------------------------------------------
232
-/** Erase a range of blocks.
232
+
233
+/**
234
+ * Erase a range of blocks.
233 235
  *
234 236
  * \param[in] firstBlock The address of the first block in the range.
235 237
  * \param[in] lastBlock The address of the last block in the range.
@@ -239,12 +241,11 @@ void Sd2Card::chipSelectLow() {
239 241
  * either 0 or 1, depends on the card vendor.  The card must support
240 242
  * single block erase.
241 243
  *
242
- * \return The value one, true, is returned for success and
243
- * the value zero, false, is returned for failure.
244
+ * \return true for success, false for failure.
244 245
  */
245 246
 bool Sd2Card::erase(uint32_t firstBlock, uint32_t lastBlock) {
246 247
   csd_t csd;
247
-  if (!readCSD(&csd)) goto fail;
248
+  if (!readCSD(&csd)) goto FAIL;
248 249
   // check for single block erase
249 250
   if (!csd.v1.erase_blk_en) {
250 251
     // erase size mask
@@ -252,7 +253,7 @@ bool Sd2Card::erase(uint32_t firstBlock, uint32_t lastBlock) {
252 253
     if ((firstBlock & m) != 0 || ((lastBlock + 1) & m) != 0) {
253 254
       // error card can't erase specified area
254 255
       error(SD_CARD_ERROR_ERASE_SINGLE_BLOCK);
255
-      goto fail;
256
+      goto FAIL;
256 257
     }
257 258
   }
258 259
   if (type_ != SD_CARD_TYPE_SDHC) {
@@ -263,38 +264,38 @@ bool Sd2Card::erase(uint32_t firstBlock, uint32_t lastBlock) {
263 264
       || cardCommand(CMD33, lastBlock)
264 265
       || cardCommand(CMD38, 0)) {
265 266
     error(SD_CARD_ERROR_ERASE);
266
-    goto fail;
267
+    goto FAIL;
267 268
   }
268 269
   if (!waitNotBusy(SD_ERASE_TIMEOUT)) {
269 270
     error(SD_CARD_ERROR_ERASE_TIMEOUT);
270
-    goto fail;
271
+    goto FAIL;
271 272
   }
272 273
   chipSelectHigh();
273 274
   return true;
274
-fail:
275
+  FAIL:
275 276
   chipSelectHigh();
276 277
   return false;
277 278
 }
278
-//------------------------------------------------------------------------------
279
-/** Determine if card supports single block erase.
279
+
280
+/**
281
+ * Determine if card supports single block erase.
280 282
  *
281
- * \return The value one, true, is returned if single block erase is supported.
282
- * The value zero, false, is returned if single block erase is not supported.
283
+ * \return true if single block erase is supported.
284
+ *         false if single block erase is not supported.
283 285
  */
284 286
 bool Sd2Card::eraseSingleBlockEnable() {
285 287
   csd_t csd;
286 288
   return readCSD(&csd) ? csd.v1.erase_blk_en : false;
287 289
 }
288
-//------------------------------------------------------------------------------
290
+
289 291
 /**
290 292
  * Initialize an SD flash memory card.
291 293
  *
292 294
  * \param[in] sckRateID SPI clock rate selector. See setSckRate().
293 295
  * \param[in] chipSelectPin SD chip select pin number.
294 296
  *
295
- * \return The value one, true, is returned for success and
296
- * the value zero, false, is returned for failure.  The reason for failure
297
- * can be determined by calling errorCode() and errorData().
297
+ * \return true for success, false for failure.
298
+ * The reason for failure can be determined by calling errorCode() and errorData().
298 299
  */
299 300
 bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
300 301
   errorCode_ = type_ = 0;
@@ -329,13 +330,13 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
329 330
   #endif  // SOFTWARE_SPI
330 331
 
331 332
   // must supply min of 74 clock cycles with CS high.
332
-  for (uint8_t i = 0; i < 10; i++) spiSend(0XFF);
333
+  for (uint8_t i = 0; i < 10; i++) spiSend(0xFF);
333 334
 
334 335
   // command to go idle in SPI mode
335 336
   while ((status_ = cardCommand(CMD0, 0)) != R1_IDLE_STATE) {
336 337
     if (((uint16_t)millis() - t0) > SD_INIT_TIMEOUT) {
337 338
       error(SD_CARD_ERROR_CMD0);
338
-      goto fail;
339
+      goto FAIL;
339 340
     }
340 341
   }
341 342
   // check SD version
@@ -345,29 +346,29 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
345 346
   else {
346 347
     // only need last byte of r7 response
347 348
     for (uint8_t i = 0; i < 4; i++) status_ = spiRec();
348
-    if (status_ != 0XAA) {
349
+    if (status_ != 0xAA) {
349 350
       error(SD_CARD_ERROR_CMD8);
350
-      goto fail;
351
+      goto FAIL;
351 352
     }
352 353
     type(SD_CARD_TYPE_SD2);
353 354
   }
354 355
   // initialize card and send host supports SDHC if SD2
355
-  arg = type() == SD_CARD_TYPE_SD2 ? 0X40000000 : 0;
356
+  arg = type() == SD_CARD_TYPE_SD2 ? 0x40000000 : 0;
356 357
 
357 358
   while ((status_ = cardAcmd(ACMD41, arg)) != R1_READY_STATE) {
358 359
     // check for timeout
359 360
     if (((uint16_t)millis() - t0) > SD_INIT_TIMEOUT) {
360 361
       error(SD_CARD_ERROR_ACMD41);
361
-      goto fail;
362
+      goto FAIL;
362 363
     }
363 364
   }
364 365
   // if SD2 read OCR register to check for SDHC card
365 366
   if (type() == SD_CARD_TYPE_SD2) {
366 367
     if (cardCommand(CMD58, 0)) {
367 368
       error(SD_CARD_ERROR_CMD58);
368
-      goto fail;
369
+      goto FAIL;
369 370
     }
370
-    if ((spiRec() & 0XC0) == 0XC0) type(SD_CARD_TYPE_SDHC);
371
+    if ((spiRec() & 0xC0) == 0xC0) type(SD_CARD_TYPE_SDHC);
371 372
     // discard rest of ocr - contains allowed voltage range
372 373
     for (uint8_t i = 0; i < 3; i++) spiRec();
373 374
   }
@@ -380,18 +381,17 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
380 381
     return true;
381 382
   #endif  // SOFTWARE_SPI
382 383
 
383
-fail:
384
+  FAIL:
384 385
   chipSelectHigh();
385 386
   return false;
386 387
 }
387
-//------------------------------------------------------------------------------
388
+
388 389
 /**
389 390
  * Read a 512 byte block from an SD card.
390 391
  *
391 392
  * \param[in] blockNumber Logical block to be read.
392 393
  * \param[out] dst Pointer to the location that will receive the data.
393
- * \return The value one, true, is returned for success and
394
- * the value zero, false, is returned for failure.
394
+ * \return true for success, false for failure.
395 395
  */
396 396
 bool Sd2Card::readBlock(uint32_t blockNumber, uint8_t* dst) {
397 397
   // use address if not SDHC card
@@ -399,19 +399,18 @@ bool Sd2Card::readBlock(uint32_t blockNumber, uint8_t* dst) {
399 399
 
400 400
   #if ENABLED(SD_CHECK_AND_RETRY)
401 401
     uint8_t retryCnt = 3;
402
-    do {
403
-      if (!cardCommand(CMD17, blockNumber)) {
404
-        if (readData(dst, 512)) return true;
405
-      }
406
-      else
402
+    for(;;) {
403
+      if (cardCommand(CMD17, blockNumber))
407 404
         error(SD_CARD_ERROR_CMD17);
405
+      else if (readData(dst, 512))
406
+        return true;
408 407
 
409 408
       if (!--retryCnt) break;
410 409
 
411 410
       chipSelectHigh();
412 411
       cardCommand(CMD12, 0); // Try sending a stop command, ignore the result.
413 412
       errorCode_ = 0;
414
-    } while (true);
413
+    }
415 414
   #else
416 415
     if (cardCommand(CMD17, blockNumber))
417 416
       error(SD_CARD_ERROR_CMD17);
@@ -422,13 +421,13 @@ bool Sd2Card::readBlock(uint32_t blockNumber, uint8_t* dst) {
422 421
   chipSelectHigh();
423 422
   return false;
424 423
 }
425
-//------------------------------------------------------------------------------
426
-/** Read one data block in a multiple block read sequence
424
+
425
+/**
426
+ * Read one data block in a multiple block read sequence
427 427
  *
428 428
  * \param[in] dst Pointer to the location for the data to be read.
429 429
  *
430
- * \return The value one, true, is returned for success and
431
- * the value zero, false, is returned for failure.
430
+ * \return true for success, false for failure.
432 431
  */
433 432
 bool Sd2Card::readData(uint8_t* dst) {
434 433
   chipSelectLow();
@@ -436,62 +435,61 @@ bool Sd2Card::readData(uint8_t* dst) {
436 435
 }
437 436
 
438 437
 #if ENABLED(SD_CHECK_AND_RETRY)
439
-static const uint16_t crctab[] PROGMEM = {
440
-  0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7,
441
-  0x8108, 0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF,
442
-  0x1231, 0x0210, 0x3273, 0x2252, 0x52B5, 0x4294, 0x72F7, 0x62D6,
443
-  0x9339, 0x8318, 0xB37B, 0xA35A, 0xD3BD, 0xC39C, 0xF3FF, 0xE3DE,
444
-  0x2462, 0x3443, 0x0420, 0x1401, 0x64E6, 0x74C7, 0x44A4, 0x5485,
445
-  0xA56A, 0xB54B, 0x8528, 0x9509, 0xE5EE, 0xF5CF, 0xC5AC, 0xD58D,
446
-  0x3653, 0x2672, 0x1611, 0x0630, 0x76D7, 0x66F6, 0x5695, 0x46B4,
447
-  0xB75B, 0xA77A, 0x9719, 0x8738, 0xF7DF, 0xE7FE, 0xD79D, 0xC7BC,
448
-  0x48C4, 0x58E5, 0x6886, 0x78A7, 0x0840, 0x1861, 0x2802, 0x3823,
449
-  0xC9CC, 0xD9ED, 0xE98E, 0xF9AF, 0x8948, 0x9969, 0xA90A, 0xB92B,
450
-  0x5AF5, 0x4AD4, 0x7AB7, 0x6A96, 0x1A71, 0x0A50, 0x3A33, 0x2A12,
451
-  0xDBFD, 0xCBDC, 0xFBBF, 0xEB9E, 0x9B79, 0x8B58, 0xBB3B, 0xAB1A,
452
-  0x6CA6, 0x7C87, 0x4CE4, 0x5CC5, 0x2C22, 0x3C03, 0x0C60, 0x1C41,
453
-  0xEDAE, 0xFD8F, 0xCDEC, 0xDDCD, 0xAD2A, 0xBD0B, 0x8D68, 0x9D49,
454
-  0x7E97, 0x6EB6, 0x5ED5, 0x4EF4, 0x3E13, 0x2E32, 0x1E51, 0x0E70,
455
-  0xFF9F, 0xEFBE, 0xDFDD, 0xCFFC, 0xBF1B, 0xAF3A, 0x9F59, 0x8F78,
456
-  0x9188, 0x81A9, 0xB1CA, 0xA1EB, 0xD10C, 0xC12D, 0xF14E, 0xE16F,
457
-  0x1080, 0x00A1, 0x30C2, 0x20E3, 0x5004, 0x4025, 0x7046, 0x6067,
458
-  0x83B9, 0x9398, 0xA3FB, 0xB3DA, 0xC33D, 0xD31C, 0xE37F, 0xF35E,
459
-  0x02B1, 0x1290, 0x22F3, 0x32D2, 0x4235, 0x5214, 0x6277, 0x7256,
460
-  0xB5EA, 0xA5CB, 0x95A8, 0x8589, 0xF56E, 0xE54F, 0xD52C, 0xC50D,
461
-  0x34E2, 0x24C3, 0x14A0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405,
462
-  0xA7DB, 0xB7FA, 0x8799, 0x97B8, 0xE75F, 0xF77E, 0xC71D, 0xD73C,
463
-  0x26D3, 0x36F2, 0x0691, 0x16B0, 0x6657, 0x7676, 0x4615, 0x5634,
464
-  0xD94C, 0xC96D, 0xF90E, 0xE92F, 0x99C8, 0x89E9, 0xB98A, 0xA9AB,
465
-  0x5844, 0x4865, 0x7806, 0x6827, 0x18C0, 0x08E1, 0x3882, 0x28A3,
466
-  0xCB7D, 0xDB5C, 0xEB3F, 0xFB1E, 0x8BF9, 0x9BD8, 0xABBB, 0xBB9A,
467
-  0x4A75, 0x5A54, 0x6A37, 0x7A16, 0x0AF1, 0x1AD0, 0x2AB3, 0x3A92,
468
-  0xFD2E, 0xED0F, 0xDD6C, 0xCD4D, 0xBDAA, 0xAD8B, 0x9DE8, 0x8DC9,
469
-  0x7C26, 0x6C07, 0x5C64, 0x4C45, 0x3CA2, 0x2C83, 0x1CE0, 0x0CC1,
470
-  0xEF1F, 0xFF3E, 0xCF5D, 0xDF7C, 0xAF9B, 0xBFBA, 0x8FD9, 0x9FF8,
471
-  0x6E17, 0x7E36, 0x4E55, 0x5E74, 0x2E93, 0x3EB2, 0x0ED1, 0x1EF0
472
-};
473
-static uint16_t CRC_CCITT(const uint8_t* data, size_t n) {
474
-  uint16_t crc = 0;
475
-  for (size_t i = 0; i < n; i++) {
476
-    crc = pgm_read_word(&crctab[(crc >> 8 ^ data[i]) & 0XFF]) ^ (crc << 8);
477
-  }
478
-  return crc;
479
-}
480
-#endif
438
+  static const uint16_t crctab[] PROGMEM = {
439
+    0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7,
440
+    0x8108, 0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF,
441
+    0x1231, 0x0210, 0x3273, 0x2252, 0x52B5, 0x4294, 0x72F7, 0x62D6,
442
+    0x9339, 0x8318, 0xB37B, 0xA35A, 0xD3BD, 0xC39C, 0xF3FF, 0xE3DE,
443
+    0x2462, 0x3443, 0x0420, 0x1401, 0x64E6, 0x74C7, 0x44A4, 0x5485,
444
+    0xA56A, 0xB54B, 0x8528, 0x9509, 0xE5EE, 0xF5CF, 0xC5AC, 0xD58D,
445
+    0x3653, 0x2672, 0x1611, 0x0630, 0x76D7, 0x66F6, 0x5695, 0x46B4,
446
+    0xB75B, 0xA77A, 0x9719, 0x8738, 0xF7DF, 0xE7FE, 0xD79D, 0xC7BC,
447
+    0x48C4, 0x58E5, 0x6886, 0x78A7, 0x0840, 0x1861, 0x2802, 0x3823,
448
+    0xC9CC, 0xD9ED, 0xE98E, 0xF9AF, 0x8948, 0x9969, 0xA90A, 0xB92B,
449
+    0x5AF5, 0x4AD4, 0x7AB7, 0x6A96, 0x1A71, 0x0A50, 0x3A33, 0x2A12,
450
+    0xDBFD, 0xCBDC, 0xFBBF, 0xEB9E, 0x9B79, 0x8B58, 0xBB3B, 0xAB1A,
451
+    0x6CA6, 0x7C87, 0x4CE4, 0x5CC5, 0x2C22, 0x3C03, 0x0C60, 0x1C41,
452
+    0xEDAE, 0xFD8F, 0xCDEC, 0xDDCD, 0xAD2A, 0xBD0B, 0x8D68, 0x9D49,
453
+    0x7E97, 0x6EB6, 0x5ED5, 0x4EF4, 0x3E13, 0x2E32, 0x1E51, 0x0E70,
454
+    0xFF9F, 0xEFBE, 0xDFDD, 0xCFFC, 0xBF1B, 0xAF3A, 0x9F59, 0x8F78,
455
+    0x9188, 0x81A9, 0xB1CA, 0xA1EB, 0xD10C, 0xC12D, 0xF14E, 0xE16F,
456
+    0x1080, 0x00A1, 0x30C2, 0x20E3, 0x5004, 0x4025, 0x7046, 0x6067,
457
+    0x83B9, 0x9398, 0xA3FB, 0xB3DA, 0xC33D, 0xD31C, 0xE37F, 0xF35E,
458
+    0x02B1, 0x1290, 0x22F3, 0x32D2, 0x4235, 0x5214, 0x6277, 0x7256,
459
+    0xB5EA, 0xA5CB, 0x95A8, 0x8589, 0xF56E, 0xE54F, 0xD52C, 0xC50D,
460
+    0x34E2, 0x24C3, 0x14A0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405,
461
+    0xA7DB, 0xB7FA, 0x8799, 0x97B8, 0xE75F, 0xF77E, 0xC71D, 0xD73C,
462
+    0x26D3, 0x36F2, 0x0691, 0x16B0, 0x6657, 0x7676, 0x4615, 0x5634,
463
+    0xD94C, 0xC96D, 0xF90E, 0xE92F, 0x99C8, 0x89E9, 0xB98A, 0xA9AB,
464
+    0x5844, 0x4865, 0x7806, 0x6827, 0x18C0, 0x08E1, 0x3882, 0x28A3,
465
+    0xCB7D, 0xDB5C, 0xEB3F, 0xFB1E, 0x8BF9, 0x9BD8, 0xABBB, 0xBB9A,
466
+    0x4A75, 0x5A54, 0x6A37, 0x7A16, 0x0AF1, 0x1AD0, 0x2AB3, 0x3A92,
467
+    0xFD2E, 0xED0F, 0xDD6C, 0xCD4D, 0xBDAA, 0xAD8B, 0x9DE8, 0x8DC9,
468
+    0x7C26, 0x6C07, 0x5C64, 0x4C45, 0x3CA2, 0x2C83, 0x1CE0, 0x0CC1,
469
+    0xEF1F, 0xFF3E, 0xCF5D, 0xDF7C, 0xAF9B, 0xBFBA, 0x8FD9, 0x9FF8,
470
+    0x6E17, 0x7E36, 0x4E55, 0x5E74, 0x2E93, 0x3EB2, 0x0ED1, 0x1EF0
471
+  };
472
+  static uint16_t CRC_CCITT(const uint8_t* data, size_t n) {
473
+    uint16_t crc = 0;
474
+    for (size_t i = 0; i < n; i++) {
475
+      crc = pgm_read_word(&crctab[(crc >> 8 ^ data[i]) & 0xFF]) ^ (crc << 8);
476
+    }
477
+    return crc;
478
+  }
479
+#endif // SD_CHECK_AND_RETRY
481 480
 
482
-//------------------------------------------------------------------------------
483 481
 bool Sd2Card::readData(uint8_t* dst, uint16_t count) {
484 482
   // wait for start block token
485 483
   uint16_t t0 = millis();
486 484
   while ((status_ = spiRec()) == 0XFF) {
487 485
     if (((uint16_t)millis() - t0) > SD_READ_TIMEOUT) {
488 486
       error(SD_CARD_ERROR_READ_TIMEOUT);
489
-      goto fail;
487
+      goto FAIL;
490 488
     }
491 489
   }
492 490
   if (status_ != DATA_START_BLOCK) {
493 491
     error(SD_CARD_ERROR_READ);
494
-    goto fail;
492
+    goto FAIL;
495 493
   }
496 494
   // transfer data
497 495
   spiRead(dst, count);
@@ -503,7 +501,7 @@ bool Sd2Card::readData(uint8_t* dst, uint16_t count) {
503 501
     recvCrc |= spiRec();
504 502
     if (calcCrc != recvCrc) {
505 503
       error(SD_CARD_ERROR_CRC);
506
-      goto fail;
504
+      goto FAIL;
507 505
     }
508 506
   }
509 507
 #else
@@ -515,67 +513,61 @@ bool Sd2Card::readData(uint8_t* dst, uint16_t count) {
515 513
   // Send an additional dummy byte, required by Toshiba Flash Air SD Card
516 514
   spiSend(0XFF);
517 515
   return true;
518
-fail:
516
+  FAIL:
519 517
   chipSelectHigh();
520 518
   // Send an additional dummy byte, required by Toshiba Flash Air SD Card
521 519
   spiSend(0XFF);
522 520
   return false;
523 521
 }
524
-//------------------------------------------------------------------------------
522
+
525 523
 /** read CID or CSR register */
526 524
 bool Sd2Card::readRegister(uint8_t cmd, void* buf) {
527 525
   uint8_t* dst = reinterpret_cast<uint8_t*>(buf);
528 526
   if (cardCommand(cmd, 0)) {
529 527
     error(SD_CARD_ERROR_READ_REG);
530
-    goto fail;
528
+    chipSelectHigh();
529
+    return false;
531 530
   }
532 531
   return readData(dst, 16);
533
-fail:
534
-  chipSelectHigh();
535
-  return false;
536 532
 }
537
-//------------------------------------------------------------------------------
538
-/** Start a read multiple blocks sequence.
533
+
534
+/**
535
+ * Start a read multiple blocks sequence.
539 536
  *
540 537
  * \param[in] blockNumber Address of first block in sequence.
541 538
  *
542 539
  * \note This function is used with readData() and readStop() for optimized
543 540
  * multiple block reads.  SPI chipSelect must be low for the entire sequence.
544 541
  *
545
- * \return The value one, true, is returned for success and
546
- * the value zero, false, is returned for failure.
542
+ * \return true for success, false for failure.
547 543
  */
548 544
 bool Sd2Card::readStart(uint32_t blockNumber) {
549 545
   if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9;
550 546
   if (cardCommand(CMD18, blockNumber)) {
551 547
     error(SD_CARD_ERROR_CMD18);
552
-    goto fail;
548
+    chipSelectHigh();
549
+    return false;
553 550
   }
554 551
   chipSelectHigh();
555 552
   return true;
556
-fail:
557
-  chipSelectHigh();
558
-  return false;
559 553
 }
560
-//------------------------------------------------------------------------------
561
-/** End a read multiple blocks sequence.
554
+
555
+/**
556
+ * End a read multiple blocks sequence.
562 557
  *
563
-* \return The value one, true, is returned for success and
564
- * the value zero, false, is returned for failure.
558
+ * \return true for success, false for failure.
565 559
  */
566 560
 bool Sd2Card::readStop() {
567 561
   chipSelectLow();
568 562
   if (cardCommand(CMD12, 0)) {
569 563
     error(SD_CARD_ERROR_CMD12);
570
-    goto fail;
564
+    chipSelectHigh();
565
+    return false;
571 566
   }
572 567
   chipSelectHigh();
573 568
   return true;
574
-fail:
575
-  chipSelectHigh();
576
-  return false;
577 569
 }
578
-//------------------------------------------------------------------------------
570
+
579 571
 /**
580 572
  * Set the SPI clock rate.
581 573
  *
@@ -596,70 +588,66 @@ bool Sd2Card::setSckRate(uint8_t sckRateID) {
596 588
   spiRate_ = sckRateID;
597 589
   return true;
598 590
 }
599
-//------------------------------------------------------------------------------
591
+
600 592
 // wait for card to go not busy
601 593
 bool Sd2Card::waitNotBusy(uint16_t timeoutMillis) {
602 594
   uint16_t t0 = millis();
603
-  while (spiRec() != 0XFF) {
604
-    if (((uint16_t)millis() - t0) >= timeoutMillis) goto fail;
605
-  }
595
+  while (spiRec() != 0XFF)
596
+    if (((uint16_t)millis() - t0) >= timeoutMillis) return false;
597
+
606 598
   return true;
607
-fail:
608
-  return false;
609 599
 }
610
-//------------------------------------------------------------------------------
600
+
611 601
 /**
612 602
  * Writes a 512 byte block to an SD card.
613 603
  *
614 604
  * \param[in] blockNumber Logical block to be written.
615 605
  * \param[in] src Pointer to the location of the data to be written.
616
- * \return The value one, true, is returned for success and
617
- * the value zero, false, is returned for failure.
606
+ * \return true for success, false for failure.
618 607
  */
619 608
 bool Sd2Card::writeBlock(uint32_t blockNumber, const uint8_t* src) {
620 609
   // use address if not SDHC card
621 610
   if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9;
622 611
   if (cardCommand(CMD24, blockNumber)) {
623 612
     error(SD_CARD_ERROR_CMD24);
624
-    goto fail;
613
+    goto FAIL;
625 614
   }
626
-  if (!writeData(DATA_START_BLOCK, src)) goto fail;
615
+  if (!writeData(DATA_START_BLOCK, src)) goto FAIL;
627 616
 
628 617
   // wait for flash programming to complete
629 618
   if (!waitNotBusy(SD_WRITE_TIMEOUT)) {
630 619
     error(SD_CARD_ERROR_WRITE_TIMEOUT);
631
-    goto fail;
620
+    goto FAIL;
632 621
   }
633 622
   // response is r2 so get and check two bytes for nonzero
634 623
   if (cardCommand(CMD13, 0) || spiRec()) {
635 624
     error(SD_CARD_ERROR_WRITE_PROGRAMMING);
636
-    goto fail;
625
+    goto FAIL;
637 626
   }
638 627
   chipSelectHigh();
639 628
   return true;
640
-fail:
629
+  FAIL:
641 630
   chipSelectHigh();
642 631
   return false;
643 632
 }
644
-//------------------------------------------------------------------------------
645
-/** Write one data block in a multiple block write sequence
633
+
634
+/**
635
+ * Write one data block in a multiple block write sequence
646 636
  * \param[in] src Pointer to the location of the data to be written.
647
- * \return The value one, true, is returned for success and
648
- * the value zero, false, is returned for failure.
637
+ * \return true for success, false for failure.
649 638
  */
650 639
 bool Sd2Card::writeData(const uint8_t* src) {
651 640
   chipSelectLow();
652 641
   // wait for previous write to finish
653
-  if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto fail;
654
-  if (!writeData(WRITE_MULTIPLE_TOKEN, src)) goto fail;
642
+  if (!waitNotBusy(SD_WRITE_TIMEOUT) || !writeData(WRITE_MULTIPLE_TOKEN, src)) {
643
+    error(SD_CARD_ERROR_WRITE_MULTIPLE);
644
+    chipSelectHigh();
645
+    return false;
646
+  }
655 647
   chipSelectHigh();
656 648
   return true;
657
-fail:
658
-  error(SD_CARD_ERROR_WRITE_MULTIPLE);
659
-  chipSelectHigh();
660
-  return false;
661 649
 }
662
-//------------------------------------------------------------------------------
650
+
663 651
 // send one block of data for write block or write multiple blocks
664 652
 bool Sd2Card::writeData(uint8_t token, const uint8_t* src) {
665 653
   spiSendBlock(token, src);
@@ -670,15 +658,14 @@ bool Sd2Card::writeData(uint8_t token, const uint8_t* src) {
670 658
   status_ = spiRec();
671 659
   if ((status_ & DATA_RES_MASK) != DATA_RES_ACCEPTED) {
672 660
     error(SD_CARD_ERROR_WRITE);
673
-    goto fail;
661
+    chipSelectHigh();
662
+    return false;
674 663
   }
675 664
   return true;
676
-fail:
677
-  chipSelectHigh();
678
-  return false;
679 665
 }
680
-//------------------------------------------------------------------------------
681
-/** Start a write multiple blocks sequence.
666
+
667
+/**
668
+ * Start a write multiple blocks sequence.
682 669
  *
683 670
  * \param[in] blockNumber Address of first block in sequence.
684 671
  * \param[in] eraseCount The number of blocks to be pre-erased.
@@ -686,44 +673,43 @@ fail:
686 673
  * \note This function is used with writeData() and writeStop()
687 674
  * for optimized multiple block writes.
688 675
  *
689
- * \return The value one, true, is returned for success and
690
- * the value zero, false, is returned for failure.
676
+ * \return true for success, false for failure.
691 677
  */
692 678
 bool Sd2Card::writeStart(uint32_t blockNumber, uint32_t eraseCount) {
693 679
   // send pre-erase count
694 680
   if (cardAcmd(ACMD23, eraseCount)) {
695 681
     error(SD_CARD_ERROR_ACMD23);
696
-    goto fail;
682
+    goto FAIL;
697 683
   }
698 684
   // use address if not SDHC card
699 685
   if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9;
700 686
   if (cardCommand(CMD25, blockNumber)) {
701 687
     error(SD_CARD_ERROR_CMD25);
702
-    goto fail;
688
+    goto FAIL;
703 689
   }
704 690
   chipSelectHigh();
705 691
   return true;
706
-fail:
692
+  FAIL:
707 693
   chipSelectHigh();
708 694
   return false;
709 695
 }
710
-//------------------------------------------------------------------------------
711
-/** End a write multiple blocks sequence.
696
+
697
+/**
698
+ * End a write multiple blocks sequence.
712 699
  *
713
-* \return The value one, true, is returned for success and
714
- * the value zero, false, is returned for failure.
700
+ * \return true for success, false for failure.
715 701
  */
716 702
 bool Sd2Card::writeStop() {
717 703
   chipSelectLow();
718
-  if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto fail;
704
+  if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto FAIL;
719 705
   spiSend(STOP_TRAN_TOKEN);
720
-  if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto fail;
706
+  if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto FAIL;
721 707
   chipSelectHigh();
722 708
   return true;
723
-fail:
709
+  FAIL:
724 710
   error(SD_CARD_ERROR_STOP_TRAN);
725 711
   chipSelectHigh();
726 712
   return false;
727 713
 }
728 714
 
729
-#endif
715
+#endif // SDSUPPORT

+ 85
- 132
Marlin/Sd2Card.h 파일 보기

@@ -21,164 +21,118 @@
21 21
  */
22 22
 
23 23
 /**
24
+ * \file
25
+ * \brief Sd2Card class for V2 SD/SDHC cards
26
+ */
27
+
28
+/**
24 29
  * Arduino Sd2Card Library
25 30
  * Copyright (C) 2009 by William Greiman
26 31
  *
27 32
  * This file is part of the Arduino Sd2Card Library
28 33
  */
34
+#ifndef _SD2CARD_H_
35
+#define _SD2CARD_H_
29 36
 
30
-#include "Marlin.h"
31
-#if ENABLED(SDSUPPORT)
32
-
33
-#ifndef Sd2Card_h
34
-#define Sd2Card_h
35
-/**
36
- * \file
37
- * \brief Sd2Card class for V2 SD/SDHC cards
38
- */
39 37
 #include "SdFatConfig.h"
40 38
 #include "SdInfo.h"
41
-//------------------------------------------------------------------------------
39
+
42 40
 // SPI speed is F_CPU/2^(1 + index), 0 <= index <= 6
43
-/** Set SCK to max rate of F_CPU/2. See Sd2Card::setSckRate(). */
44
-uint8_t const SPI_FULL_SPEED = 0;
45
-/** Set SCK rate to F_CPU/4. See Sd2Card::setSckRate(). */
46
-uint8_t const SPI_HALF_SPEED = 1;
47
-/** Set SCK rate to F_CPU/8. See Sd2Card::setSckRate(). */
48
-uint8_t const SPI_QUARTER_SPEED = 2;
49
-/** Set SCK rate to F_CPU/16. See Sd2Card::setSckRate(). */
50
-uint8_t const SPI_EIGHTH_SPEED = 3;
51
-/** Set SCK rate to F_CPU/32. See Sd2Card::setSckRate(). */
52
-uint8_t const SPI_SIXTEENTH_SPEED = 4;
53
-//------------------------------------------------------------------------------
54
-/** init timeout ms */
55
-uint16_t const SD_INIT_TIMEOUT = 2000;
56
-/** erase timeout ms */
57
-uint16_t const SD_ERASE_TIMEOUT = 10000;
58
-/** read timeout ms */
59
-uint16_t const SD_READ_TIMEOUT = 300;
60
-/** write time out ms */
61
-uint16_t const SD_WRITE_TIMEOUT = 600;
62
-//------------------------------------------------------------------------------
41
+uint8_t const SPI_FULL_SPEED = 0,         // Set SCK to max rate of F_CPU/2. See Sd2Card::setSckRate().
42
+              SPI_HALF_SPEED = 1,         // Set SCK rate to F_CPU/4. See Sd2Card::setSckRate().
43
+              SPI_QUARTER_SPEED = 2,      // Set SCK rate to F_CPU/8. See Sd2Card::setSckRate().
44
+              SPI_EIGHTH_SPEED = 3,       // Set SCK rate to F_CPU/16. See Sd2Card::setSckRate().
45
+              SPI_SIXTEENTH_SPEED = 4;    // Set SCK rate to F_CPU/32. See Sd2Card::setSckRate().
46
+
47
+uint16_t const SD_INIT_TIMEOUT = 2000,    // init timeout ms
48
+               SD_ERASE_TIMEOUT = 10000,  // erase timeout ms
49
+               SD_READ_TIMEOUT = 300,     // read timeout ms
50
+               SD_WRITE_TIMEOUT = 600;    // write time out ms
51
+
63 52
 // SD card errors
64
-/** timeout error for command CMD0 (initialize card in SPI mode) */
65
-uint8_t const SD_CARD_ERROR_CMD0 = 0X1;
66
-/** CMD8 was not accepted - not a valid SD card*/
67
-uint8_t const SD_CARD_ERROR_CMD8 = 0X2;
68
-/** card returned an error response for CMD12 (write stop) */
69
-uint8_t const SD_CARD_ERROR_CMD12 = 0X3;
70
-/** card returned an error response for CMD17 (read block) */
71
-uint8_t const SD_CARD_ERROR_CMD17 = 0X4;
72
-/** card returned an error response for CMD18 (read multiple block) */
73
-uint8_t const SD_CARD_ERROR_CMD18 = 0X5;
74
-/** card returned an error response for CMD24 (write block) */
75
-uint8_t const SD_CARD_ERROR_CMD24 = 0X6;
76
-/**  WRITE_MULTIPLE_BLOCKS command failed */
77
-uint8_t const SD_CARD_ERROR_CMD25 = 0X7;
78
-/** card returned an error response for CMD58 (read OCR) */
79
-uint8_t const SD_CARD_ERROR_CMD58 = 0X8;
80
-/** SET_WR_BLK_ERASE_COUNT failed */
81
-uint8_t const SD_CARD_ERROR_ACMD23 = 0X9;
82
-/** ACMD41 initialization process timeout */
83
-uint8_t const SD_CARD_ERROR_ACMD41 = 0XA;
84
-/** card returned a bad CSR version field */
85
-uint8_t const SD_CARD_ERROR_BAD_CSD = 0XB;
86
-/** erase block group command failed */
87
-uint8_t const SD_CARD_ERROR_ERASE = 0XC;
88
-/** card not capable of single block erase */
89
-uint8_t const SD_CARD_ERROR_ERASE_SINGLE_BLOCK = 0XD;
90
-/** Erase sequence timed out */
91
-uint8_t const SD_CARD_ERROR_ERASE_TIMEOUT = 0XE;
92
-/** card returned an error token instead of read data */
93
-uint8_t const SD_CARD_ERROR_READ = 0XF;
94
-/** read CID or CSD failed */
95
-uint8_t const SD_CARD_ERROR_READ_REG = 0X10;
96
-/** timeout while waiting for start of read data */
97
-uint8_t const SD_CARD_ERROR_READ_TIMEOUT = 0X11;
98
-/** card did not accept STOP_TRAN_TOKEN */
99
-uint8_t const SD_CARD_ERROR_STOP_TRAN = 0X12;
100
-/** card returned an error token as a response to a write operation */
101
-uint8_t const SD_CARD_ERROR_WRITE = 0X13;
102
-/** attempt to write protected block zero */
103
-uint8_t const SD_CARD_ERROR_WRITE_BLOCK_ZERO = 0X14;  // REMOVE - not used
104
-/** card did not go ready for a multiple block write */
105
-uint8_t const SD_CARD_ERROR_WRITE_MULTIPLE = 0X15;
106
-/** card returned an error to a CMD13 status check after a write */
107
-uint8_t const SD_CARD_ERROR_WRITE_PROGRAMMING = 0X16;
108
-/** timeout occurred during write programming */
109
-uint8_t const SD_CARD_ERROR_WRITE_TIMEOUT = 0X17;
110
-/** incorrect rate selected */
111
-uint8_t const SD_CARD_ERROR_SCK_RATE = 0X18;
112
-/** init() not called */
113
-uint8_t const SD_CARD_ERROR_INIT_NOT_CALLED = 0X19;
114
-/** crc check error */
115
-uint8_t const SD_CARD_ERROR_CRC = 0X20;
116
-//------------------------------------------------------------------------------
53
+uint8_t const SD_CARD_ERROR_CMD0 = 0X1,                 // timeout error for command CMD0 (initialize card in SPI mode)
54
+              SD_CARD_ERROR_CMD8 = 0X2,                 // CMD8 was not accepted - not a valid SD card
55
+              SD_CARD_ERROR_CMD12 = 0X3,                // card returned an error response for CMD12 (write stop)
56
+              SD_CARD_ERROR_CMD17 = 0X4,                // card returned an error response for CMD17 (read block)
57
+              SD_CARD_ERROR_CMD18 = 0X5,                // card returned an error response for CMD18 (read multiple block)
58
+              SD_CARD_ERROR_CMD24 = 0X6,                // card returned an error response for CMD24 (write block)
59
+              SD_CARD_ERROR_CMD25 = 0X7,                // WRITE_MULTIPLE_BLOCKS command failed
60
+              SD_CARD_ERROR_CMD58 = 0X8,                // card returned an error response for CMD58 (read OCR)
61
+              SD_CARD_ERROR_ACMD23 = 0X9,               // SET_WR_BLK_ERASE_COUNT failed
62
+              SD_CARD_ERROR_ACMD41 = 0XA,               // ACMD41 initialization process timeout
63
+              SD_CARD_ERROR_BAD_CSD = 0XB,              // card returned a bad CSR version field
64
+              SD_CARD_ERROR_ERASE = 0XC,                // erase block group command failed
65
+              SD_CARD_ERROR_ERASE_SINGLE_BLOCK = 0XD,   // card not capable of single block erase
66
+              SD_CARD_ERROR_ERASE_TIMEOUT = 0XE,        // Erase sequence timed out
67
+              SD_CARD_ERROR_READ = 0XF,                 // card returned an error token instead of read data
68
+              SD_CARD_ERROR_READ_REG = 0x10,            // read CID or CSD failed
69
+              SD_CARD_ERROR_READ_TIMEOUT = 0x11,        // timeout while waiting for start of read data
70
+              SD_CARD_ERROR_STOP_TRAN = 0x12,           // card did not accept STOP_TRAN_TOKEN
71
+              SD_CARD_ERROR_WRITE = 0x13,               // card returned an error token as a response to a write operation
72
+              SD_CARD_ERROR_WRITE_BLOCK_ZERO = 0x14,    // REMOVE - not used ... attempt to write protected block zero
73
+              SD_CARD_ERROR_WRITE_MULTIPLE = 0x15,      // card did not go ready for a multiple block write
74
+              SD_CARD_ERROR_WRITE_PROGRAMMING = 0x16,   // card returned an error to a CMD13 status check after a write
75
+              SD_CARD_ERROR_WRITE_TIMEOUT = 0x17,       // timeout occurred during write programming
76
+              SD_CARD_ERROR_SCK_RATE = 0x18,            // incorrect rate selected
77
+              SD_CARD_ERROR_INIT_NOT_CALLED = 0x19,     // init() not called
78
+              SD_CARD_ERROR_CRC = 0x20;                 // crc check error
79
+
117 80
 // card types
118
-/** Standard capacity V1 SD card */
119
-uint8_t const SD_CARD_TYPE_SD1  = 1;
120
-/** Standard capacity V2 SD card */
121
-uint8_t const SD_CARD_TYPE_SD2  = 2;
122
-/** High Capacity SD card */
123
-uint8_t const SD_CARD_TYPE_SDHC = 3;
81
+uint8_t const SD_CARD_TYPE_SD1  = 1,                    // Standard capacity V1 SD card
82
+              SD_CARD_TYPE_SD2  = 2,                    // Standard capacity V2 SD card
83
+              SD_CARD_TYPE_SDHC = 3;                    // High Capacity SD card
84
+
124 85
 /**
125 86
  * define SOFTWARE_SPI to use bit-bang SPI
126 87
  */
127
-//------------------------------------------------------------------------------
128 88
 #if MEGA_SOFT_SPI
129 89
   #define SOFTWARE_SPI
130 90
 #elif USE_SOFTWARE_SPI
131 91
   #define SOFTWARE_SPI
132
-#endif  // MEGA_SOFT_SPI
133
-//------------------------------------------------------------------------------
92
+#endif
93
+
134 94
 // SPI pin definitions - do not edit here - change in SdFatConfig.h
135
-//
136 95
 #if DISABLED(SOFTWARE_SPI)
137 96
   // hardware pin defs
138
-  /** The default chip select pin for the SD card is SS. */
139
-  #define SD_CHIP_SELECT_PIN SS_PIN
97
+  #define SD_CHIP_SELECT_PIN SS_PIN   // The default chip select pin for the SD card is SS.
140 98
   // The following three pins must not be redefined for hardware SPI.
141
-  /** SPI Master Out Slave In pin */
142
-  #define SPI_MOSI_PIN MOSI_PIN
143
-  /** SPI Master In Slave Out pin */
144
-  #define SPI_MISO_PIN MISO_PIN
145
-  /** SPI Clock pin */
146
-  #define SPI_SCK_PIN SCK_PIN
147
-
99
+  #define SPI_MOSI_PIN MOSI_PIN       // SPI Master Out Slave In pin
100
+  #define SPI_MISO_PIN MISO_PIN       // SPI Master In Slave Out pin
101
+  #define SPI_SCK_PIN SCK_PIN         // SPI Clock pin
148 102
 #else  // SOFTWARE_SPI
149
-
150
-  /** SPI chip select pin */
151
-  #define SD_CHIP_SELECT_PIN SOFT_SPI_CS_PIN
152
-  /** SPI Master Out Slave In pin */
153
-  #define SPI_MOSI_PIN SOFT_SPI_MOSI_PIN
154
-  /** SPI Master In Slave Out pin */
155
-  #define SPI_MISO_PIN SOFT_SPI_MISO_PIN
156
-  /** SPI Clock pin */
157
-  #define SPI_SCK_PIN SOFT_SPI_SCK_PIN
103
+  #define SD_CHIP_SELECT_PIN SOFT_SPI_CS_PIN  // SPI chip select pin
104
+  #define SPI_MOSI_PIN SOFT_SPI_MOSI_PIN      // SPI Master Out Slave In pin
105
+  #define SPI_MISO_PIN SOFT_SPI_MISO_PIN      // SPI Master In Slave Out pin
106
+  #define SPI_SCK_PIN SOFT_SPI_SCK_PIN        // SPI Clock pin
158 107
 #endif  // SOFTWARE_SPI
159
-//------------------------------------------------------------------------------
108
+
160 109
 /**
161 110
  * \class Sd2Card
162 111
  * \brief Raw access to SD and SDHC flash memory cards.
163 112
  */
164 113
 class Sd2Card {
165
- public:
166
-  /** Construct an instance of Sd2Card. */
114
+  public:
115
+
167 116
   Sd2Card() : errorCode_(SD_CARD_ERROR_INIT_NOT_CALLED), type_(0) {}
117
+
168 118
   uint32_t cardSize();
169 119
   bool erase(uint32_t firstBlock, uint32_t lastBlock);
170 120
   bool eraseSingleBlockEnable();
121
+
171 122
   /**
172 123
    *  Set SD error code.
173 124
    *  \param[in] code value for error code.
174 125
    */
175 126
   void error(uint8_t code) {errorCode_ = code;}
127
+
176 128
   /**
177 129
    * \return error code for last error. See Sd2Card.h for a list of error codes.
178 130
    */
179 131
   int errorCode() const {return errorCode_;}
132
+
180 133
   /** \return error data for last error. */
181 134
   int errorData() const {return status_;}
135
+
182 136
   /**
183 137
    * Initialize an SD flash memory card with default clock rate and chip
184 138
    * select pin.  See sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin).
@@ -188,6 +142,7 @@ class Sd2Card {
188 142
   bool init(uint8_t sckRateID = SPI_FULL_SPEED,
189 143
             uint8_t chipSelectPin = SD_CHIP_SELECT_PIN);
190 144
   bool readBlock(uint32_t block, uint8_t* dst);
145
+
191 146
   /**
192 147
    * Read a card's CID register. The CID contains card identification
193 148
    * information such as Manufacturer ID, Product name, Product serial
@@ -197,9 +152,8 @@ class Sd2Card {
197 152
    *
198 153
    * \return true for success or false for failure.
199 154
    */
200
-  bool readCID(cid_t* cid) {
201
-    return readRegister(CMD10, cid);
202
-  }
155
+  bool readCID(cid_t* cid) { return readRegister(CMD10, cid); }
156
+
203 157
   /**
204 158
    * Read a card's CSD register. The CSD contains Card-Specific Data that
205 159
    * provides information regarding access to the card's contents.
@@ -208,14 +162,14 @@ class Sd2Card {
208 162
    *
209 163
    * \return true for success or false for failure.
210 164
    */
211
-  bool readCSD(csd_t* csd) {
212
-    return readRegister(CMD9, csd);
213
-  }
165
+  bool readCSD(csd_t* csd) { return readRegister(CMD9, csd); }
166
+
214 167
   bool readData(uint8_t* dst);
215 168
   bool readStart(uint32_t blockNumber);
216 169
   bool readStop();
217 170
   bool setSckRate(uint8_t sckRateID);
218
-  /** Return the card type: SD V1, SD V2 or SDHC
171
+  /**
172
+   * Return the card type: SD V1, SD V2 or SDHC
219 173
    * \return 0 - SD V1, 1 - SD V2, or 3 - SDHC.
220 174
    */
221 175
   int type() const {return type_;}
@@ -223,13 +177,14 @@ class Sd2Card {
223 177
   bool writeData(const uint8_t* src);
224 178
   bool writeStart(uint32_t blockNumber, uint32_t eraseCount);
225 179
   bool writeStop();
226
- private:
227
-  //----------------------------------------------------------------------------
228
-  uint8_t chipSelectPin_;
229
-  uint8_t errorCode_;
230
-  uint8_t spiRate_;
231
-  uint8_t status_;
232
-  uint8_t type_;
180
+
181
+  private:
182
+  uint8_t chipSelectPin_,
183
+          errorCode_,
184
+          spiRate_,
185
+          status_,
186
+          type_;
187
+
233 188
   // private functions
234 189
   uint8_t cardAcmd(uint8_t cmd, uint32_t arg) {
235 190
     cardCommand(CMD55, 0);
@@ -241,11 +196,9 @@ class Sd2Card {
241 196
   bool readRegister(uint8_t cmd, void* buf);
242 197
   void chipSelectHigh();
243 198
   void chipSelectLow();
244
-  void type(uint8_t value) {type_ = value;}
199
+  void type(uint8_t value) { type_ = value; }
245 200
   bool waitNotBusy(uint16_t timeoutMillis);
246 201
   bool writeData(uint8_t token, const uint8_t* src);
247 202
 };
248
-#endif  // Sd2Card_h
249 203
 
250
-
251
-#endif
204
+#endif  // _SD2CARD_H_

+ 340
- 437
Marlin/SdBaseFile.cpp
파일 크기가 너무 크기때문에 변경 상태를 표시하지 않습니다.
파일 보기


+ 229
- 220
Marlin/SdBaseFile.h 파일 보기

@@ -21,207 +21,195 @@
21 21
  */
22 22
 
23 23
 /**
24
+ * \file
25
+ * \brief SdBaseFile class
26
+ */
27
+
28
+/**
24 29
  * Arduino SdFat Library
25 30
  * Copyright (C) 2009 by William Greiman
26 31
  *
27 32
  * This file is part of the Arduino Sd2Card Library
28 33
  */
29
-#include "Marlin.h"
30
-#if ENABLED(SDSUPPORT)
34
+#ifndef _SDBASEFILE_H_
35
+#define _SDBASEFILE_H_
31 36
 
32
-#ifndef SdBaseFile_h
33
-#define SdBaseFile_h
34
-/**
35
- * \file
36
- * \brief SdBaseFile class
37
- */
38
-#include "Marlin.h"
39 37
 #include "SdFatConfig.h"
40 38
 #include "SdVolume.h"
41
-//------------------------------------------------------------------------------
39
+
42 40
 /**
43 41
  * \struct filepos_t
44 42
  * \brief internal type for istream
45 43
  * do not use in user apps
46 44
  */
47 45
 struct filepos_t {
48
-  /** stream position */
49
-  uint32_t position;
50
-  /** cluster for position */
51
-  uint32_t cluster;
46
+  uint32_t position;  // stream byte position
47
+  uint32_t cluster;   // cluster of position
52 48
   filepos_t() : position(0), cluster(0) {}
53 49
 };
54 50
 
55 51
 // use the gnu style oflag in open()
56
-/** open() oflag for reading */
57
-uint8_t const O_READ = 0X01;
58
-/** open() oflag - same as O_IN */
59
-uint8_t const O_RDONLY = O_READ;
60
-/** open() oflag for write */
61
-uint8_t const O_WRITE = 0X02;
62
-/** open() oflag - same as O_WRITE */
63
-uint8_t const O_WRONLY = O_WRITE;
64
-/** open() oflag for reading and writing */
65
-uint8_t const O_RDWR = (O_READ | O_WRITE);
66
-/** open() oflag mask for access modes */
67
-uint8_t const O_ACCMODE = (O_READ | O_WRITE);
68
-/** The file offset shall be set to the end of the file prior to each write. */
69
-uint8_t const O_APPEND = 0X04;
70
-/** synchronous writes - call sync() after each write */
71
-uint8_t const O_SYNC = 0X08;
72
-/** truncate the file to zero length */
73
-uint8_t const O_TRUNC = 0X10;
74
-/** set the initial position at the end of the file */
75
-uint8_t const O_AT_END = 0X20;
76
-/** create the file if nonexistent */
77
-uint8_t const O_CREAT = 0X40;
78
-/** If O_CREAT and O_EXCL are set, open() shall fail if the file exists */
79
-uint8_t const O_EXCL = 0X80;
52
+uint8_t const O_READ = 0x01,                    // open() oflag for reading
53
+              O_RDONLY = O_READ,                // open() oflag - same as O_IN
54
+              O_WRITE = 0x02,                   // open() oflag for write
55
+              O_WRONLY = O_WRITE,               // open() oflag - same as O_WRITE
56
+              O_RDWR = (O_READ | O_WRITE),      // open() oflag for reading and writing
57
+              O_ACCMODE = (O_READ | O_WRITE),   // open() oflag mask for access modes
58
+              O_APPEND = 0x04,                  // The file offset shall be set to the end of the file prior to each write.
59
+              O_SYNC = 0x08,                    // Synchronous writes - call sync() after each write
60
+              O_TRUNC = 0x10,                   // Truncate the file to zero length
61
+              O_AT_END = 0x20,                  // Set the initial position at the end of the file
62
+              O_CREAT = 0x40,                   // Create the file if nonexistent
63
+              O_EXCL = 0x80;                    // If O_CREAT and O_EXCL are set, open() shall fail if the file exists
80 64
 
81 65
 // SdBaseFile class static and const definitions
66
+
82 67
 // flags for ls()
83
-/** ls() flag to print modify date */
84
-uint8_t const LS_DATE = 1;
85
-/** ls() flag to print file size */
86
-uint8_t const LS_SIZE = 2;
87
-/** ls() flag for recursive list of subdirectories */
88
-uint8_t const LS_R = 4;
68
+uint8_t const LS_DATE = 1,    // ls() flag to print modify date
69
+              LS_SIZE = 2,    // ls() flag to print file size
70
+              LS_R = 4;       // ls() flag for recursive list of subdirectories
89 71
 
90 72
 
91 73
 // flags for timestamp
92
-/** set the file's last access date */
93
-uint8_t const T_ACCESS = 1;
94
-/** set the file's creation date and time */
95
-uint8_t const T_CREATE = 2;
96
-/** Set the file's write date and time */
97
-uint8_t const T_WRITE = 4;
74
+uint8_t const T_ACCESS = 1,   // Set the file's last access date
75
+              T_CREATE = 2,   // Set the file's creation date and time
76
+              T_WRITE = 4;    // Set the file's write date and time
77
+
98 78
 // values for type_
99
-/** This file has not been opened. */
100
-uint8_t const FAT_FILE_TYPE_CLOSED = 0;
101
-/** A normal file */
102
-uint8_t const FAT_FILE_TYPE_NORMAL = 1;
103
-/** A FAT12 or FAT16 root directory */
104
-uint8_t const FAT_FILE_TYPE_ROOT_FIXED = 2;
105
-/** A FAT32 root directory */
106
-uint8_t const FAT_FILE_TYPE_ROOT32 = 3;
107
-/** A subdirectory file*/
108
-uint8_t const FAT_FILE_TYPE_SUBDIR = 4;
109
-/** Test value for directory type */
110
-uint8_t const FAT_FILE_TYPE_MIN_DIR = FAT_FILE_TYPE_ROOT_FIXED;
111
-
112
-/** date field for FAT directory entry
79
+uint8_t const FAT_FILE_TYPE_CLOSED = 0,                           // This file has not been opened.
80
+              FAT_FILE_TYPE_NORMAL = 1,                           // A normal file
81
+              FAT_FILE_TYPE_ROOT_FIXED = 2,                       // A FAT12 or FAT16 root directory
82
+              FAT_FILE_TYPE_ROOT32 = 3,                           // A FAT32 root directory
83
+              FAT_FILE_TYPE_SUBDIR = 4,                           // A subdirectory file
84
+              FAT_FILE_TYPE_MIN_DIR = FAT_FILE_TYPE_ROOT_FIXED;   // Test value for directory type
85
+
86
+/**
87
+ * date field for FAT directory entry
113 88
  * \param[in] year [1980,2107]
114 89
  * \param[in] month [1,12]
115 90
  * \param[in] day [1,31]
116 91
  *
117 92
  * \return Packed date for dir_t entry.
118 93
  */
119
-static inline uint16_t FAT_DATE(uint16_t year, uint8_t month, uint8_t day) {
120
-  return (year - 1980) << 9 | month << 5 | day;
121
-}
122
-/** year part of FAT directory date field
94
+static inline uint16_t FAT_DATE(uint16_t year, uint8_t month, uint8_t day) { return (year - 1980) << 9 | month << 5 | day; }
95
+
96
+/**
97
+ * year part of FAT directory date field
123 98
  * \param[in] fatDate Date in packed dir format.
124 99
  *
125 100
  * \return Extracted year [1980,2107]
126 101
  */
127
-static inline uint16_t FAT_YEAR(uint16_t fatDate) {
128
-  return 1980 + (fatDate >> 9);
129
-}
130
-/** month part of FAT directory date field
102
+static inline uint16_t FAT_YEAR(uint16_t fatDate) { return 1980 + (fatDate >> 9); }
103
+
104
+/**
105
+ * month part of FAT directory date field
131 106
  * \param[in] fatDate Date in packed dir format.
132 107
  *
133 108
  * \return Extracted month [1,12]
134 109
  */
135
-static inline uint8_t FAT_MONTH(uint16_t fatDate) {
136
-  return (fatDate >> 5) & 0XF;
137
-}
138
-/** day part of FAT directory date field
110
+static inline uint8_t FAT_MONTH(uint16_t fatDate) { return (fatDate >> 5) & 0XF; }
111
+
112
+/**
113
+ * day part of FAT directory date field
139 114
  * \param[in] fatDate Date in packed dir format.
140 115
  *
141 116
  * \return Extracted day [1,31]
142 117
  */
143
-static inline uint8_t FAT_DAY(uint16_t fatDate) {
144
-  return fatDate & 0X1F;
145
-}
146
-/** time field for FAT directory entry
118
+static inline uint8_t FAT_DAY(uint16_t fatDate) { return fatDate & 0x1F; }
119
+
120
+/**
121
+ * time field for FAT directory entry
147 122
  * \param[in] hour [0,23]
148 123
  * \param[in] minute [0,59]
149 124
  * \param[in] second [0,59]
150 125
  *
151 126
  * \return Packed time for dir_t entry.
152 127
  */
153
-static inline uint16_t FAT_TIME(uint8_t hour, uint8_t minute, uint8_t second) {
154
-  return hour << 11 | minute << 5 | second >> 1;
155
-}
156
-/** hour part of FAT directory time field
128
+static inline uint16_t FAT_TIME(uint8_t hour, uint8_t minute, uint8_t second) { return hour << 11 | minute << 5 | second >> 1; }
129
+
130
+/**
131
+ * hour part of FAT directory time field
157 132
  * \param[in] fatTime Time in packed dir format.
158 133
  *
159 134
  * \return Extracted hour [0,23]
160 135
  */
161
-static inline uint8_t FAT_HOUR(uint16_t fatTime) {
162
-  return fatTime >> 11;
163
-}
164
-/** minute part of FAT directory time field
136
+static inline uint8_t FAT_HOUR(uint16_t fatTime) { return fatTime >> 11; }
137
+
138
+/**
139
+ * minute part of FAT directory time field
165 140
  * \param[in] fatTime Time in packed dir format.
166 141
  *
167 142
  * \return Extracted minute [0,59]
168 143
  */
169
-static inline uint8_t FAT_MINUTE(uint16_t fatTime) {
170
-  return (fatTime >> 5) & 0X3F;
171
-}
172
-/** second part of FAT directory time field
144
+static inline uint8_t FAT_MINUTE(uint16_t fatTime) { return (fatTime >> 5) & 0x3F; }
145
+
146
+/**
147
+ * second part of FAT directory time field
173 148
  * Note second/2 is stored in packed time.
174 149
  *
175 150
  * \param[in] fatTime Time in packed dir format.
176 151
  *
177 152
  * \return Extracted second [0,58]
178 153
  */
179
-static inline uint8_t FAT_SECOND(uint16_t fatTime) {
180
-  return 2 * (fatTime & 0X1F);
181
-}
182
-/** Default date for file timestamps is 1 Jan 2000 */
154
+static inline uint8_t FAT_SECOND(uint16_t fatTime) { return 2 * (fatTime & 0x1F); }
155
+
156
+// Default date for file timestamps is 1 Jan 2000
183 157
 uint16_t const FAT_DEFAULT_DATE = ((2000 - 1980) << 9) | (1 << 5) | 1;
184
-/** Default time for file timestamp is 1 am */
158
+// Default time for file timestamp is 1 am
185 159
 uint16_t const FAT_DEFAULT_TIME = (1 << 11);
186
-//------------------------------------------------------------------------------
160
+
187 161
 /**
188 162
  * \class SdBaseFile
189 163
  * \brief Base class for SdFile with Print and C++ streams.
190 164
  */
191 165
 class SdBaseFile {
192 166
  public:
193
-  /** Create an instance. */
194 167
   SdBaseFile() : writeError(false), type_(FAT_FILE_TYPE_CLOSED) {}
195 168
   SdBaseFile(const char* path, uint8_t oflag);
196
-  ~SdBaseFile() {if (isOpen()) close();}
169
+  ~SdBaseFile() { if (isOpen()) close(); }
170
+
197 171
   /**
198 172
    * writeError is set to true if an error occurs during a write().
199 173
    * Set writeError to false before calling print() and/or write() and check
200 174
    * for true after calls to print() and/or write().
201 175
    */
202 176
   bool writeError;
203
-  //----------------------------------------------------------------------------
177
+
204 178
   // helpers for stream classes
205
-  /** get position for streams
179
+
180
+  /**
181
+   * get position for streams
206 182
    * \param[out] pos struct to receive position
207 183
    */
208 184
   void getpos(filepos_t* pos);
209
-  /** set position for streams
185
+
186
+  /**
187
+   * set position for streams
210 188
    * \param[out] pos struct with value for new position
211 189
    */
212 190
   void setpos(filepos_t* pos);
213
-  //----------------------------------------------------------------------------
191
+
214 192
   bool close();
215 193
   bool contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock);
216 194
   bool createContiguous(SdBaseFile* dirFile,
217 195
                         const char* path, uint32_t size);
218
-  /** \return The current cluster number for a file or directory. */
219
-  uint32_t curCluster() const {return curCluster_;}
220
-  /** \return The current position for a file or directory. */
221
-  uint32_t curPosition() const {return curPosition_;}
222
-  /** \return Current working directory */
223
-  static SdBaseFile* cwd() {return cwd_;}
224
-  /** Set the date/time callback function
196
+  /**
197
+   * \return The current cluster number for a file or directory.
198
+   */
199
+  uint32_t curCluster() const { return curCluster_; }
200
+
201
+  /**
202
+   * \return The current position for a file or directory.
203
+   */
204
+  uint32_t curPosition() const { return curPosition_; }
205
+
206
+  /**
207
+   * \return Current working directory
208
+   */
209
+  static SdBaseFile* cwd() { return cwd_; }
210
+
211
+  /**
212
+   * Set the date/time callback function
225 213
    *
226 214
    * \param[in] dateTime The user's call back function.  The callback
227 215
    * function is of the form:
@@ -252,35 +240,55 @@ class SdBaseFile {
252 240
     void (*dateTime)(uint16_t* date, uint16_t* time)) {
253 241
     dateTime_ = dateTime;
254 242
   }
255
-  /**  Cancel the date/time callback function. */
256
-  static void dateTimeCallbackCancel() {dateTime_ = 0;}
243
+
244
+  /**
245
+   * Cancel the date/time callback function.
246
+   */
247
+  static void dateTimeCallbackCancel() { dateTime_ = 0; }
257 248
   bool dirEntry(dir_t* dir);
258 249
   static void dirName(const dir_t& dir, char* name);
259 250
   bool exists(const char* name);
260 251
   int16_t fgets(char* str, int16_t num, char* delim = 0);
261
-  /** \return The total number of bytes in a file or directory. */
262
-  uint32_t fileSize() const {return fileSize_;}
263
-  /** \return The first cluster number for a file or directory. */
264
-  uint32_t firstCluster() const {return firstCluster_;}
265
-  bool getFilename(char* name);
266
-  /** \return True if this is a directory else false. */
267
-  bool isDir() const {return type_ >= FAT_FILE_TYPE_MIN_DIR;}
268
-  /** \return True if this is a normal file else false. */
269
-  bool isFile() const {return type_ == FAT_FILE_TYPE_NORMAL;}
270
-  /** \return True if this is an open file/directory else false. */
271
-  bool isOpen() const {return type_ != FAT_FILE_TYPE_CLOSED;}
272
-  /** \return True if this is a subdirectory else false. */
273
-  bool isSubDir() const {return type_ == FAT_FILE_TYPE_SUBDIR;}
274
-  /** \return True if this is the root directory. */
275
-  bool isRoot() const {
276
-    return type_ == FAT_FILE_TYPE_ROOT_FIXED || type_ == FAT_FILE_TYPE_ROOT32;
277
-  }
252
+
253
+  /**
254
+   * \return The total number of bytes in a file or directory.
255
+   */
256
+  uint32_t fileSize() const { return fileSize_; }
257
+
258
+  /**
259
+   * \return The first cluster number for a file or directory.
260
+   */
261
+  uint32_t firstCluster() const { return firstCluster_; }
262
+
263
+  /**
264
+   * \return True if this is a directory else false.
265
+   */
266
+  bool isDir() const { return type_ >= FAT_FILE_TYPE_MIN_DIR; }
267
+
268
+  /**
269
+   * \return True if this is a normal file else false.
270
+   */
271
+  bool isFile() const { return type_ == FAT_FILE_TYPE_NORMAL; }
272
+
273
+  /**
274
+   * \return True if this is an open file/directory else false.
275
+   */
276
+  bool isOpen() const { return type_ != FAT_FILE_TYPE_CLOSED; }
277
+
278
+  /**
279
+   * \return True if this is a subdirectory else false.
280
+   */
281
+  bool isSubDir() const { return type_ == FAT_FILE_TYPE_SUBDIR; }
282
+
283
+  /**
284
+   * \return True if this is the root directory.
285
+   */
286
+  bool isRoot() const { return type_ == FAT_FILE_TYPE_ROOT_FIXED || type_ == FAT_FILE_TYPE_ROOT32; }
287
+
288
+  bool getFilename(char * const name);
278 289
   void ls(uint8_t flags = 0, uint8_t indent = 0);
290
+
279 291
   bool mkdir(SdBaseFile* dir, const char* path, bool pFlag = true);
280
-  // alias for backward compactability
281
-  bool makeDir(SdBaseFile* dir, const char* path) {
282
-    return mkdir(dir, path, false);
283
-  }
284 292
   bool open(SdBaseFile* dirFile, uint16_t index, uint8_t oflag);
285 293
   bool open(SdBaseFile* dirFile, const char* path, uint8_t oflag);
286 294
   bool open(const char* path, uint8_t oflag = O_READ);
@@ -295,53 +303,58 @@ class SdBaseFile {
295 303
   int8_t readDir(dir_t* dir, char* longFilename);
296 304
   static bool remove(SdBaseFile* dirFile, const char* path);
297 305
   bool remove();
298
-  /** Set the file's current position to zero. */
299
-  void rewind() {seekSet(0);}
306
+
307
+  /**
308
+   * Set the file's current position to zero.
309
+   */
310
+  void rewind() { seekSet(0); }
300 311
   bool rename(SdBaseFile* dirFile, const char* newPath);
301 312
   bool rmdir();
302
-  // for backward compatibility
303
-  bool rmDir() {return rmdir();}
304 313
   bool rmRfStar();
305
-  /** Set the files position to current position + \a pos. See seekSet().
314
+
315
+  /**
316
+   * Set the files position to current position + \a pos. See seekSet().
306 317
    * \param[in] offset The new position in bytes from the current position.
307 318
    * \return true for success or false for failure.
308 319
    */
309
-  bool seekCur(int32_t offset) {
310
-    return seekSet(curPosition_ + offset);
311
-  }
312
-  /** Set the files position to end-of-file + \a offset. See seekSet().
320
+  bool seekCur(const int32_t offset) { return seekSet(curPosition_ + offset); }
321
+
322
+  /**
323
+   * Set the files position to end-of-file + \a offset. See seekSet().
313 324
    * \param[in] offset The new position in bytes from end-of-file.
314 325
    * \return true for success or false for failure.
315 326
    */
316
-  bool seekEnd(int32_t offset = 0) {return seekSet(fileSize_ + offset);}
317
-  bool seekSet(uint32_t pos);
327
+  bool seekEnd(const int32_t offset = 0) { return seekSet(fileSize_ + offset); }
328
+  bool seekSet(const uint32_t pos);
318 329
   bool sync();
319 330
   bool timestamp(SdBaseFile* file);
320 331
   bool timestamp(uint8_t flag, uint16_t year, uint8_t month, uint8_t day,
321 332
                  uint8_t hour, uint8_t minute, uint8_t second);
322
-  /** Type of file.  You should use isFile() or isDir() instead of type()
323
-   * if possible.
333
+
334
+  /**
335
+   * Type of file. Use isFile() or isDir() instead of type() if possible.
324 336
    *
325 337
    * \return The file or directory type.
326 338
    */
327
-  uint8_t type() const {return type_;}
339
+  uint8_t type() const { return type_; }
328 340
   bool truncate(uint32_t size);
329
-  /** \return SdVolume that contains this file. */
330
-  SdVolume* volume() const {return vol_;}
341
+
342
+  /**
343
+   * \return SdVolume that contains this file.
344
+   */
345
+  SdVolume* volume() const { return vol_; }
331 346
   int16_t write(const void* buf, uint16_t nbyte);
332
-  //------------------------------------------------------------------------------
347
+
333 348
  private:
334
-  // allow SdFat to set cwd_
335
-  friend class SdFat;
336
-  // global pointer to cwd dir
337
-  static SdBaseFile* cwd_;
349
+  friend class SdFat;           // allow SdFat to set cwd_
350
+  static SdBaseFile* cwd_;      // global pointer to cwd dir
351
+
338 352
   // data time callback function
339 353
   static void (*dateTime_)(uint16_t* date, uint16_t* time);
354
+
340 355
   // bits defined in flags_
341
-  // should be 0X0F
342
-  static uint8_t const F_OFLAG = (O_ACCMODE | O_APPEND | O_SYNC);
343
-  // sync of directory entry required
344
-  static uint8_t const F_FILE_DIR_DIRTY = 0X80;
356
+  static uint8_t const F_OFLAG = (O_ACCMODE | O_APPEND | O_SYNC),   // should be 0x0F
357
+                       F_FILE_DIR_DIRTY = 0x80;                     // sync of directory entry required
345 358
 
346 359
   // private data
347 360
   uint8_t   flags_;         // See above for definition of flags_ bits
@@ -355,8 +368,11 @@ class SdBaseFile {
355 368
   uint32_t  firstCluster_;  // first cluster of file
356 369
   SdVolume* vol_;           // volume where file is located
357 370
 
358
-  /** experimental don't use */
359
-  bool openParent(SdBaseFile* dir);
371
+  /**
372
+   * EXPERIMENTAL - Don't use!
373
+   */
374
+  //bool openParent(SdBaseFile* dir);
375
+
360 376
   // private functions
361 377
   bool addCluster();
362 378
   bool addDirCluster();
@@ -367,61 +383,48 @@ class SdBaseFile {
367 383
   bool open(SdBaseFile* dirFile, const uint8_t dname[11], uint8_t oflag);
368 384
   bool openCachedEntry(uint8_t cacheIndex, uint8_t oflags);
369 385
   dir_t* readDirCache();
370
-  //------------------------------------------------------------------------------
371
-  // to be deleted
372
-  static void printDirName(const dir_t& dir,
373
-                           uint8_t width, bool printSlash);
374
-  //------------------------------------------------------------------------------
375
-  // Deprecated functions  - suppress cpplint warnings with NOLINT comment
376
-#if ALLOW_DEPRECATED_FUNCTIONS && !defined(DOXYGEN)
386
+
387
+// Deprecated functions
388
+#if ALLOW_DEPRECATED_FUNCTIONS
377 389
  public:
378
-  /** \deprecated Use:
390
+
391
+  /**
392
+   * \deprecated Use:
379 393
    * bool contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock);
380 394
    * \param[out] bgnBlock the first block address for the file.
381 395
    * \param[out] endBlock the last  block address for the file.
382 396
    * \return true for success or false for failure.
383 397
    */
384
-  bool contiguousRange(uint32_t& bgnBlock, uint32_t& endBlock) {  // NOLINT
398
+  bool contiguousRange(uint32_t& bgnBlock, uint32_t& endBlock) {
385 399
     return contiguousRange(&bgnBlock, &endBlock);
386 400
   }
387
-  /** \deprecated Use:
388
-    * bool createContiguous(SdBaseFile* dirFile,
389
-    *   const char* path, uint32_t size)
390
-    * \param[in] dirFile The directory where the file will be created.
391
-    * \param[in] path A path with a valid DOS 8.3 file name.
392
-    * \param[in] size The desired file size.
393
-    * \return true for success or false for failure.
394
-    */
395
-  bool createContiguous(SdBaseFile& dirFile,  // NOLINT
396
-                        const char* path, uint32_t size) {
401
+
402
+  /**
403
+   * \deprecated Use:
404
+   * bool createContiguous(SdBaseFile* dirFile, const char* path, uint32_t size)
405
+   * \param[in] dirFile The directory where the file will be created.
406
+   * \param[in] path A path with a valid DOS 8.3 file name.
407
+   * \param[in] size The desired file size.
408
+   * \return true for success or false for failure.
409
+   */
410
+  bool createContiguous(SdBaseFile& dirFile, const char* path, uint32_t size) {
397 411
     return createContiguous(&dirFile, path, size);
398 412
   }
399
-  /** \deprecated Use:
413
+
414
+  /**
415
+   * \deprecated Use:
400 416
    * static void dateTimeCallback(
401 417
    *   void (*dateTime)(uint16_t* date, uint16_t* time));
402 418
    * \param[in] dateTime The user's call back function.
403 419
    */
404 420
   static void dateTimeCallback(
405
-    void (*dateTime)(uint16_t &date, uint16_t &time)) {  // NOLINT
421
+    void (*dateTime)(uint16_t &date, uint16_t &time)) {
406 422
     oldDateTime_ = dateTime;
407 423
     dateTime_ = dateTime ? oldToNew : 0;
408 424
   }
409
-  /** \deprecated Use: bool dirEntry(dir_t* dir);
410
-   * \param[out] dir Location for return of the file's directory entry.
411
-   * \return true for success or false for failure.
412
-   */
413
-  bool dirEntry(dir_t& dir) {return dirEntry(&dir);}  // NOLINT
414
-  /** \deprecated Use:
415
-   * bool mkdir(SdBaseFile* dir, const char* path);
416
-   * \param[in] dir An open SdFat instance for the directory that will contain
417
-   * the new directory.
418
-   * \param[in] path A path with a valid 8.3 DOS name for the new directory.
419
-   * \return true for success or false for failure.
420
-   */
421
-  bool mkdir(SdBaseFile& dir, const char* path) {  // NOLINT
422
-    return mkdir(&dir, path);
423
-  }
424
-  /** \deprecated Use:
425
+
426
+  /**
427
+   * \deprecated Use:
425 428
    * bool open(SdBaseFile* dirFile, const char* path, uint8_t oflag);
426 429
    * \param[in] dirFile An open SdFat instance for the directory containing the
427 430
    * file to be opened.
@@ -430,20 +433,23 @@ class SdBaseFile {
430 433
    * OR of flags O_READ, O_WRITE, O_TRUNC, and O_SYNC.
431 434
    * \return true for success or false for failure.
432 435
    */
433
-  bool open(SdBaseFile& dirFile, // NOLINT
434
-            const char* path, uint8_t oflag) {
436
+  bool open(SdBaseFile& dirFile, const char* path, uint8_t oflag) {
435 437
     return open(&dirFile, path, oflag);
436 438
   }
437
-  /** \deprecated  Do not use in new apps
439
+
440
+  /**
441
+   * \deprecated  Do not use in new apps
438 442
    * \param[in] dirFile An open SdFat instance for the directory containing the
439 443
    * file to be opened.
440 444
    * \param[in] path A path with a valid 8.3 DOS name for a file to be opened.
441 445
    * \return true for success or false for failure.
442 446
    */
443
-  bool open(SdBaseFile& dirFile, const char* path) {  // NOLINT
447
+  bool open(SdBaseFile& dirFile, const char* path) {
444 448
     return open(dirFile, path, O_RDWR);
445 449
   }
446
-  /** \deprecated Use:
450
+
451
+  /**
452
+   * \deprecated Use:
447 453
    * bool open(SdBaseFile* dirFile, uint16_t index, uint8_t oflag);
448 454
    * \param[in] dirFile An open SdFat instance for the directory.
449 455
    * \param[in] index The \a index of the directory entry for the file to be
@@ -452,35 +458,39 @@ class SdBaseFile {
452 458
    * OR of flags O_READ, O_WRITE, O_TRUNC, and O_SYNC.
453 459
    * \return true for success or false for failure.
454 460
    */
455
-  bool open(SdBaseFile& dirFile, uint16_t index, uint8_t oflag) {  // NOLINT
461
+  bool open(SdBaseFile& dirFile, uint16_t index, uint8_t oflag) {
456 462
     return open(&dirFile, index, oflag);
457 463
   }
458
-  /** \deprecated Use: bool openRoot(SdVolume* vol);
464
+
465
+  /**
466
+   * \deprecated Use: bool openRoot(SdVolume* vol);
459 467
    * \param[in] vol The FAT volume containing the root directory to be opened.
460 468
    * \return true for success or false for failure.
461 469
    */
462
-  bool openRoot(SdVolume& vol) {return openRoot(&vol);}  // NOLINT
463
-  /** \deprecated Use: int8_t readDir(dir_t* dir);
470
+  bool openRoot(SdVolume& vol) { return openRoot(&vol); }
471
+
472
+  /**
473
+   * \deprecated Use: int8_t readDir(dir_t* dir);
464 474
    * \param[out] dir The dir_t struct that will receive the data.
465 475
    * \return bytes read for success zero for eof or -1 for failure.
466 476
    */
467
-  int8_t readDir(dir_t& dir, char* longFilename) {return readDir(&dir, longFilename);}  // NOLINT
468
-  /** \deprecated Use:
477
+  int8_t readDir(dir_t& dir, char* longFilename) {
478
+    return readDir(&dir, longFilename);
479
+  }
480
+
481
+  /**
482
+   * \deprecated Use:
469 483
    * static uint8_t remove(SdBaseFile* dirFile, const char* path);
470 484
    * \param[in] dirFile The directory that contains the file.
471 485
    * \param[in] path The name of the file to be removed.
472 486
    * \return true for success or false for failure.
473 487
    */
474
-  static bool remove(SdBaseFile& dirFile, const char* path) {  // NOLINT
475
-    return remove(&dirFile, path);
476
-  }
477
-  //------------------------------------------------------------------------------
478
-  // rest are private
488
+  static bool remove(SdBaseFile& dirFile, const char* path) { return remove(&dirFile, path); }
489
+
479 490
  private:
480
-  static void (*oldDateTime_)(uint16_t &date, uint16_t &time);  // NOLINT
481
-  static void oldToNew(uint16_t* date, uint16_t* time) {
482
-    uint16_t d;
483
-    uint16_t t;
491
+  static void (*oldDateTime_)(uint16_t &date, uint16_t &time);
492
+  static void oldToNew(uint16_t * const date, uint16_t * const time) {
493
+    uint16_t d, t;
484 494
     oldDateTime_(d, t);
485 495
     *date = d;
486 496
     *time = t;
@@ -488,5 +498,4 @@ class SdBaseFile {
488 498
 #endif  // ALLOW_DEPRECATED_FUNCTIONS
489 499
 };
490 500
 
491
-#endif  // SdBaseFile_h
492
-#endif
501
+#endif // _SDBASEFILE_H_

+ 91
- 104
Marlin/SdFatConfig.h 파일 보기

@@ -21,114 +21,101 @@
21 21
  */
22 22
 
23 23
 /**
24
+ * SdFatConfig.h
24 25
  * Arduino SdFat Library
25 26
  * Copyright (C) 2009 by William Greiman
26 27
  *
27 28
  * This file is part of the Arduino Sd2Card Library
28 29
  */
30
+
31
+#ifndef _SDFATCONFIG_H_
32
+#define _SDFATCONFIG_H_
33
+
34
+#include "MarlinConfig.h"
35
+
36
+/**
37
+ * To use multiple SD cards set USE_MULTIPLE_CARDS nonzero.
38
+ *
39
+ * Using multiple cards costs 400 - 500  bytes of flash.
40
+ *
41
+ * Each card requires about 550 bytes of SRAM so use of a Mega is recommended.
42
+ */
43
+#define USE_MULTIPLE_CARDS 0
44
+
45
+/**
46
+ * Call flush for endl if ENDL_CALLS_FLUSH is nonzero
47
+ *
48
+ * The standard for iostreams is to call flush.  This is very costly for
49
+ * SdFat.  Each call to flush causes 2048 bytes of I/O to the SD.
50
+ *
51
+ * SdFat has a single 512 byte buffer for SD I/O so it must write the current
52
+ * data block to the SD, read the directory block from the SD, update the
53
+ * directory entry, write the directory block to the SD and read the data
54
+ * block back into the buffer.
55
+ *
56
+ * The SD flash memory controller is not designed for this many rewrites
57
+ * so performance may be reduced by more than a factor of 100.
58
+ *
59
+ * If ENDL_CALLS_FLUSH is zero, you must call flush and/or close to force
60
+ * all data to be written to the SD.
61
+ */
62
+#define ENDL_CALLS_FLUSH 0
63
+
29 64
 /**
30
- * \file
31
- * \brief configuration definitions
65
+ * Allow use of deprecated functions if ALLOW_DEPRECATED_FUNCTIONS is nonzero
32 66
  */
33
-#include "Marlin.h"
34
-#if ENABLED(SDSUPPORT)
35
-
36
-#ifndef SdFatConfig_h
37
-  #define SdFatConfig_h
38
-  #include <stdint.h>
39
-  //------------------------------------------------------------------------------
40
-  /**
41
-  * To use multiple SD cards set USE_MULTIPLE_CARDS nonzero.
42
-  *
43
-  * Using multiple cards costs 400 - 500  bytes of flash.
44
-  *
45
-  * Each card requires about 550 bytes of SRAM so use of a Mega is recommended.
46
-  */
47
-  #define USE_MULTIPLE_CARDS 0
48
-  //------------------------------------------------------------------------------
49
-  /**
50
-  * Call flush for endl if ENDL_CALLS_FLUSH is nonzero
51
-  *
52
-  * The standard for iostreams is to call flush.  This is very costly for
53
-  * SdFat.  Each call to flush causes 2048 bytes of I/O to the SD.
54
-  *
55
-  * SdFat has a single 512 byte buffer for SD I/O so it must write the current
56
-  * data block to the SD, read the directory block from the SD, update the
57
-  * directory entry, write the directory block to the SD and read the data
58
-  * block back into the buffer.
59
-  *
60
-  * The SD flash memory controller is not designed for this many rewrites
61
-  * so performance may be reduced by more than a factor of 100.
62
-  *
63
-  * If ENDL_CALLS_FLUSH is zero, you must call flush and/or close to force
64
-  * all data to be written to the SD.
65
-  */
66
-  #define ENDL_CALLS_FLUSH 0
67
-  //------------------------------------------------------------------------------
68
-  /**
69
-  * Allow use of deprecated functions if ALLOW_DEPRECATED_FUNCTIONS is nonzero
70
-  */
71
-  #define ALLOW_DEPRECATED_FUNCTIONS 1
72
-  //------------------------------------------------------------------------------
73
-  /**
74
-  * Allow FAT12 volumes if FAT12_SUPPORT is nonzero.
75
-  * FAT12 has not been well tested.
76
-  */
77
-  #define FAT12_SUPPORT 0
78
-  //------------------------------------------------------------------------------
79
-  /**
80
-  * SPI init rate for SD initialization commands. Must be 5 (F_CPU/64)
81
-  * or 6 (F_CPU/128).
82
-  */
83
-  #define SPI_SD_INIT_RATE 5
84
-  //------------------------------------------------------------------------------
85
-  /**
86
-  * Set the SS pin high for hardware SPI.  If SS is chip select for another SPI
87
-  * device this will disable that device during the SD init phase.
88
-  */
89
-  #define SET_SPI_SS_HIGH 1
90
-  //------------------------------------------------------------------------------
91
-  /**
92
-  * Define MEGA_SOFT_SPI nonzero to use software SPI on Mega Arduinos.
93
-  * Pins used are SS 10, MOSI 11, MISO 12, and SCK 13.
94
-  *
95
-  * MEGA_SOFT_SPI allows an unmodified Adafruit GPS Shield to be used
96
-  * on Mega Arduinos.  Software SPI works well with GPS Shield V1.1
97
-  * but many SD cards will fail with GPS Shield V1.0.
98
-  */
99
-  #define MEGA_SOFT_SPI 0
100
-  //------------------------------------------------------------------------------
101
-  /**
102
-  * Set USE_SOFTWARE_SPI nonzero to always use software SPI.
103
-  */
104
-  #define USE_SOFTWARE_SPI 0
105
-  // define software SPI pins so Mega can use unmodified 168/328 shields
106
-  /** Software SPI chip select pin for the SD */
107
-  #define SOFT_SPI_CS_PIN 10
108
-  /** Software SPI Master Out Slave In pin */
109
-  #define SOFT_SPI_MOSI_PIN 11
110
-  /** Software SPI Master In Slave Out pin */
111
-  #define SOFT_SPI_MISO_PIN 12
112
-  /** Software SPI Clock pin */
113
-  #define SOFT_SPI_SCK_PIN 13
114
-  //------------------------------------------------------------------------------
115
-  /**
116
-  * The __cxa_pure_virtual function is an error handler that is invoked when
117
-  * a pure virtual function is called.
118
-  */
119
-  #define USE_CXA_PURE_VIRTUAL 1
120
-
121
-  /** Number of UTF-16 characters per entry */
122
-  #define FILENAME_LENGTH 13
123
-
124
-  /**
125
-  * Defines for long (vfat) filenames
126
-  */
127
-  /** Number of VFAT entries used. Every entry has 13 UTF-16 characters */
128
-  #define MAX_VFAT_ENTRIES (2)
129
-  /** Total size of the buffer used to store the long filenames */
130
-  #define LONG_FILENAME_LENGTH (FILENAME_LENGTH*MAX_VFAT_ENTRIES+1)
131
-#endif  // SdFatConfig_h
132
-
133
-
134
-#endif
67
+#define ALLOW_DEPRECATED_FUNCTIONS 1
68
+
69
+/**
70
+ * Allow FAT12 volumes if FAT12_SUPPORT is nonzero.
71
+ * FAT12 has not been well tested.
72
+ */
73
+#define FAT12_SUPPORT 0
74
+
75
+/**
76
+ * SPI init rate for SD initialization commands. Must be 5 (F_CPU/64)
77
+ * or 6 (F_CPU/128).
78
+ */
79
+#define SPI_SD_INIT_RATE 5
80
+
81
+/**
82
+ * Set the SS pin high for hardware SPI.  If SS is chip select for another SPI
83
+ * device this will disable that device during the SD init phase.
84
+ */
85
+#define SET_SPI_SS_HIGH 1
86
+
87
+/**
88
+ * Define MEGA_SOFT_SPI nonzero to use software SPI on Mega Arduinos.
89
+ * Pins used are SS 10, MOSI 11, MISO 12, and SCK 13.
90
+ *
91
+ * MEGA_SOFT_SPI allows an unmodified Adafruit GPS Shield to be used
92
+ * on Mega Arduinos.  Software SPI works well with GPS Shield V1.1
93
+ * but many SD cards will fail with GPS Shield V1.0.
94
+ */
95
+#define MEGA_SOFT_SPI 0
96
+
97
+// Set USE_SOFTWARE_SPI nonzero to ALWAYS use Software SPI.
98
+#define USE_SOFTWARE_SPI 0
99
+
100
+// Define software SPI pins so Mega can use unmodified 168/328 shields
101
+#define SOFT_SPI_CS_PIN   10 // Software SPI chip select pin for the SD
102
+#define SOFT_SPI_MOSI_PIN 11 // Software SPI Master Out Slave In pin
103
+#define SOFT_SPI_MISO_PIN 12 // Software SPI Master In Slave Out pin
104
+#define SOFT_SPI_SCK_PIN  13 // Software SPI Clock pin
105
+
106
+/**
107
+ * The __cxa_pure_virtual function is an error handler that is invoked when
108
+ * a pure virtual function is called.
109
+ */
110
+#define USE_CXA_PURE_VIRTUAL 1
111
+
112
+/**
113
+ * Defines for 8.3 and long (vfat) filenames
114
+ */
115
+
116
+#define FILENAME_LENGTH 13 // Number of UTF-16 characters per entry
117
+
118
+// Total bytes needed to store a single long filename
119
+#define LONG_FILENAME_LENGTH (FILENAME_LENGTH * MAX_VFAT_ENTRIES + 1)
120
+
121
+#endif // _SDFATCONFIG_H_

+ 384
- 424
Marlin/SdFatStructs.h 파일 보기

@@ -21,34 +21,30 @@
21 21
  */
22 22
 
23 23
 /**
24
+ * \file
25
+ * \brief FAT file structures
26
+ */
27
+
28
+/**
24 29
  * Arduino SdFat Library
25 30
  * Copyright (C) 2009 by William Greiman
26 31
  *
27 32
  * This file is part of the Arduino Sd2Card Library
28 33
  */
29
-#include "Marlin.h"
30
-#if ENABLED(SDSUPPORT)
31
-
32
-#ifndef SdFatStructs_h
33
-#define SdFatStructs_h
34
+#ifndef SDFATSTRUCTS_H
35
+#define SDFATSTRUCTS_H
34 36
 
35 37
 #define PACKED __attribute__((__packed__))
36
-/**
37
- * \file
38
- * \brief FAT file structures
39
- */
38
+
40 39
 /**
41 40
  * mostly from Microsoft document fatgen103.doc
42 41
  * http://www.microsoft.com/whdc/system/platform/firmware/fatgen.mspx
43 42
  */
44
-//------------------------------------------------------------------------------
45
-/** Value for byte 510 of boot block or MBR */
46
-uint8_t const BOOTSIG0 = 0X55;
47
-/** Value for byte 511 of boot block or MBR */
48
-uint8_t const BOOTSIG1 = 0XAA;
49
-/** Value for bootSignature field int FAT/FAT32 boot sector */
50
-uint8_t const EXTENDED_BOOT_SIG = 0X29;
51
-//------------------------------------------------------------------------------
43
+
44
+uint8_t const BOOTSIG0 = 0x55,          // Value for byte 510 of boot block or MBR
45
+              BOOTSIG1 = 0xAA,          // Value for byte 511 of boot block or MBR
46
+              EXTENDED_BOOT_SIG = 0x29; // Value for bootSignature field int FAT/FAT32 boot sector
47
+
52 48
 /**
53 49
  * \struct partitionTable
54 50
  * \brief MBR partition table entry
@@ -57,59 +53,58 @@ uint8_t const EXTENDED_BOOT_SIG = 0X29;
57 53
  * The MBR partition table has four entries.
58 54
  */
59 55
 struct partitionTable {
60
-          /**
61
-           * Boot Indicator . Indicates whether the volume is the active
62
-           * partition.  Legal values include: 0X00. Do not use for booting.
63
-           * 0X80 Active partition.
64
-           */
56
+  /**
57
+   * Boot Indicator . Indicates whether the volume is the active
58
+   * partition.  Legal values include: 0x00. Do not use for booting.
59
+   * 0x80 Active partition.
60
+   */
65 61
   uint8_t  boot;
66
-          /**
67
-           * Head part of Cylinder-head-sector address of the first block in
68
-           * the partition. Legal values are 0-255. Only used in old PC BIOS.
69
-           */
62
+  /**
63
+   * Head part of Cylinder-head-sector address of the first block in
64
+   * the partition. Legal values are 0-255. Only used in old PC BIOS.
65
+   */
70 66
   uint8_t  beginHead;
71
-          /**
72
-           * Sector part of Cylinder-head-sector address of the first block in
73
-           * the partition. Legal values are 1-63. Only used in old PC BIOS.
74
-           */
67
+  /**
68
+   * Sector part of Cylinder-head-sector address of the first block in
69
+   * the partition. Legal values are 1-63. Only used in old PC BIOS.
70
+   */
75 71
   unsigned beginSector : 6;
76
-           /** High bits cylinder for first block in partition. */
72
+  /** High bits cylinder for first block in partition. */
77 73
   unsigned beginCylinderHigh : 2;
78
-          /**
79
-           * Combine beginCylinderLow with beginCylinderHigh. Legal values
80
-           * are 0-1023.  Only used in old PC BIOS.
81
-           */
74
+  /**
75
+   * Combine beginCylinderLow with beginCylinderHigh. Legal values
76
+   * are 0-1023.  Only used in old PC BIOS.
77
+   */
82 78
   uint8_t  beginCylinderLow;
83
-          /**
84
-           * Partition type. See defines that begin with PART_TYPE_ for
85
-           * some Microsoft partition types.
86
-           */
79
+  /**
80
+   * Partition type. See defines that begin with PART_TYPE_ for
81
+   * some Microsoft partition types.
82
+   */
87 83
   uint8_t  type;
88
-          /**
89
-           * head part of cylinder-head-sector address of the last sector in the
90
-           * partition.  Legal values are 0-255. Only used in old PC BIOS.
91
-           */
84
+  /**
85
+   * head part of cylinder-head-sector address of the last sector in the
86
+   * partition.  Legal values are 0-255. Only used in old PC BIOS.
87
+   */
92 88
   uint8_t  endHead;
93
-          /**
94
-           * Sector part of cylinder-head-sector address of the last sector in
95
-           * the partition.  Legal values are 1-63. Only used in old PC BIOS.
96
-           */
89
+  /**
90
+   * Sector part of cylinder-head-sector address of the last sector in
91
+   * the partition.  Legal values are 1-63. Only used in old PC BIOS.
92
+   */
97 93
   unsigned endSector : 6;
98
-           /** High bits of end cylinder */
94
+  /** High bits of end cylinder */
99 95
   unsigned endCylinderHigh : 2;
100
-          /**
101
-           * Combine endCylinderLow with endCylinderHigh. Legal values
102
-           * are 0-1023.  Only used in old PC BIOS.
103
-           */
96
+  /**
97
+   * Combine endCylinderLow with endCylinderHigh. Legal values
98
+   * are 0-1023.  Only used in old PC BIOS.
99
+   */
104 100
   uint8_t  endCylinderLow;
105
-           /** Logical block address of the first block in the partition. */
106
-  uint32_t firstSector;
107
-           /** Length of the partition, in blocks. */
108
-  uint32_t totalSectors;
101
+
102
+  uint32_t firstSector;   // Logical block address of the first block in the partition.
103
+  uint32_t totalSectors;  // Length of the partition, in blocks.
109 104
 } PACKED;
110
-/** Type name for partitionTable */
111
-typedef struct partitionTable part_t;
112
-//------------------------------------------------------------------------------
105
+
106
+typedef struct partitionTable part_t; // Type name for partitionTable
107
+
113 108
 /**
114 109
  * \struct masterBootRecord
115 110
  *
@@ -118,22 +113,16 @@ typedef struct partitionTable part_t;
118 113
  * The first block of a storage device that is formatted with a MBR.
119 114
  */
120 115
 struct masterBootRecord {
121
-           /** Code Area for master boot program. */
122
-  uint8_t  codeArea[440];
123
-           /** Optional Windows NT disk signature. May contain boot code. */
124
-  uint32_t diskSignature;
125
-           /** Usually zero but may be more boot code. */
126
-  uint16_t usuallyZero;
127
-           /** Partition tables. */
128
-  part_t   part[4];
129
-           /** First MBR signature byte. Must be 0X55 */
130
-  uint8_t  mbrSig0;
131
-           /** Second MBR signature byte. Must be 0XAA */
132
-  uint8_t  mbrSig1;
116
+  uint8_t  codeArea[440]; // Code Area for master boot program.
117
+  uint32_t diskSignature; // Optional Windows NT disk signature. May contain boot code.
118
+  uint16_t usuallyZero;   // Usually zero but may be more boot code.
119
+  part_t   part[4];       // Partition tables.
120
+  uint8_t  mbrSig0;       // First MBR signature byte. Must be 0x55
121
+  uint8_t  mbrSig1;       // Second MBR signature byte. Must be 0xAA
133 122
 } PACKED;
134 123
 /** Type name for masterBootRecord */
135 124
 typedef struct masterBootRecord mbr_t;
136
-//------------------------------------------------------------------------------
125
+
137 126
 /**
138 127
  * \struct fat_boot
139 128
  *
@@ -141,285 +130,280 @@ typedef struct masterBootRecord mbr_t;
141 130
  *
142 131
  */
143 132
 struct fat_boot {
144
-         /**
145
-          * The first three bytes of the boot sector must be valid,
146
-          * executable x 86-based CPU instructions. This includes a
147
-          * jump instruction that skips the next nonexecutable bytes.
148
-          */
133
+  /**
134
+   * The first three bytes of the boot sector must be valid,
135
+   * executable x 86-based CPU instructions. This includes a
136
+   * jump instruction that skips the next nonexecutable bytes.
137
+   */
149 138
   uint8_t jump[3];
150
-         /**
151
-          * This is typically a string of characters that identifies
152
-          * the operating system that formatted the volume.
153
-          */
139
+  /**
140
+   * This is typically a string of characters that identifies
141
+   * the operating system that formatted the volume.
142
+   */
154 143
   char    oemId[8];
155
-          /**
156
-           * The size of a hardware sector. Valid decimal values for this
157
-           * field are 512, 1024, 2048, and 4096. For most disks used in
158
-           * the United States, the value of this field is 512.
159
-           */
144
+  /**
145
+   * The size of a hardware sector. Valid decimal values for this
146
+   * field are 512, 1024, 2048, and 4096. For most disks used in
147
+   * the United States, the value of this field is 512.
148
+   */
160 149
   uint16_t bytesPerSector;
161
-          /**
162
-           * Number of sectors per allocation unit. This value must be a
163
-           * power of 2 that is greater than 0. The legal values are
164
-           * 1, 2, 4, 8, 16, 32, 64, and 128.  128 should be avoided.
165
-           */
150
+  /**
151
+   * Number of sectors per allocation unit. This value must be a
152
+   * power of 2 that is greater than 0. The legal values are
153
+   * 1, 2, 4, 8, 16, 32, 64, and 128.  128 should be avoided.
154
+   */
166 155
   uint8_t  sectorsPerCluster;
167
-          /**
168
-           * The number of sectors preceding the start of the first FAT,
169
-           * including the boot sector. The value of this field is always 1.
170
-           */
156
+  /**
157
+   * The number of sectors preceding the start of the first FAT,
158
+   * including the boot sector. The value of this field is always 1.
159
+   */
171 160
   uint16_t reservedSectorCount;
172
-          /**
173
-           * The number of copies of the FAT on the volume.
174
-           * The value of this field is always 2.
175
-           */
161
+  /**
162
+   * The number of copies of the FAT on the volume.
163
+   * The value of this field is always 2.
164
+   */
176 165
   uint8_t  fatCount;
177
-          /**
178
-           * For FAT12 and FAT16 volumes, this field contains the count of
179
-           * 32-byte directory entries in the root directory. For FAT32 volumes,
180
-           * this field must be set to 0. For FAT12 and FAT16 volumes, this
181
-           * value should always specify a count that when multiplied by 32
182
-           * results in a multiple of bytesPerSector.  FAT16 volumes should
183
-           * use the value 512.
184
-           */
166
+  /**
167
+   * For FAT12 and FAT16 volumes, this field contains the count of
168
+   * 32-byte directory entries in the root directory. For FAT32 volumes,
169
+   * this field must be set to 0. For FAT12 and FAT16 volumes, this
170
+   * value should always specify a count that when multiplied by 32
171
+   * results in a multiple of bytesPerSector.  FAT16 volumes should
172
+   * use the value 512.
173
+   */
185 174
   uint16_t rootDirEntryCount;
186
-          /**
187
-           * This field is the old 16-bit total count of sectors on the volume.
188
-           * This count includes the count of all sectors in all four regions
189
-           * of the volume. This field can be 0; if it is 0, then totalSectors32
190
-           * must be nonzero.  For FAT32 volumes, this field must be 0. For
191
-           * FAT12 and FAT16 volumes, this field contains the sector count, and
192
-           * totalSectors32 is 0 if the total sector count fits
193
-           * (is less than 0x10000).
194
-           */
175
+  /**
176
+   * This field is the old 16-bit total count of sectors on the volume.
177
+   * This count includes the count of all sectors in all four regions
178
+   * of the volume. This field can be 0; if it is 0, then totalSectors32
179
+   * must be nonzero.  For FAT32 volumes, this field must be 0. For
180
+   * FAT12 and FAT16 volumes, this field contains the sector count, and
181
+   * totalSectors32 is 0 if the total sector count fits
182
+   * (is less than 0x10000).
183
+   */
195 184
   uint16_t totalSectors16;
196
-          /**
197
-           * This dates back to the old MS-DOS 1.x media determination and is
198
-           * no longer usually used for anything.  0xF8 is the standard value
199
-           * for fixed (nonremovable) media. For removable media, 0xF0 is
200
-           * frequently used. Legal values are 0xF0 or 0xF8-0xFF.
201
-           */
185
+  /**
186
+   * This dates back to the old MS-DOS 1.x media determination and is
187
+   * no longer usually used for anything.  0xF8 is the standard value
188
+   * for fixed (nonremovable) media. For removable media, 0xF0 is
189
+   * frequently used. Legal values are 0xF0 or 0xF8-0xFF.
190
+   */
202 191
   uint8_t  mediaType;
203
-          /**
204
-           * Count of sectors occupied by one FAT on FAT12/FAT16 volumes.
205
-           * On FAT32 volumes this field must be 0, and sectorsPerFat32
206
-           * contains the FAT size count.
207
-           */
192
+  /**
193
+   * Count of sectors occupied by one FAT on FAT12/FAT16 volumes.
194
+   * On FAT32 volumes this field must be 0, and sectorsPerFat32
195
+   * contains the FAT size count.
196
+   */
208 197
   uint16_t sectorsPerFat16;
209
-           /** Sectors per track for interrupt 0x13. Not used otherwise. */
210
-  uint16_t sectorsPerTrack;
211
-           /** Number of heads for interrupt 0x13.  Not used otherwise. */
212
-  uint16_t headCount;
213
-          /**
214
-           * Count of hidden sectors preceding the partition that contains this
215
-           * FAT volume. This field is generally only relevant for media
216
-           * visible on interrupt 0x13.
217
-           */
198
+
199
+  uint16_t sectorsPerTrack; // Sectors per track for interrupt 0x13. Not used otherwise.
200
+  uint16_t headCount;       // Number of heads for interrupt 0x13. Not used otherwise.
201
+
202
+  /**
203
+   * Count of hidden sectors preceding the partition that contains this
204
+   * FAT volume. This field is generally only relevant for media
205
+   * visible on interrupt 0x13.
206
+   */
218 207
   uint32_t hidddenSectors;
219
-          /**
220
-           * This field is the new 32-bit total count of sectors on the volume.
221
-           * This count includes the count of all sectors in all four regions
222
-           * of the volume.  This field can be 0; if it is 0, then
223
-           * totalSectors16 must be nonzero.
224
-           */
208
+  /**
209
+   * This field is the new 32-bit total count of sectors on the volume.
210
+   * This count includes the count of all sectors in all four regions
211
+   * of the volume.  This field can be 0; if it is 0, then
212
+   * totalSectors16 must be nonzero.
213
+   */
225 214
   uint32_t totalSectors32;
226
-           /**
227
-            * Related to the BIOS physical drive number. Floppy drives are
228
-            * identified as 0x00 and physical hard disks are identified as
229
-            * 0x80, regardless of the number of physical disk drives.
230
-            * Typically, this value is set prior to issuing an INT 13h BIOS
231
-            * call to specify the device to access. The value is only
232
-            * relevant if the device is a boot device.
233
-            */
215
+  /**
216
+   * Related to the BIOS physical drive number. Floppy drives are
217
+   * identified as 0x00 and physical hard disks are identified as
218
+   * 0x80, regardless of the number of physical disk drives.
219
+   * Typically, this value is set prior to issuing an INT 13h BIOS
220
+   * call to specify the device to access. The value is only
221
+   * relevant if the device is a boot device.
222
+   */
234 223
   uint8_t  driveNumber;
235
-           /** used by Windows NT - should be zero for FAT */
236
-  uint8_t  reserved1;
237
-           /** 0X29 if next three fields are valid */
238
-  uint8_t  bootSignature;
239
-           /**
240
-            * A random serial number created when formatting a disk,
241
-            * which helps to distinguish between disks.
242
-            * Usually generated by combining date and time.
243
-            */
224
+
225
+  uint8_t  reserved1;       // used by Windows NT - should be zero for FAT
226
+  uint8_t  bootSignature;   // 0x29 if next three fields are valid
227
+
228
+  /**
229
+   * A random serial number created when formatting a disk,
230
+   * which helps to distinguish between disks.
231
+   * Usually generated by combining date and time.
232
+   */
244 233
   uint32_t volumeSerialNumber;
245
-           /**
246
-            * A field once used to store the volume label. The volume label
247
-            * is now stored as a special file in the root directory.
248
-            */
234
+  /**
235
+   * A field once used to store the volume label. The volume label
236
+   * is now stored as a special file in the root directory.
237
+   */
249 238
   char     volumeLabel[11];
250
-           /**
251
-            * A field with a value of either FAT, FAT12 or FAT16,
252
-            * depending on the disk format.
253
-            */
239
+  /**
240
+   * A field with a value of either FAT, FAT12 or FAT16,
241
+   * depending on the disk format.
242
+   */
254 243
   char     fileSystemType[8];
255
-           /** X86 boot code */
256
-  uint8_t  bootCode[448];
257
-           /** must be 0X55 */
258
-  uint8_t  bootSectorSig0;
259
-           /** must be 0XAA */
260
-  uint8_t  bootSectorSig1;
244
+
245
+  uint8_t  bootCode[448];   // X86 boot code
246
+  uint8_t  bootSectorSig0;  // must be 0x55
247
+  uint8_t  bootSectorSig1;  // must be 0xAA
261 248
 } PACKED;
262
-/** Type name for FAT Boot Sector */
263
-typedef struct fat_boot fat_boot_t;
264
-//------------------------------------------------------------------------------
249
+
250
+typedef struct fat_boot fat_boot_t;   // Type name for FAT Boot Sector
251
+
265 252
 /**
266 253
  * \struct fat32_boot
267 254
  *
268 255
  * \brief Boot sector for a FAT32 volume.
269
- *
270 256
  */
271 257
 struct fat32_boot {
272
-         /**
273
-          * The first three bytes of the boot sector must be valid,
274
-          * executable x 86-based CPU instructions. This includes a
275
-          * jump instruction that skips the next nonexecutable bytes.
276
-          */
258
+  /**
259
+   * The first three bytes of the boot sector must be valid,
260
+   * executable x 86-based CPU instructions. This includes a
261
+   * jump instruction that skips the next nonexecutable bytes.
262
+   */
277 263
   uint8_t jump[3];
278
-         /**
279
-          * This is typically a string of characters that identifies
280
-          * the operating system that formatted the volume.
281
-          */
264
+  /**
265
+   * This is typically a string of characters that identifies
266
+   * the operating system that formatted the volume.
267
+   */
282 268
   char    oemId[8];
283
-          /**
284
-           * The size of a hardware sector. Valid decimal values for this
285
-           * field are 512, 1024, 2048, and 4096. For most disks used in
286
-           * the United States, the value of this field is 512.
287
-           */
269
+  /**
270
+   * The size of a hardware sector. Valid decimal values for this
271
+   * field are 512, 1024, 2048, and 4096. For most disks used in
272
+   * the United States, the value of this field is 512.
273
+   */
288 274
   uint16_t bytesPerSector;
289
-          /**
290
-           * Number of sectors per allocation unit. This value must be a
291
-           * power of 2 that is greater than 0. The legal values are
292
-           * 1, 2, 4, 8, 16, 32, 64, and 128.  128 should be avoided.
293
-           */
275
+  /**
276
+   * Number of sectors per allocation unit. This value must be a
277
+   * power of 2 that is greater than 0. The legal values are
278
+   * 1, 2, 4, 8, 16, 32, 64, and 128.  128 should be avoided.
279
+   */
294 280
   uint8_t  sectorsPerCluster;
295
-          /**
296
-           * The number of sectors preceding the start of the first FAT,
297
-           * including the boot sector. Must not be zero
298
-           */
281
+  /**
282
+   * The number of sectors preceding the start of the first FAT,
283
+   * including the boot sector. Must not be zero
284
+   */
299 285
   uint16_t reservedSectorCount;
300
-          /**
301
-           * The number of copies of the FAT on the volume.
302
-           * The value of this field is always 2.
303
-           */
286
+  /**
287
+   * The number of copies of the FAT on the volume.
288
+   * The value of this field is always 2.
289
+   */
304 290
   uint8_t  fatCount;
305
-          /**
306
-           * FAT12/FAT16 only. For FAT32 volumes, this field must be set to 0.
307
-           */
291
+  /**
292
+   * FAT12/FAT16 only. For FAT32 volumes, this field must be set to 0.
293
+   */
308 294
   uint16_t rootDirEntryCount;
309
-          /**
310
-           * For FAT32 volumes, this field must be 0.
311
-           */
295
+  /**
296
+   * For FAT32 volumes, this field must be 0.
297
+   */
312 298
   uint16_t totalSectors16;
313
-          /**
314
-           * This dates back to the old MS-DOS 1.x media determination and is
315
-           * no longer usually used for anything.  0xF8 is the standard value
316
-           * for fixed (nonremovable) media. For removable media, 0xF0 is
317
-           * frequently used. Legal values are 0xF0 or 0xF8-0xFF.
318
-           */
299
+  /**
300
+   * This dates back to the old MS-DOS 1.x media determination and is
301
+   * no longer usually used for anything.  0xF8 is the standard value
302
+   * for fixed (nonremovable) media. For removable media, 0xF0 is
303
+   * frequently used. Legal values are 0xF0 or 0xF8-0xFF.
304
+   */
319 305
   uint8_t  mediaType;
320
-          /**
321
-           * On FAT32 volumes this field must be 0, and sectorsPerFat32
322
-           * contains the FAT size count.
323
-           */
306
+  /**
307
+   * On FAT32 volumes this field must be 0, and sectorsPerFat32
308
+   * contains the FAT size count.
309
+   */
324 310
   uint16_t sectorsPerFat16;
325
-           /** Sectors per track for interrupt 0x13. Not used otherwise. */
326
-  uint16_t sectorsPerTrack;
327
-           /** Number of heads for interrupt 0x13.  Not used otherwise. */
328
-  uint16_t headCount;
329
-          /**
330
-           * Count of hidden sectors preceding the partition that contains this
331
-           * FAT volume. This field is generally only relevant for media
332
-           * visible on interrupt 0x13.
333
-           */
311
+
312
+  uint16_t sectorsPerTrack; // Sectors per track for interrupt 0x13. Not used otherwise.
313
+  uint16_t headCount;       // Number of heads for interrupt 0x13. Not used otherwise.
314
+
315
+  /**
316
+   * Count of hidden sectors preceding the partition that contains this
317
+   * FAT volume. This field is generally only relevant for media
318
+   * visible on interrupt 0x13.
319
+   */
334 320
   uint32_t hidddenSectors;
335
-          /**
336
-           * Contains the total number of sectors in the FAT32 volume.
337
-           */
321
+  /**
322
+   * Contains the total number of sectors in the FAT32 volume.
323
+   */
338 324
   uint32_t totalSectors32;
339
-         /**
340
-           * Count of sectors occupied by one FAT on FAT32 volumes.
341
-           */
325
+  /**
326
+   * Count of sectors occupied by one FAT on FAT32 volumes.
327
+   */
342 328
   uint32_t sectorsPerFat32;
343
-          /**
344
-           * This field is only defined for FAT32 media and does not exist on
345
-           * FAT12 and FAT16 media.
346
-           * Bits 0-3 -- Zero-based number of active FAT.
347
-           *             Only valid if mirroring is disabled.
348
-           * Bits 4-6 -- Reserved.
349
-           * Bit 7  -- 0 means the FAT is mirrored at runtime into all FATs.
350
-           *        -- 1 means only one FAT is active; it is the one referenced
351
-           *             in bits 0-3.
352
-           * Bits 8-15  -- Reserved.
353
-           */
329
+  /**
330
+   * This field is only defined for FAT32 media and does not exist on
331
+   * FAT12 and FAT16 media.
332
+   * Bits 0-3 -- Zero-based number of active FAT.
333
+   *             Only valid if mirroring is disabled.
334
+   * Bits 4-6 -- Reserved.
335
+   * Bit 7  -- 0 means the FAT is mirrored at runtime into all FATs.
336
+   *        -- 1 means only one FAT is active; it is the one referenced
337
+   *             in bits 0-3.
338
+   * Bits 8-15  -- Reserved.
339
+   */
354 340
   uint16_t fat32Flags;
355
-          /**
356
-           * FAT32 version. High byte is major revision number.
357
-           * Low byte is minor revision number. Only 0.0 define.
358
-           */
341
+  /**
342
+   * FAT32 version. High byte is major revision number.
343
+   * Low byte is minor revision number. Only 0.0 define.
344
+   */
359 345
   uint16_t fat32Version;
360
-          /**
361
-           * Cluster number of the first cluster of the root directory for FAT32.
362
-           * This usually 2 but not required to be 2.
363
-           */
346
+  /**
347
+   * Cluster number of the first cluster of the root directory for FAT32.
348
+   * This usually 2 but not required to be 2.
349
+   */
364 350
   uint32_t fat32RootCluster;
365
-          /**
366
-           * Sector number of FSINFO structure in the reserved area of the
367
-           * FAT32 volume. Usually 1.
368
-           */
351
+  /**
352
+   * Sector number of FSINFO structure in the reserved area of the
353
+   * FAT32 volume. Usually 1.
354
+   */
369 355
   uint16_t fat32FSInfo;
370
-          /**
371
-           * If nonzero, indicates the sector number in the reserved area
372
-           * of the volume of a copy of the boot record. Usually 6.
373
-           * No value other than 6 is recommended.
374
-           */
356
+  /**
357
+   * If nonzero, indicates the sector number in the reserved area
358
+   * of the volume of a copy of the boot record. Usually 6.
359
+   * No value other than 6 is recommended.
360
+   */
375 361
   uint16_t fat32BackBootBlock;
376
-          /**
377
-           * Reserved for future expansion. Code that formats FAT32 volumes
378
-           * should always set all of the bytes of this field to 0.
379
-           */
362
+  /**
363
+   * Reserved for future expansion. Code that formats FAT32 volumes
364
+   * should always set all of the bytes of this field to 0.
365
+   */
380 366
   uint8_t  fat32Reserved[12];
381
-           /**
382
-            * Related to the BIOS physical drive number. Floppy drives are
383
-            * identified as 0x00 and physical hard disks are identified as
384
-            * 0x80, regardless of the number of physical disk drives.
385
-            * Typically, this value is set prior to issuing an INT 13h BIOS
386
-            * call to specify the device to access. The value is only
387
-            * relevant if the device is a boot device.
388
-            */
367
+  /**
368
+   * Related to the BIOS physical drive number. Floppy drives are
369
+   * identified as 0x00 and physical hard disks are identified as
370
+   * 0x80, regardless of the number of physical disk drives.
371
+   * Typically, this value is set prior to issuing an INT 13h BIOS
372
+   * call to specify the device to access. The value is only
373
+   * relevant if the device is a boot device.
374
+   */
389 375
   uint8_t  driveNumber;
390
-           /** used by Windows NT - should be zero for FAT */
391
-  uint8_t  reserved1;
392
-           /** 0X29 if next three fields are valid */
393
-  uint8_t  bootSignature;
394
-           /**
395
-            * A random serial number created when formatting a disk,
396
-            * which helps to distinguish between disks.
397
-            * Usually generated by combining date and time.
398
-            */
376
+
377
+  uint8_t  reserved1;       // Used by Windows NT - should be zero for FAT
378
+  uint8_t  bootSignature;   // 0x29 if next three fields are valid
379
+
380
+  /**
381
+   * A random serial number created when formatting a disk,
382
+   * which helps to distinguish between disks.
383
+   * Usually generated by combining date and time.
384
+   */
399 385
   uint32_t volumeSerialNumber;
400
-           /**
401
-            * A field once used to store the volume label. The volume label
402
-            * is now stored as a special file in the root directory.
403
-            */
386
+  /**
387
+   * A field once used to store the volume label. The volume label
388
+   * is now stored as a special file in the root directory.
389
+   */
404 390
   char     volumeLabel[11];
405
-           /**
406
-            * A text field with a value of FAT32.
407
-            */
391
+  /**
392
+   * A text field with a value of FAT32.
393
+   */
408 394
   char     fileSystemType[8];
409
-           /** X86 boot code */
410
-  uint8_t  bootCode[420];
411
-           /** must be 0X55 */
412
-  uint8_t  bootSectorSig0;
413
-           /** must be 0XAA */
414
-  uint8_t  bootSectorSig1;
395
+
396
+  uint8_t  bootCode[420];   // X86 boot code
397
+  uint8_t  bootSectorSig0;  // must be 0x55
398
+  uint8_t  bootSectorSig1;  // must be 0xAA
399
+
415 400
 } PACKED;
416
-/** Type name for FAT32 Boot Sector */
417
-typedef struct fat32_boot fat32_boot_t;
418
-//------------------------------------------------------------------------------
419
-/** Lead signature for a FSINFO sector */
420
-uint32_t const FSINFO_LEAD_SIG = 0x41615252;
421
-/** Struct signature for a FSINFO sector */
422
-uint32_t const FSINFO_STRUCT_SIG = 0x61417272;
401
+
402
+typedef struct fat32_boot fat32_boot_t; // Type name for FAT32 Boot Sector
403
+
404
+uint32_t const FSINFO_LEAD_SIG   = 0x41615252,  // 'AaRR' Lead signature for a FSINFO sector
405
+               FSINFO_STRUCT_SIG = 0x61417272;  // 'aArr' Struct signature for a FSINFO sector
406
+
423 407
 /**
424 408
  * \struct fat32_fsinfo
425 409
  *
@@ -427,12 +411,9 @@ uint32_t const FSINFO_STRUCT_SIG = 0x61417272;
427 411
  *
428 412
  */
429 413
 struct fat32_fsinfo {
430
-           /** must be 0X52, 0X52, 0X61, 0X41 */
431
-  uint32_t  leadSignature;
432
-           /** must be zero */
433
-  uint8_t  reserved1[480];
434
-           /** must be 0X72, 0X72, 0X41, 0X61 */
435
-  uint32_t  structSignature;
414
+  uint32_t  leadSignature;    // must be 0x52, 0x52, 0x61, 0x41 'RRaA'
415
+  uint8_t  reserved1[480];    // must be zero
416
+  uint32_t  structSignature;  // must be 0x72, 0x72, 0x41, 0x61 'rrAa'
436 417
           /**
437 418
            * Contains the last known free cluster count on the volume.
438 419
            * If the value is 0xFFFFFFFF, then the free count is unknown
@@ -448,30 +429,22 @@ struct fat32_fsinfo {
448 429
            * should start looking at cluster 2.
449 430
            */
450 431
   uint32_t nextFree;
451
-           /** must be zero */
452
-  uint8_t  reserved2[12];
453
-           /** must be 0X00, 0X00, 0X55, 0XAA */
454
-  uint8_t  tailSignature[4];
432
+
433
+  uint8_t  reserved2[12];     // must be zero
434
+  uint8_t  tailSignature[4];  // must be 0x00, 0x00, 0x55, 0xAA
455 435
 } PACKED;
456
-/** Type name for FAT32 FSINFO Sector */
457
-typedef struct fat32_fsinfo fat32_fsinfo_t;
458
-//------------------------------------------------------------------------------
436
+
437
+typedef struct fat32_fsinfo fat32_fsinfo_t; // Type name for FAT32 FSINFO Sector
438
+
459 439
 // End Of Chain values for FAT entries
460
-/** FAT12 end of chain value used by Microsoft. */
461
-uint16_t const FAT12EOC = 0XFFF;
462
-/** Minimum value for FAT12 EOC.  Use to test for EOC. */
463
-uint16_t const FAT12EOC_MIN = 0XFF8;
464
-/** FAT16 end of chain value used by Microsoft. */
465
-uint16_t const FAT16EOC = 0XFFFF;
466
-/** Minimum value for FAT16 EOC.  Use to test for EOC. */
467
-uint16_t const FAT16EOC_MIN = 0XFFF8;
468
-/** FAT32 end of chain value used by Microsoft. */
469
-uint32_t const FAT32EOC = 0X0FFFFFFF;
470
-/** Minimum value for FAT32 EOC.  Use to test for EOC. */
471
-uint32_t const FAT32EOC_MIN = 0X0FFFFFF8;
472
-/** Mask a for FAT32 entry. Entries are 28 bits. */
473
-uint32_t const FAT32MASK = 0X0FFFFFFF;
474
-//------------------------------------------------------------------------------
440
+uint16_t const FAT12EOC = 0xFFF,          // FAT12 end of chain value used by Microsoft.
441
+               FAT12EOC_MIN = 0xFF8,      // Minimum value for FAT12 EOC.  Use to test for EOC.
442
+               FAT16EOC = 0xFFFF,         // FAT16 end of chain value used by Microsoft.
443
+               FAT16EOC_MIN = 0xFFF8;     // Minimum value for FAT16 EOC.  Use to test for EOC.
444
+uint32_t const FAT32EOC = 0x0FFFFFFF,     // FAT32 end of chain value used by Microsoft.
445
+               FAT32EOC_MIN = 0x0FFFFFF8, // Minimum value for FAT32 EOC.  Use to test for EOC.
446
+               FAT32MASK = 0x0FFFFFFF;    // Mask a for FAT32 entry. Entries are 28 bits.
447
+
475 448
 /**
476 449
  * \struct directoryEntry
477 450
  * \brief FAT short directory entry
@@ -503,54 +476,54 @@ uint32_t const FAT32MASK = 0X0FFFFFFF;
503 476
  * The valid time range is from Midnight 00:00:00 to 23:59:58.
504 477
  */
505 478
 struct directoryEntry {
506
-           /** Short 8.3 name.
507
-            *
508
-            * The first eight bytes contain the file name with blank fill.
509
-            * The last three bytes contain the file extension with blank fill.
510
-            */
479
+  /**
480
+   * Short 8.3 name.
481
+   *
482
+   * The first eight bytes contain the file name with blank fill.
483
+   * The last three bytes contain the file extension with blank fill.
484
+   */
511 485
   uint8_t  name[11];
512
-          /** Entry attributes.
513
-           *
514
-           * The upper two bits of the attribute byte are reserved and should
515
-           * always be set to 0 when a file is created and never modified or
516
-           * looked at after that.  See defines that begin with DIR_ATT_.
517
-           */
486
+  /**
487
+   * Entry attributes.
488
+   *
489
+   * The upper two bits of the attribute byte are reserved and should
490
+   * always be set to 0 when a file is created and never modified or
491
+   * looked at after that.  See defines that begin with DIR_ATT_.
492
+   */
518 493
   uint8_t  attributes;
519
-          /**
520
-           * Reserved for use by Windows NT. Set value to 0 when a file is
521
-           * created and never modify or look at it after that.
522
-           */
494
+  /**
495
+   * Reserved for use by Windows NT. Set value to 0 when a file is
496
+   * created and never modify or look at it after that.
497
+   */
523 498
   uint8_t  reservedNT;
524
-          /**
525
-           * The granularity of the seconds part of creationTime is 2 seconds
526
-           * so this field is a count of tenths of a second and it's valid
527
-           * value range is 0-199 inclusive. (WHG note - seems to be hundredths)
528
-           */
499
+  /**
500
+   * The granularity of the seconds part of creationTime is 2 seconds
501
+   * so this field is a count of tenths of a second and it's valid
502
+   * value range is 0-199 inclusive. (WHG note - seems to be hundredths)
503
+   */
529 504
   uint8_t  creationTimeTenths;
530
-           /** Time file was created. */
531
-  uint16_t creationTime;
532
-           /** Date file was created. */
533
-  uint16_t creationDate;
534
-          /**
535
-           * Last access date. Note that there is no last access time, only
536
-           * a date.  This is the date of last read or write. In the case of
537
-           * a write, this should be set to the same date as lastWriteDate.
538
-           */
505
+
506
+  uint16_t creationTime;    // Time file was created.
507
+  uint16_t creationDate;    // Date file was created.
508
+
509
+  /**
510
+   * Last access date. Note that there is no last access time, only
511
+   * a date.  This is the date of last read or write. In the case of
512
+   * a write, this should be set to the same date as lastWriteDate.
513
+   */
539 514
   uint16_t lastAccessDate;
540
-          /**
541
-           * High word of this entry's first cluster number (always 0 for a
542
-           * FAT12 or FAT16 volume).
543
-           */
515
+  /**
516
+   * High word of this entry's first cluster number (always 0 for a
517
+   * FAT12 or FAT16 volume).
518
+   */
544 519
   uint16_t firstClusterHigh;
545
-           /** Time of last write. File creation is considered a write. */
546
-  uint16_t lastWriteTime;
547
-           /** Date of last write. File creation is considered a write. */
548
-  uint16_t lastWriteDate;
549
-           /** Low word of this entry's first cluster number. */
550
-  uint16_t firstClusterLow;
551
-           /** 32-bit unsigned holding this file's size in bytes. */
552
-  uint32_t fileSize;
520
+
521
+  uint16_t lastWriteTime;   // Time of last write. File creation is considered a write.
522
+  uint16_t lastWriteDate;   // Date of last write. File creation is considered a write.
523
+  uint16_t firstClusterLow; // Low word of this entry's first cluster number.
524
+  uint32_t fileSize;        // 32-bit unsigned holding this file's size in bytes.
553 525
 } PACKED;
526
+
554 527
 /**
555 528
  * \struct directoryVFATEntry
556 529
  * \brief VFAT long filename directory entry
@@ -568,54 +541,36 @@ struct directoryVFATEntry {
568 541
    *  bit 0-4: the position of this long filename block (first block is 1)
569 542
    */
570 543
   uint8_t  sequenceNumber;
571
-  /** First set of UTF-16 characters */
572
-  uint16_t name1[5];//UTF-16
573
-  /** attributes (at the same location as in directoryEntry), always 0x0F */
574
-  uint8_t  attributes;
575
-  /** Reserved for use by Windows NT. Always 0. */
576
-  uint8_t  reservedNT;
577
-  /** Checksum of the short 8.3 filename, can be used to checked if the file system as modified by a not-long-filename aware implementation. */
578
-  uint8_t  checksum;
579
-  /** Second set of UTF-16 characters */
580
-  uint16_t name2[6];//UTF-16
581
-  /** firstClusterLow is always zero for longFilenames */
582
-  uint16_t firstClusterLow;
583
-  /** Third set of UTF-16 characters */
584
-  uint16_t name3[2];//UTF-16
544
+
545
+  uint16_t name1[5];        // First set of UTF-16 characters
546
+  uint8_t  attributes;      // attributes (at the same location as in directoryEntry), always 0x0F
547
+  uint8_t  reservedNT;      // Reserved for use by Windows NT. Always 0.
548
+  uint8_t  checksum;        // Checksum of the short 8.3 filename, can be used to checked if the file system as modified by a not-long-filename aware implementation.
549
+  uint16_t name2[6];        // Second set of UTF-16 characters
550
+  uint16_t firstClusterLow; // firstClusterLow is always zero for longFilenames
551
+  uint16_t name3[2];        // Third set of UTF-16 characters
585 552
 } PACKED;
586
-//------------------------------------------------------------------------------
553
+
587 554
 // Definitions for directory entries
588 555
 //
589
-/** Type name for directoryEntry */
590
-typedef struct directoryEntry dir_t;
591
-/** Type name for directoryVFATEntry */
592
-typedef struct directoryVFATEntry vfat_t;
593
-/** escape for name[0] = 0XE5 */
594
-uint8_t const DIR_NAME_0XE5 = 0X05;
595
-/** name[0] value for entry that is free after being "deleted" */
596
-uint8_t const DIR_NAME_DELETED = 0XE5;
597
-/** name[0] value for entry that is free and no allocated entries follow */
598
-uint8_t const DIR_NAME_FREE = 0X00;
599
-/** file is read-only */
600
-uint8_t const DIR_ATT_READ_ONLY = 0X01;
601
-/** File should hidden in directory listings */
602
-uint8_t const DIR_ATT_HIDDEN = 0X02;
603
-/** Entry is for a system file */
604
-uint8_t const DIR_ATT_SYSTEM = 0X04;
605
-/** Directory entry contains the volume label */
606
-uint8_t const DIR_ATT_VOLUME_ID = 0X08;
607
-/** Entry is for a directory */
608
-uint8_t const DIR_ATT_DIRECTORY = 0X10;
609
-/** Old DOS archive bit for backup support */
610
-uint8_t const DIR_ATT_ARCHIVE = 0X20;
611
-/** Test value for long name entry.  Test is
612
-  (d->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME. */
613
-uint8_t const DIR_ATT_LONG_NAME = 0X0F;
614
-/** Test mask for long name entry */
615
-uint8_t const DIR_ATT_LONG_NAME_MASK = 0X3F;
616
-/** defined attribute bits */
617
-uint8_t const DIR_ATT_DEFINED_BITS = 0X3F;
618
-/** Directory entry is part of a long name
556
+typedef struct directoryEntry dir_t;          // Type name for directoryEntry
557
+typedef struct directoryVFATEntry vfat_t;     // Type name for directoryVFATEntry
558
+
559
+uint8_t const DIR_NAME_0xE5     = 0x05,       // escape for name[0] = 0xE5
560
+              DIR_NAME_DELETED  = 0xE5,       // name[0] value for entry that is free after being "deleted"
561
+              DIR_NAME_FREE     = 0x00,       // name[0] value for entry that is free and no allocated entries follow
562
+              DIR_ATT_READ_ONLY = 0x01,       // file is read-only
563
+              DIR_ATT_HIDDEN    = 0x02,       // File should hidden in directory listings
564
+              DIR_ATT_SYSTEM    = 0x04,       // Entry is for a system file
565
+              DIR_ATT_VOLUME_ID = 0x08,       // Directory entry contains the volume label
566
+              DIR_ATT_DIRECTORY = 0x10,       // Entry is for a directory
567
+              DIR_ATT_ARCHIVE   = 0x20,       // Old DOS archive bit for backup support
568
+              DIR_ATT_LONG_NAME = 0x0F,       // Test value for long name entry.  Test is (d->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME.
569
+              DIR_ATT_LONG_NAME_MASK = 0x3F,  // Test mask for long name entry
570
+              DIR_ATT_DEFINED_BITS = 0x3F;    // defined attribute bits
571
+
572
+/**
573
+ * Directory entry is part of a long name
619 574
  * \param[in] dir Pointer to a directory entry.
620 575
  *
621 576
  * \return true if the entry is for part of a long name else false.
@@ -623,9 +578,12 @@ uint8_t const DIR_ATT_DEFINED_BITS = 0X3F;
623 578
 static inline uint8_t DIR_IS_LONG_NAME(const dir_t* dir) {
624 579
   return (dir->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME;
625 580
 }
581
+
626 582
 /** Mask for file/subdirectory tests */
627 583
 uint8_t const DIR_ATT_FILE_TYPE_MASK = (DIR_ATT_VOLUME_ID | DIR_ATT_DIRECTORY);
628
-/** Directory entry is for a file
584
+
585
+/**
586
+ * Directory entry is for a file
629 587
  * \param[in] dir Pointer to a directory entry.
630 588
  *
631 589
  * \return true if the entry is for a normal file else false.
@@ -633,7 +591,9 @@ uint8_t const DIR_ATT_FILE_TYPE_MASK = (DIR_ATT_VOLUME_ID | DIR_ATT_DIRECTORY);
633 591
 static inline uint8_t DIR_IS_FILE(const dir_t* dir) {
634 592
   return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == 0;
635 593
 }
636
-/** Directory entry is for a subdirectory
594
+
595
+/**
596
+ * Directory entry is for a subdirectory
637 597
  * \param[in] dir Pointer to a directory entry.
638 598
  *
639 599
  * \return true if the entry is for a subdirectory else false.
@@ -641,7 +601,9 @@ static inline uint8_t DIR_IS_FILE(const dir_t* dir) {
641 601
 static inline uint8_t DIR_IS_SUBDIR(const dir_t* dir) {
642 602
   return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == DIR_ATT_DIRECTORY;
643 603
 }
644
-/** Directory entry is for a file or subdirectory
604
+
605
+/**
606
+ * Directory entry is for a file or subdirectory
645 607
  * \param[in] dir Pointer to a directory entry.
646 608
  *
647 609
  * \return true if the entry is for a normal file or subdirectory else false.
@@ -649,7 +611,5 @@ static inline uint8_t DIR_IS_SUBDIR(const dir_t* dir) {
649 611
 static inline uint8_t DIR_IS_FILE_OR_SUBDIR(const dir_t* dir) {
650 612
   return (dir->attributes & DIR_ATT_VOLUME_ID) == 0;
651 613
 }
652
-#endif  // SdFatStructs_h
653
-
654 614
 
655
-#endif
615
+#endif // SDFATSTRUCTS_H

+ 23
- 23
Marlin/SdFatUtil.cpp 파일 보기

@@ -26,13 +26,15 @@
26 26
  *
27 27
  * This file is part of the Arduino Sd2Card Library
28 28
  */
29
-#include "Marlin.h"
29
+#include "MarlinConfig.h"
30 30
 
31 31
 #if ENABLED(SDSUPPORT)
32
+
32 33
 #include "SdFatUtil.h"
34
+#include "serial.h"
33 35
 
34
-//------------------------------------------------------------------------------
35
-/** Amount of free RAM
36
+/**
37
+ * Amount of free RAM
36 38
  * \return The number of free bytes.
37 39
  */
38 40
 #ifdef __arm__
@@ -44,7 +46,8 @@ int SdFatUtil::FreeRam() {
44 46
 #else  // __arm__
45 47
 extern char* __brkval;
46 48
 extern char __bss_end;
47
-/** Amount of free RAM
49
+/**
50
+ * Amount of free RAM
48 51
  * \return The number of free bytes.
49 52
  */
50 53
 int SdFatUtil::FreeRam() {
@@ -53,8 +56,8 @@ int SdFatUtil::FreeRam() {
53 56
 }
54 57
 #endif  // __arm
55 58
 
56
-//------------------------------------------------------------------------------
57
-/** %Print a string in flash memory.
59
+/**
60
+ * %Print a string in flash memory.
58 61
  *
59 62
  * \param[in] pr Print object for output.
60 63
  * \param[in] str Pointer to string stored in flash memory.
@@ -62,30 +65,27 @@ int SdFatUtil::FreeRam() {
62 65
 void SdFatUtil::print_P(PGM_P str) {
63 66
   for (uint8_t c; (c = pgm_read_byte(str)); str++) MYSERIAL.write(c);
64 67
 }
65
-//------------------------------------------------------------------------------
66
-/** %Print a string in flash memory followed by a CR/LF.
68
+
69
+/**
70
+ * %Print a string in flash memory followed by a CR/LF.
67 71
  *
68 72
  * \param[in] pr Print object for output.
69 73
  * \param[in] str Pointer to string stored in flash memory.
70 74
  */
71
-void SdFatUtil::println_P(PGM_P str) {
72
-  print_P(str);
73
-  MYSERIAL.println();
74
-}
75
-//------------------------------------------------------------------------------
76
-/** %Print a string in flash memory to Serial.
75
+void SdFatUtil::println_P(PGM_P str) { print_P(str); MYSERIAL.println(); }
76
+
77
+/**
78
+ * %Print a string in flash memory to Serial.
77 79
  *
78 80
  * \param[in] str Pointer to string stored in flash memory.
79 81
  */
80
-void SdFatUtil::SerialPrint_P(PGM_P str) {
81
-  print_P(str);
82
-}
83
-//------------------------------------------------------------------------------
84
-/** %Print a string in flash memory to Serial followed by a CR/LF.
82
+void SdFatUtil::SerialPrint_P(PGM_P str) { print_P(str); }
83
+
84
+/**
85
+ * %Print a string in flash memory to Serial followed by a CR/LF.
85 86
  *
86 87
  * \param[in] str Pointer to string stored in flash memory.
87 88
  */
88
-void SdFatUtil::SerialPrintln_P(PGM_P str) {
89
-  println_P(str);
90
-}
91
-#endif
89
+void SdFatUtil::SerialPrintln_P(PGM_P str) { println_P(str); }
90
+
91
+#endif // SDSUPPORT

+ 3
- 8
Marlin/SdFatUtil.h 파일 보기

@@ -26,11 +26,8 @@
26 26
  *
27 27
  * This file is part of the Arduino Sd2Card Library
28 28
  */
29
-#ifndef SdFatUtil_h
30
-#define SdFatUtil_h
31
-
32
-#include "Marlin.h"
33
-#if ENABLED(SDSUPPORT)
29
+#ifndef _SDFATUTIL_H_
30
+#define _SDFATUTIL_H_
34 31
 
35 32
 /**
36 33
  * \file
@@ -51,6 +48,4 @@ namespace SdFatUtil {
51 48
 
52 49
 using namespace SdFatUtil;  // NOLINT
53 50
 
54
-#endif // SDSUPPORT
55
-
56
-#endif // SdFatUtil_h
51
+#endif // _SDFATUTIL_H_

+ 26
- 28
Marlin/SdFile.cpp 파일 보기

@@ -26,21 +26,24 @@
26 26
  *
27 27
  * This file is part of the Arduino Sd2Card Library
28 28
  */
29
-#include "Marlin.h"
29
+#include "MarlinConfig.h"
30 30
 
31 31
 #if ENABLED(SDSUPPORT)
32
+
32 33
 #include "SdFile.h"
33
-/**  Create a file object and open it in the current working directory.
34
+
35
+/**
36
+ *  Create a file object and open it in the current working directory.
34 37
  *
35 38
  * \param[in] path A path with a valid 8.3 DOS name for a file to be opened.
36 39
  *
37 40
  * \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive
38 41
  * OR of open flags. see SdBaseFile::open(SdBaseFile*, const char*, uint8_t).
39 42
  */
40
-SdFile::SdFile(const char* path, uint8_t oflag) : SdBaseFile(path, oflag) {
41
-}
42
-//------------------------------------------------------------------------------
43
-/** Write data to an open file.
43
+SdFile::SdFile(const char* path, uint8_t oflag) : SdBaseFile(path, oflag) { }
44
+
45
+/**
46
+ * Write data to an open file.
44 47
  *
45 48
  * \note Data is moved to the cache but may not be written to the
46 49
  * storage device until sync() is called.
@@ -55,41 +58,37 @@ SdFile::SdFile(const char* path, uint8_t oflag) : SdBaseFile(path, oflag) {
55 58
  * for a read-only file, device is full, a corrupt file system or an I/O error.
56 59
  *
57 60
  */
58
-int16_t SdFile::write(const void* buf, uint16_t nbyte) {
59
-  return SdBaseFile::write(buf, nbyte);
60
-}
61
-//------------------------------------------------------------------------------
62
-/** Write a byte to a file. Required by the Arduino Print class.
61
+int16_t SdFile::write(const void* buf, uint16_t nbyte) { return SdBaseFile::write(buf, nbyte); }
62
+
63
+/**
64
+ * Write a byte to a file. Required by the Arduino Print class.
63 65
  * \param[in] b the byte to be written.
64 66
  * Use writeError to check for errors.
65 67
  */
66 68
 #if ARDUINO >= 100
67
-  size_t SdFile::write(uint8_t b) {
68
-    return SdBaseFile::write(&b, 1);
69
-  }
69
+  size_t SdFile::write(uint8_t b) { return SdBaseFile::write(&b, 1); }
70 70
 #else
71
-  void SdFile::write(uint8_t b) {
72
-    SdBaseFile::write(&b, 1);
73
-  }
71
+  void SdFile::write(uint8_t b) { SdBaseFile::write(&b, 1); }
74 72
 #endif
75
-//------------------------------------------------------------------------------
76
-/** Write a string to a file. Used by the Arduino Print class.
73
+
74
+/**
75
+ * Write a string to a file. Used by the Arduino Print class.
77 76
  * \param[in] str Pointer to the string.
78 77
  * Use writeError to check for errors.
79 78
  */
80
-void SdFile::write(const char* str) {
81
-  SdBaseFile::write(str, strlen(str));
82
-}
83
-//------------------------------------------------------------------------------
84
-/** Write a PROGMEM string to a file.
79
+void SdFile::write(const char* str) { SdBaseFile::write(str, strlen(str)); }
80
+
81
+/**
82
+ * Write a PROGMEM string to a file.
85 83
  * \param[in] str Pointer to the PROGMEM string.
86 84
  * Use writeError to check for errors.
87 85
  */
88 86
 void SdFile::write_P(PGM_P str) {
89 87
   for (uint8_t c; (c = pgm_read_byte(str)); str++) write(c);
90 88
 }
91
-//------------------------------------------------------------------------------
92
-/** Write a PROGMEM string followed by CR/LF to a file.
89
+
90
+/**
91
+ * Write a PROGMEM string followed by CR/LF to a file.
93 92
  * \param[in] str Pointer to the PROGMEM string.
94 93
  * Use writeError to check for errors.
95 94
  */
@@ -98,5 +97,4 @@ void SdFile::writeln_P(PGM_P str) {
98 97
   write_P(PSTR("\r\n"));
99 98
 }
100 99
 
101
-
102
-#endif
100
+#endif // SDSUPPORT

+ 9
- 12
Marlin/SdFile.h 파일 보기

@@ -21,23 +21,22 @@
21 21
  */
22 22
 
23 23
 /**
24
+ * \file
25
+ * \brief SdFile class
26
+ */
27
+
28
+/**
24 29
  * Arduino SdFat Library
25 30
  * Copyright (C) 2009 by William Greiman
26 31
  *
27 32
  * This file is part of the Arduino Sd2Card Library
28 33
  */
29
-/**
30
- * \file
31
- * \brief SdFile class
32
- */
33
-#include "Marlin.h"
34
+#ifndef _SDFILE_H_
35
+#define _SDFILE_H_
34 36
 
35
-#if ENABLED(SDSUPPORT)
36 37
 #include "SdBaseFile.h"
37 38
 #include <Print.h>
38
-#ifndef SdFile_h
39
-#define SdFile_h
40
-//------------------------------------------------------------------------------
39
+
41 40
 /**
42 41
  * \class SdFile
43 42
  * \brief SdBaseFile with Print.
@@ -57,7 +56,5 @@ class SdFile : public SdBaseFile, public Print {
57 56
   void write_P(PGM_P str);
58 57
   void writeln_P(PGM_P str);
59 58
 };
60
-#endif  // SdFile_h
61
-
62 59
 
63
-#endif
60
+#endif // _SDFILE_H_

+ 36
- 58
Marlin/SdInfo.h 파일 보기

@@ -26,12 +26,11 @@
26 26
  *
27 27
  * This file is part of the Arduino Sd2Card Library
28 28
  */
29
-#include "Marlin.h"
30
-#if ENABLED(SDSUPPORT)
29
+#ifndef _SDINFO_H_
30
+#define _SDINFO_H_
31 31
 
32
-#ifndef SdInfo_h
33
-#define SdInfo_h
34 32
 #include <stdint.h>
33
+
35 34
 // Based on the document:
36 35
 //
37 36
 // SD Specifications
@@ -42,63 +41,43 @@
42 41
 // May 18, 2010
43 42
 //
44 43
 // http://www.sdcard.org/developers/tech/sdcard/pls/simplified_specs
45
-//------------------------------------------------------------------------------
44
+
46 45
 // SD card commands
47
-/** GO_IDLE_STATE - init card in spi mode if CS low */
48
-uint8_t const CMD0 = 0X00;
49
-/** SEND_IF_COND - verify SD Memory Card interface operating condition.*/
50
-uint8_t const CMD8 = 0X08;
51
-/** SEND_CSD - read the Card Specific Data (CSD register) */
52
-uint8_t const CMD9 = 0X09;
53
-/** SEND_CID - read the card identification information (CID register) */
54
-uint8_t const CMD10 = 0X0A;
55
-/** STOP_TRANSMISSION - end multiple block read sequence */
56
-uint8_t const CMD12 = 0X0C;
57
-/** SEND_STATUS - read the card status register */
58
-uint8_t const CMD13 = 0X0D;
59
-/** READ_SINGLE_BLOCK - read a single data block from the card */
60
-uint8_t const CMD17 = 0X11;
61
-/** READ_MULTIPLE_BLOCK - read a multiple data blocks from the card */
62
-uint8_t const CMD18 = 0X12;
63
-/** WRITE_BLOCK - write a single data block to the card */
64
-uint8_t const CMD24 = 0X18;
65
-/** WRITE_MULTIPLE_BLOCK - write blocks of data until a STOP_TRANSMISSION */
66
-uint8_t const CMD25 = 0X19;
67
-/** ERASE_WR_BLK_START - sets the address of the first block to be erased */
68
-uint8_t const CMD32 = 0X20;
69
-/** ERASE_WR_BLK_END - sets the address of the last block of the continuous
70
-    range to be erased*/
71
-uint8_t const CMD33 = 0X21;
72
-/** ERASE - erase all previously selected blocks */
73
-uint8_t const CMD38 = 0X26;
74
-/** APP_CMD - escape for application specific command */
75
-uint8_t const CMD55 = 0X37;
76
-/** READ_OCR - read the OCR register of a card */
77
-uint8_t const CMD58 = 0X3A;
78
-/** SET_WR_BLK_ERASE_COUNT - Set the number of write blocks to be
79
-     pre-erased before writing */
80
-uint8_t const ACMD23 = 0X17;
81
-/** SD_SEND_OP_COMD - Sends host capacity support information and
82
-    activates the card's initialization process */
83
-uint8_t const ACMD41 = 0X29;
84
-//------------------------------------------------------------------------------
46
+uint8_t const CMD0 = 0x00,    // GO_IDLE_STATE - init card in spi mode if CS low
47
+              CMD8 = 0x08,    // SEND_IF_COND - verify SD Memory Card interface operating condition
48
+              CMD9 = 0x09,    // SEND_CSD - read the Card Specific Data (CSD register)
49
+              CMD10 = 0x0A,   // SEND_CID - read the card identification information (CID register)
50
+              CMD12 = 0x0C,   // STOP_TRANSMISSION - end multiple block read sequence
51
+              CMD13 = 0x0D,   // SEND_STATUS - read the card status register
52
+              CMD17 = 0x11,   // READ_SINGLE_BLOCK - read a single data block from the card
53
+              CMD18 = 0x12,   // READ_MULTIPLE_BLOCK - read a multiple data blocks from the card
54
+              CMD24 = 0x18,   // WRITE_BLOCK - write a single data block to the card
55
+              CMD25 = 0x19,   // WRITE_MULTIPLE_BLOCK - write blocks of data until a STOP_TRANSMISSION
56
+              CMD32 = 0x20,   // ERASE_WR_BLK_START - sets the address of the first block to be erased
57
+              CMD33 = 0x21,   // ERASE_WR_BLK_END - sets the address of the last block of the continuous range to be erased*/
58
+              CMD38 = 0x26,   // ERASE - erase all previously selected blocks */
59
+              CMD55 = 0x37,   // APP_CMD - escape for application specific command */
60
+              CMD58 = 0x3A,   // READ_OCR - read the OCR register of a card */
61
+              ACMD23 = 0x17,  // SET_WR_BLK_ERASE_COUNT - Set the number of write blocks to be pre-erased before writing */
62
+              ACMD41 = 0x29;  // SD_SEND_OP_COMD - Sends host capacity support information and activates the card's initialization process */
63
+
85 64
 /** status for card in the ready state */
86
-uint8_t const R1_READY_STATE = 0X00;
65
+uint8_t const R1_READY_STATE = 0x00;
87 66
 /** status for card in the idle state */
88
-uint8_t const R1_IDLE_STATE = 0X01;
67
+uint8_t const R1_IDLE_STATE = 0x01;
89 68
 /** status bit for illegal command */
90
-uint8_t const R1_ILLEGAL_COMMAND = 0X04;
69
+uint8_t const R1_ILLEGAL_COMMAND = 0x04;
91 70
 /** start data token for read or write single block*/
92
-uint8_t const DATA_START_BLOCK = 0XFE;
71
+uint8_t const DATA_START_BLOCK = 0xFE;
93 72
 /** stop token for write multiple blocks*/
94
-uint8_t const STOP_TRAN_TOKEN = 0XFD;
73
+uint8_t const STOP_TRAN_TOKEN = 0xFD;
95 74
 /** start data token for write multiple blocks*/
96
-uint8_t const WRITE_MULTIPLE_TOKEN = 0XFC;
75
+uint8_t const WRITE_MULTIPLE_TOKEN = 0xFC;
97 76
 /** mask for data response tokens after a write block operation */
98
-uint8_t const DATA_RES_MASK = 0X1F;
77
+uint8_t const DATA_RES_MASK = 0x1F;
99 78
 /** write data accepted token */
100
-uint8_t const DATA_RES_ACCEPTED = 0X05;
101
-//------------------------------------------------------------------------------
79
+uint8_t const DATA_RES_ACCEPTED = 0x05;
80
+
102 81
 /** Card IDentification (CID) register */
103 82
 typedef struct CID {
104 83
   // byte 0
@@ -134,7 +113,7 @@ typedef struct CID {
134 113
   /** CRC7 checksum */
135 114
   unsigned char crc : 7;
136 115
 } cid_t;
137
-//------------------------------------------------------------------------------
116
+
138 117
 /** CSD for version 1.00 cards */
139 118
 typedef struct CSDV1 {
140 119
   // byte 0
@@ -196,14 +175,14 @@ typedef struct CSDV1 {
196 175
   unsigned char always1 : 1;
197 176
   unsigned char crc : 7;
198 177
 } csd1_t;
199
-//------------------------------------------------------------------------------
178
+
200 179
 /** CSD for version 2.00 cards */
201 180
 typedef struct CSDV2 {
202 181
   // byte 0
203 182
   unsigned char reserved1 : 6;
204 183
   unsigned char csd_ver : 2;
205 184
   // byte 1
206
-  /** fixed to 0X0E */
185
+  /** fixed to 0x0E */
207 186
   unsigned char taac;
208 187
   // byte 2
209 188
   /** fixed to 0 */
@@ -278,12 +257,11 @@ typedef struct CSDV2 {
278 257
   /** checksum */
279 258
   unsigned char crc : 7;
280 259
 } csd2_t;
281
-//------------------------------------------------------------------------------
260
+
282 261
 /** union of old and new style CSD register */
283 262
 union csd_t {
284 263
   csd1_t v1;
285 264
   csd2_t v2;
286 265
 };
287
-#endif  // SdInfo_h
288 266
 
289
-#endif
267
+#endif // _SDINFO_H_

+ 82
- 118
Marlin/SdVolume.cpp 파일 보기

@@ -26,11 +26,12 @@
26 26
  *
27 27
  * This file is part of the Arduino Sd2Card Library
28 28
  */
29
-#include "Marlin.h"
29
+#include "MarlinConfig.h"
30
+
30 31
 #if ENABLED(SDSUPPORT)
31 32
 
32 33
 #include "SdVolume.h"
33
-//------------------------------------------------------------------------------
34
+
34 35
 #if !USE_MULTIPLE_CARDS
35 36
   // raw block cache
36 37
   uint32_t SdVolume::cacheBlockNumber_;  // current block number
@@ -39,7 +40,7 @@
39 40
   bool     SdVolume::cacheDirty_;        // cacheFlush() will write block if true
40 41
   uint32_t SdVolume::cacheMirrorBlock_;  // mirror  block for second FAT
41 42
 #endif  // USE_MULTIPLE_CARDS
42
-//------------------------------------------------------------------------------
43
+
43 44
 // find a contiguous group of clusters
44 45
 bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) {
45 46
   // start of group
@@ -73,14 +74,14 @@ bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) {
73 74
   // search the FAT for free clusters
74 75
   for (uint32_t n = 0;; n++, endCluster++) {
75 76
     // can't find space checked all clusters
76
-    if (n >= clusterCount_) goto fail;
77
+    if (n >= clusterCount_) return false;
77 78
 
78 79
     // past end - start from beginning of FAT
79 80
     if (endCluster > fatEnd) {
80 81
       bgnCluster = endCluster = 2;
81 82
     }
82 83
     uint32_t f;
83
-    if (!fatGet(endCluster, &f)) goto fail;
84
+    if (!fatGet(endCluster, &f)) return false;
84 85
 
85 86
     if (f != 0) {
86 87
       // cluster in use try next cluster as bgnCluster
@@ -92,16 +93,16 @@ bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) {
92 93
     }
93 94
   }
94 95
   // mark end of chain
95
-  if (!fatPutEOC(endCluster)) goto fail;
96
+  if (!fatPutEOC(endCluster)) return false;
96 97
 
97 98
   // link clusters
98 99
   while (endCluster > bgnCluster) {
99
-    if (!fatPut(endCluster - 1, endCluster)) goto fail;
100
+    if (!fatPut(endCluster - 1, endCluster)) return false;
100 101
     endCluster--;
101 102
   }
102 103
   if (*curCluster != 0) {
103 104
     // connect chains
104
-    if (!fatPut(*curCluster, bgnCluster)) goto fail;
105
+    if (!fatPut(*curCluster, bgnCluster)) return false;
105 106
   }
106 107
   // return first cluster number to caller
107 108
   *curCluster = bgnCluster;
@@ -110,114 +111,97 @@ bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) {
110 111
   if (setStart) allocSearchStart_ = bgnCluster + 1;
111 112
 
112 113
   return true;
113
-fail:
114
-  return false;
115 114
 }
116
-//------------------------------------------------------------------------------
115
+
117 116
 bool SdVolume::cacheFlush() {
118 117
   if (cacheDirty_) {
119
-    if (!sdCard_->writeBlock(cacheBlockNumber_, cacheBuffer_.data)) {
120
-      goto fail;
121
-    }
118
+    if (!sdCard_->writeBlock(cacheBlockNumber_, cacheBuffer_.data))
119
+      return false;
120
+
122 121
     // mirror FAT tables
123 122
     if (cacheMirrorBlock_) {
124
-      if (!sdCard_->writeBlock(cacheMirrorBlock_, cacheBuffer_.data)) {
125
-        goto fail;
126
-      }
123
+      if (!sdCard_->writeBlock(cacheMirrorBlock_, cacheBuffer_.data))
124
+        return false;
127 125
       cacheMirrorBlock_ = 0;
128 126
     }
129 127
     cacheDirty_ = 0;
130 128
   }
131 129
   return true;
132
-fail:
133
-  return false;
134 130
 }
135
-//------------------------------------------------------------------------------
131
+
136 132
 bool SdVolume::cacheRawBlock(uint32_t blockNumber, bool dirty) {
137 133
   if (cacheBlockNumber_ != blockNumber) {
138
-    if (!cacheFlush()) goto fail;
139
-    if (!sdCard_->readBlock(blockNumber, cacheBuffer_.data)) goto fail;
134
+    if (!cacheFlush()) return false;
135
+    if (!sdCard_->readBlock(blockNumber, cacheBuffer_.data)) return false;
140 136
     cacheBlockNumber_ = blockNumber;
141 137
   }
142 138
   if (dirty) cacheDirty_ = true;
143 139
   return true;
144
-fail:
145
-  return false;
146 140
 }
147
-//------------------------------------------------------------------------------
141
+
148 142
 // return the size in bytes of a cluster chain
149 143
 bool SdVolume::chainSize(uint32_t cluster, uint32_t* size) {
150 144
   uint32_t s = 0;
151 145
   do {
152
-    if (!fatGet(cluster, &cluster)) goto fail;
146
+    if (!fatGet(cluster, &cluster)) return false;
153 147
     s += 512UL << clusterSizeShift_;
154 148
   } while (!isEOC(cluster));
155 149
   *size = s;
156 150
   return true;
157
-fail:
158
-  return false;
159 151
 }
160
-//------------------------------------------------------------------------------
152
+
161 153
 // Fetch a FAT entry
162 154
 bool SdVolume::fatGet(uint32_t cluster, uint32_t* value) {
163 155
   uint32_t lba;
164
-  if (cluster > (clusterCount_ + 1)) goto fail;
156
+  if (cluster > (clusterCount_ + 1)) return false;
165 157
   if (FAT12_SUPPORT && fatType_ == 12) {
166 158
     uint16_t index = cluster;
167 159
     index += index >> 1;
168 160
     lba = fatStartBlock_ + (index >> 9);
169
-    if (!cacheRawBlock(lba, CACHE_FOR_READ)) goto fail;
170
-    index &= 0X1FF;
161
+    if (!cacheRawBlock(lba, CACHE_FOR_READ)) return false;
162
+    index &= 0x1FF;
171 163
     uint16_t tmp = cacheBuffer_.data[index];
172 164
     index++;
173 165
     if (index == 512) {
174
-      if (!cacheRawBlock(lba + 1, CACHE_FOR_READ)) goto fail;
166
+      if (!cacheRawBlock(lba + 1, CACHE_FOR_READ)) return false;
175 167
       index = 0;
176 168
     }
177 169
     tmp |= cacheBuffer_.data[index] << 8;
178
-    *value = cluster & 1 ? tmp >> 4 : tmp & 0XFFF;
170
+    *value = cluster & 1 ? tmp >> 4 : tmp & 0xFFF;
179 171
     return true;
180 172
   }
181
-  if (fatType_ == 16) {
173
+
174
+  if (fatType_ == 16)
182 175
     lba = fatStartBlock_ + (cluster >> 8);
183
-  }
184
-  else if (fatType_ == 32) {
176
+  else if (fatType_ == 32)
185 177
     lba = fatStartBlock_ + (cluster >> 7);
186
-  }
187
-  else {
188
-    goto fail;
189
-  }
190
-  if (lba != cacheBlockNumber_) {
191
-    if (!cacheRawBlock(lba, CACHE_FOR_READ)) goto fail;
192
-  }
193
-  if (fatType_ == 16) {
194
-    *value = cacheBuffer_.fat16[cluster & 0XFF];
195
-  }
196
-  else {
197
-    *value = cacheBuffer_.fat32[cluster & 0X7F] & FAT32MASK;
198
-  }
178
+  else
179
+    return false;
180
+
181
+  if (lba != cacheBlockNumber_ && !cacheRawBlock(lba, CACHE_FOR_READ))
182
+    return false;
183
+
184
+  *value = (fatType_ == 16) ? cacheBuffer_.fat16[cluster & 0xFF] : (cacheBuffer_.fat32[cluster & 0x7F] & FAT32MASK);
199 185
   return true;
200
-fail:
201
-  return false;
202 186
 }
203
-//------------------------------------------------------------------------------
187
+
204 188
 // Store a FAT entry
205 189
 bool SdVolume::fatPut(uint32_t cluster, uint32_t value) {
206 190
   uint32_t lba;
207 191
   // error if reserved cluster
208
-  if (cluster < 2) goto fail;
192
+  if (cluster < 2) return false;
209 193
 
210 194
   // error if not in FAT
211
-  if (cluster > (clusterCount_ + 1)) goto fail;
195
+  if (cluster > (clusterCount_ + 1)) return false;
212 196
 
213 197
   if (FAT12_SUPPORT && fatType_ == 12) {
214 198
     uint16_t index = cluster;
215 199
     index += index >> 1;
216 200
     lba = fatStartBlock_ + (index >> 9);
217
-    if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto fail;
201
+    if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) return false;
218 202
     // mirror second FAT
219 203
     if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_;
220
-    index &= 0X1FF;
204
+    index &= 0x1FF;
221 205
     uint8_t tmp = value;
222 206
     if (cluster & 1) {
223 207
       tmp = (cacheBuffer_.data[index] & 0XF) | tmp << 4;
@@ -227,62 +211,56 @@ bool SdVolume::fatPut(uint32_t cluster, uint32_t value) {
227 211
     if (index == 512) {
228 212
       lba++;
229 213
       index = 0;
230
-      if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto fail;
214
+      if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) return false;
231 215
       // mirror second FAT
232 216
       if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_;
233 217
     }
234 218
     tmp = value >> 4;
235 219
     if (!(cluster & 1)) {
236
-      tmp = ((cacheBuffer_.data[index] & 0XF0)) | tmp >> 4;
220
+      tmp = ((cacheBuffer_.data[index] & 0xF0)) | tmp >> 4;
237 221
     }
238 222
     cacheBuffer_.data[index] = tmp;
239 223
     return true;
240 224
   }
241
-  if (fatType_ == 16) {
225
+
226
+  if (fatType_ == 16)
242 227
     lba = fatStartBlock_ + (cluster >> 8);
243
-  }
244
-  else if (fatType_ == 32) {
228
+  else if (fatType_ == 32)
245 229
     lba = fatStartBlock_ + (cluster >> 7);
246
-  }
247
-  else {
248
-    goto fail;
249
-  }
250
-  if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto fail;
230
+  else
231
+    return false;
232
+
233
+  if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) return false;
234
+
251 235
   // store entry
252
-  if (fatType_ == 16) {
253
-    cacheBuffer_.fat16[cluster & 0XFF] = value;
254
-  }
255
-  else {
256
-    cacheBuffer_.fat32[cluster & 0X7F] = value;
257
-  }
236
+  if (fatType_ == 16)
237
+    cacheBuffer_.fat16[cluster & 0xFF] = value;
238
+  else
239
+    cacheBuffer_.fat32[cluster & 0x7F] = value;
240
+
258 241
   // mirror second FAT
259 242
   if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_;
260 243
   return true;
261
-fail:
262
-  return false;
263 244
 }
264
-//------------------------------------------------------------------------------
245
+
265 246
 // free a cluster chain
266 247
 bool SdVolume::freeChain(uint32_t cluster) {
267
-  uint32_t next;
268
-
269 248
   // clear free cluster location
270 249
   allocSearchStart_ = 2;
271 250
 
272 251
   do {
273
-    if (!fatGet(cluster, &next)) goto fail;
252
+    uint32_t next;
253
+    if (!fatGet(cluster, &next)) return false;
274 254
 
275 255
     // free cluster
276
-    if (!fatPut(cluster, 0)) goto fail;
256
+    if (!fatPut(cluster, 0)) return false;
277 257
 
278 258
     cluster = next;
279 259
   } while (!isEOC(cluster));
280 260
 
281 261
   return true;
282
-fail:
283
-  return false;
284 262
 }
285
-//------------------------------------------------------------------------------
263
+
286 264
 /** Volume free space in clusters.
287 265
  *
288 266
  * \return Count of free clusters for success or -1 if an error occurs.
@@ -292,34 +270,28 @@ int32_t SdVolume::freeClusterCount() {
292 270
   uint16_t n;
293 271
   uint32_t todo = clusterCount_ + 2;
294 272
 
295
-  if (fatType_ == 16) {
273
+  if (fatType_ == 16)
296 274
     n = 256;
297
-  }
298
-  else if (fatType_ == 32) {
275
+  else if (fatType_ == 32)
299 276
     n = 128;
300
-  }
301
-  else {
302
-    // put FAT12 here
277
+  else // put FAT12 here
303 278
     return -1;
304
-  }
305 279
 
306 280
   for (uint32_t lba = fatStartBlock_; todo; todo -= n, lba++) {
307 281
     if (!cacheRawBlock(lba, CACHE_FOR_READ)) return -1;
308 282
     NOMORE(n, todo);
309 283
     if (fatType_ == 16) {
310
-      for (uint16_t i = 0; i < n; i++) {
284
+      for (uint16_t i = 0; i < n; i++)
311 285
         if (cacheBuffer_.fat16[i] == 0) free++;
312
-      }
313 286
     }
314 287
     else {
315
-      for (uint16_t i = 0; i < n; i++) {
288
+      for (uint16_t i = 0; i < n; i++)
316 289
         if (cacheBuffer_.fat32[i] == 0) free++;
317
-      }
318 290
     }
319 291
   }
320 292
   return free;
321 293
 }
322
-//------------------------------------------------------------------------------
294
+
323 295
 /** Initialize a FAT volume.
324 296
  *
325 297
  * \param[in] dev The SD card where the volume is located.
@@ -329,14 +301,12 @@ int32_t SdVolume::freeClusterCount() {
329 301
  * a MBR, Master Boot Record, or zero if the device is formatted as
330 302
  * a super floppy with the FAT boot sector in block zero.
331 303
  *
332
- * \return The value one, true, is returned for success and
333
- * the value zero, false, is returned for failure.  Reasons for
334
- * failure include not finding a valid partition, not finding a valid
304
+ * \return true for success, false for failure.
305
+ * Reasons for failure include not finding a valid partition, not finding a valid
335 306
  * FAT file system in the specified partition or an I/O error.
336 307
  */
337 308
 bool SdVolume::init(Sd2Card* dev, uint8_t part) {
338
-  uint32_t totalBlocks;
339
-  uint32_t volumeStartBlock = 0;
309
+  uint32_t totalBlocks, volumeStartBlock = 0;
340 310
   fat32_boot_t* fbs;
341 311
 
342 312
   sdCard_ = dev;
@@ -344,30 +314,26 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) {
344 314
   allocSearchStart_ = 2;
345 315
   cacheDirty_ = 0;  // cacheFlush() will write block if true
346 316
   cacheMirrorBlock_ = 0;
347
-  cacheBlockNumber_ = 0XFFFFFFFF;
317
+  cacheBlockNumber_ = 0xFFFFFFFF;
348 318
 
349 319
   // if part == 0 assume super floppy with FAT boot sector in block zero
350 320
   // if part > 0 assume mbr volume with partition table
351 321
   if (part) {
352
-    if (part > 4)goto fail;
353
-    if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) goto fail;
322
+    if (part > 4) return false;
323
+    if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) return false;
354 324
     part_t* p = &cacheBuffer_.mbr.part[part - 1];
355
-    if ((p->boot & 0X7F) != 0  ||
356
-        p->totalSectors < 100 ||
357
-        p->firstSector == 0) {
358
-      // not a valid partition
359
-      goto fail;
360
-    }
325
+    if ((p->boot & 0x7F) != 0  || p->totalSectors < 100 || p->firstSector == 0)
326
+      return false; // not a valid partition
361 327
     volumeStartBlock = p->firstSector;
362 328
   }
363
-  if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) goto fail;
329
+  if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) return false;
364 330
   fbs = &cacheBuffer_.fbs32;
365 331
   if (fbs->bytesPerSector != 512 ||
366 332
       fbs->fatCount == 0 ||
367 333
       fbs->reservedSectorCount == 0 ||
368 334
       fbs->sectorsPerCluster == 0) {
369 335
     // not valid FAT volume
370
-    goto fail;
336
+    return false;
371 337
   }
372 338
   fatCount_ = fbs->fatCount;
373 339
   blocksPerCluster_ = fbs->sectorsPerCluster;
@@ -375,7 +341,7 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) {
375 341
   clusterSizeShift_ = 0;
376 342
   while (blocksPerCluster_ != _BV(clusterSizeShift_)) {
377 343
     // error if not power of 2
378
-    if (clusterSizeShift_++ > 7) goto fail;
344
+    if (clusterSizeShift_++ > 7) return false;
379 345
   }
380 346
   blocksPerFat_ = fbs->sectorsPerFat16 ?
381 347
                   fbs->sectorsPerFat16 : fbs->sectorsPerFat32;
@@ -404,17 +370,15 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) {
404 370
   // FAT type is determined by cluster count
405 371
   if (clusterCount_ < 4085) {
406 372
     fatType_ = 12;
407
-    if (!FAT12_SUPPORT) goto fail;
373
+    if (!FAT12_SUPPORT) return false;
408 374
   }
409
-  else if (clusterCount_ < 65525) {
375
+  else if (clusterCount_ < 65525)
410 376
     fatType_ = 16;
411
-  }
412 377
   else {
413 378
     rootDirStart_ = fbs->fat32RootCluster;
414 379
     fatType_ = 32;
415 380
   }
416 381
   return true;
417
-fail:
418
-  return false;
419 382
 }
420
-#endif
383
+
384
+#endif // SDSUPPORT

+ 106
- 122
Marlin/SdVolume.h 파일 보기

@@ -21,19 +21,19 @@
21 21
  */
22 22
 
23 23
 /**
24
+ * \file
25
+ * \brief SdVolume class
26
+ */
27
+
28
+/**
24 29
  * Arduino SdFat Library
25 30
  * Copyright (C) 2009 by William Greiman
26 31
  *
27 32
  * This file is part of the Arduino Sd2Card Library
28 33
  */
29
-#include "Marlin.h"
30
-#if ENABLED(SDSUPPORT)
31
-#ifndef SdVolume_h
32
-#define SdVolume_h
33
-/**
34
- * \file
35
- * \brief SdVolume class
36
- */
34
+#ifndef _SDVOLUME_H_
35
+#define _SDVOLUME_H_
36
+
37 37
 #include "SdFatConfig.h"
38 38
 #include "Sd2Card.h"
39 39
 #include "SdFatStructs.h"
@@ -44,89 +44,81 @@
44 44
  * \brief Cache for an SD data block
45 45
  */
46 46
 union cache_t {
47
-           /** Used to access cached file data blocks. */
48
-  uint8_t  data[512];
49
-           /** Used to access cached FAT16 entries. */
50
-  uint16_t fat16[256];
51
-           /** Used to access cached FAT32 entries. */
52
-  uint32_t fat32[128];
53
-           /** Used to access cached directory entries. */
54
-  dir_t    dir[16];
55
-           /** Used to access a cached Master Boot Record. */
56
-  mbr_t    mbr;
57
-           /** Used to access to a cached FAT boot sector. */
58
-  fat_boot_t fbs;
59
-           /** Used to access to a cached FAT32 boot sector. */
60
-  fat32_boot_t fbs32;
61
-           /** Used to access to a cached FAT32 FSINFO sector. */
62
-  fat32_fsinfo_t fsinfo;
47
+  uint8_t         data[512];  // Used to access cached file data blocks.
48
+  uint16_t        fat16[256]; // Used to access cached FAT16 entries.
49
+  uint32_t        fat32[128]; // Used to access cached FAT32 entries.
50
+  dir_t           dir[16];    // Used to access cached directory entries.
51
+  mbr_t           mbr;        // Used to access a cached Master Boot Record.
52
+  fat_boot_t      fbs;        // Used to access to a cached FAT boot sector.
53
+  fat32_boot_t    fbs32;      // Used to access to a cached FAT32 boot sector.
54
+  fat32_fsinfo_t  fsinfo;     // Used to access to a cached FAT32 FSINFO sector.
63 55
 };
64
-//------------------------------------------------------------------------------
56
+
65 57
 /**
66 58
  * \class SdVolume
67 59
  * \brief Access FAT16 and FAT32 volumes on SD and SDHC cards.
68 60
  */
69 61
 class SdVolume {
70 62
  public:
71
-  /** Create an instance of SdVolume */
63
+  // Create an instance of SdVolume
72 64
   SdVolume() : fatType_(0) {}
73
-  /** Clear the cache and returns a pointer to the cache.  Used by the WaveRP
65
+  /**
66
+   * Clear the cache and returns a pointer to the cache.  Used by the WaveRP
74 67
    * recorder to do raw write to the SD card.  Not for normal apps.
75 68
    * \return A pointer to the cache buffer or zero if an error occurs.
76 69
    */
77 70
   cache_t* cacheClear() {
78 71
     if (!cacheFlush()) return 0;
79
-    cacheBlockNumber_ = 0XFFFFFFFF;
72
+    cacheBlockNumber_ = 0xFFFFFFFF;
80 73
     return &cacheBuffer_;
81 74
   }
82
-  /** Initialize a FAT volume.  Try partition one first then try super
75
+
76
+  /**
77
+   * Initialize a FAT volume.  Try partition one first then try super
83 78
    * floppy format.
84 79
    *
85 80
    * \param[in] dev The Sd2Card where the volume is located.
86 81
    *
87
-   * \return The value one, true, is returned for success and
88
-   * the value zero, false, is returned for failure.  Reasons for
89
-   * failure include not finding a valid partition, not finding a valid
90
-   * FAT file system or an I/O error.
82
+   * \return true for success, false for failure.
83
+   * Reasons for failure include not finding a valid partition, not finding
84
+   * a valid FAT file system or an I/O error.
91 85
    */
92
-  bool init(Sd2Card* dev) { return init(dev, 1) ? true : init(dev, 0);}
86
+  bool init(Sd2Card* dev) { return init(dev, 1) ? true : init(dev, 0); }
93 87
   bool init(Sd2Card* dev, uint8_t part);
94 88
 
95 89
   // inline functions that return volume info
96
-  /** \return The volume's cluster size in blocks. */
97
-  uint8_t blocksPerCluster() const {return blocksPerCluster_;}
98
-  /** \return The number of blocks in one FAT. */
99
-  uint32_t blocksPerFat()  const {return blocksPerFat_;}
100
-  /** \return The total number of clusters in the volume. */
101
-  uint32_t clusterCount() const {return clusterCount_;}
102
-  /** \return The shift count required to multiply by blocksPerCluster. */
103
-  uint8_t clusterSizeShift() const {return clusterSizeShift_;}
104
-  /** \return The logical block number for the start of file data. */
105
-  uint32_t dataStartBlock() const {return dataStartBlock_;}
106
-  /** \return The number of FAT structures on the volume. */
107
-  uint8_t fatCount() const {return fatCount_;}
108
-  /** \return The logical block number for the start of the first FAT. */
109
-  uint32_t fatStartBlock() const {return fatStartBlock_;}
110
-  /** \return The FAT type of the volume. Values are 12, 16 or 32. */
111
-  uint8_t fatType() const {return fatType_;}
90
+  uint8_t blocksPerCluster() const { return blocksPerCluster_; } //> \return The volume's cluster size in blocks.
91
+  uint32_t blocksPerFat() const { return blocksPerFat_; }        //> \return The number of blocks in one FAT.
92
+  uint32_t clusterCount() const { return clusterCount_; }        //> \return The total number of clusters in the volume.
93
+  uint8_t clusterSizeShift() const { return clusterSizeShift_; } //> \return The shift count required to multiply by blocksPerCluster.
94
+  uint32_t dataStartBlock() const { return dataStartBlock_; }    //> \return The logical block number for the start of file data.
95
+  uint8_t fatCount() const { return fatCount_; }                 //> \return The number of FAT structures on the volume.
96
+  uint32_t fatStartBlock() const { return fatStartBlock_; }      //> \return The logical block number for the start of the first FAT.
97
+  uint8_t fatType() const { return fatType_; }                   //> \return The FAT type of the volume. Values are 12, 16 or 32.
112 98
   int32_t freeClusterCount();
113
-  /** \return The number of entries in the root directory for FAT16 volumes. */
114
-  uint32_t rootDirEntryCount() const {return rootDirEntryCount_;}
115
-  /** \return The logical block number for the start of the root directory
116
-       on FAT16 volumes or the first cluster number on FAT32 volumes. */
117
-  uint32_t rootDirStart() const {return rootDirStart_;}
118
-  /** Sd2Card object for this volume
99
+  uint32_t rootDirEntryCount() const { return rootDirEntryCount_; } /** \return The number of entries in the root directory for FAT16 volumes. */
100
+
101
+  /**
102
+   * \return The logical block number for the start of the root directory
103
+   *   on FAT16 volumes or the first cluster number on FAT32 volumes.
104
+   */
105
+  uint32_t rootDirStart() const { return rootDirStart_; }
106
+
107
+  /**
108
+   * Sd2Card object for this volume
119 109
    * \return pointer to Sd2Card object.
120 110
    */
121
-  Sd2Card* sdCard() {return sdCard_;}
122
-  /** Debug access to FAT table
111
+  Sd2Card* sdCard() { return sdCard_; }
112
+
113
+  /**
114
+   * Debug access to FAT table
123 115
    *
124 116
    * \param[in] n cluster number.
125 117
    * \param[out] v value of entry
126 118
    * \return true for success or false for failure
127 119
    */
128
-  bool dbgFat(uint32_t n, uint32_t* v) {return fatGet(n, v);}
129
-  //------------------------------------------------------------------------------
120
+  bool dbgFat(uint32_t n, uint32_t* v) { return fatGet(n, v); }
121
+
130 122
  private:
131 123
   // Allow SdBaseFile access to SdVolume private data.
132 124
   friend class SdBaseFile;
@@ -136,19 +128,20 @@ class SdVolume {
136 128
   // value for dirty argument in cacheRawBlock to indicate write to cache
137 129
   static bool const CACHE_FOR_WRITE = true;
138 130
 
139
-#if USE_MULTIPLE_CARDS
140
-  cache_t cacheBuffer_;        // 512 byte cache for device blocks
141
-  uint32_t cacheBlockNumber_;  // Logical number of block in the cache
142
-  Sd2Card* sdCard_;            // Sd2Card object for cache
143
-  bool cacheDirty_;            // cacheFlush() will write block if true
144
-  uint32_t cacheMirrorBlock_;  // block number for mirror FAT
145
-#else  // USE_MULTIPLE_CARDS
146
-  static cache_t cacheBuffer_;        // 512 byte cache for device blocks
147
-  static uint32_t cacheBlockNumber_;  // Logical number of block in the cache
148
-  static Sd2Card* sdCard_;            // Sd2Card object for cache
149
-  static bool cacheDirty_;            // cacheFlush() will write block if true
150
-  static uint32_t cacheMirrorBlock_;  // block number for mirror FAT
151
-#endif  // USE_MULTIPLE_CARDS
131
+  #if USE_MULTIPLE_CARDS
132
+    cache_t cacheBuffer_;        // 512 byte cache for device blocks
133
+    uint32_t cacheBlockNumber_;  // Logical number of block in the cache
134
+    Sd2Card* sdCard_;            // Sd2Card object for cache
135
+    bool cacheDirty_;            // cacheFlush() will write block if true
136
+    uint32_t cacheMirrorBlock_;  // block number for mirror FAT
137
+  #else
138
+    static cache_t cacheBuffer_;        // 512 byte cache for device blocks
139
+    static uint32_t cacheBlockNumber_;  // Logical number of block in the cache
140
+    static Sd2Card* sdCard_;            // Sd2Card object for cache
141
+    static bool cacheDirty_;            // cacheFlush() will write block if true
142
+    static uint32_t cacheMirrorBlock_;  // block number for mirror FAT
143
+  #endif
144
+
152 145
   uint32_t allocSearchStart_;   // start cluster for alloc search
153 146
   uint8_t blocksPerCluster_;    // cluster size in blocks
154 147
   uint32_t blocksPerFat_;       // FAT size in blocks
@@ -160,68 +153,59 @@ class SdVolume {
160 153
   uint8_t fatType_;             // volume type (12, 16, OR 32)
161 154
   uint16_t rootDirEntryCount_;  // number of entries in FAT16 root dir
162 155
   uint32_t rootDirStart_;       // root start block for FAT16, cluster for FAT32
163
-  //----------------------------------------------------------------------------
156
+
164 157
   bool allocContiguous(uint32_t count, uint32_t* curCluster);
165
-  uint8_t blockOfCluster(uint32_t position) const {
166
-    return (position >> 9) & (blocksPerCluster_ - 1);
167
-  }
168
-  uint32_t clusterStartBlock(uint32_t cluster) const {
169
-    return dataStartBlock_ + ((cluster - 2) << clusterSizeShift_);
170
-  }
171
-  uint32_t blockNumber(uint32_t cluster, uint32_t position) const {
172
-    return clusterStartBlock(cluster) + blockOfCluster(position);
173
-  }
174
-  cache_t* cache() {return &cacheBuffer_;}
175
-  uint32_t cacheBlockNumber() {return cacheBlockNumber_;}
176
-#if USE_MULTIPLE_CARDS
177
-  bool cacheFlush();
178
-  bool cacheRawBlock(uint32_t blockNumber, bool dirty);
179
-#else  // USE_MULTIPLE_CARDS
180
-  static bool cacheFlush();
181
-  static bool cacheRawBlock(uint32_t blockNumber, bool dirty);
182
-#endif  // USE_MULTIPLE_CARDS
158
+  uint8_t blockOfCluster(uint32_t position) const { return (position >> 9) & (blocksPerCluster_ - 1); }
159
+  uint32_t clusterStartBlock(uint32_t cluster) const { return dataStartBlock_ + ((cluster - 2) << clusterSizeShift_); }
160
+  uint32_t blockNumber(uint32_t cluster, uint32_t position) const { return clusterStartBlock(cluster) + blockOfCluster(position); }
161
+
162
+  cache_t* cache() { return &cacheBuffer_; }
163
+  uint32_t cacheBlockNumber() const { return cacheBlockNumber_; }
164
+
165
+  #if USE_MULTIPLE_CARDS
166
+    bool cacheFlush();
167
+    bool cacheRawBlock(uint32_t blockNumber, bool dirty);
168
+  #else
169
+    static bool cacheFlush();
170
+    static bool cacheRawBlock(uint32_t blockNumber, bool dirty);
171
+  #endif
172
+
183 173
   // used by SdBaseFile write to assign cache to SD location
184 174
   void cacheSetBlockNumber(uint32_t blockNumber, bool dirty) {
185 175
     cacheDirty_ = dirty;
186 176
     cacheBlockNumber_  = blockNumber;
187 177
   }
188
-  void cacheSetDirty() {cacheDirty_ |= CACHE_FOR_WRITE;}
178
+  void cacheSetDirty() { cacheDirty_ |= CACHE_FOR_WRITE; }
189 179
   bool chainSize(uint32_t beginCluster, uint32_t* size);
190 180
   bool fatGet(uint32_t cluster, uint32_t* value);
191 181
   bool fatPut(uint32_t cluster, uint32_t value);
192
-  bool fatPutEOC(uint32_t cluster) {
193
-    return fatPut(cluster, 0x0FFFFFFF);
194
-  }
182
+  bool fatPutEOC(uint32_t cluster) { return fatPut(cluster, 0x0FFFFFFF); }
195 183
   bool freeChain(uint32_t cluster);
196 184
   bool isEOC(uint32_t cluster) const {
197 185
     if (FAT12_SUPPORT && fatType_ == 12) return  cluster >= FAT12EOC_MIN;
198 186
     if (fatType_ == 16) return cluster >= FAT16EOC_MIN;
199 187
     return  cluster >= FAT32EOC_MIN;
200 188
   }
201
-  bool readBlock(uint32_t block, uint8_t* dst) {
202
-    return sdCard_->readBlock(block, dst);
203
-  }
204
-  bool writeBlock(uint32_t block, const uint8_t* dst) {
205
-    return sdCard_->writeBlock(block, dst);
206
-  }
207
-  //------------------------------------------------------------------------------
208
-  // Deprecated functions  - suppress cpplint warnings with NOLINT comment
209
-#if ALLOW_DEPRECATED_FUNCTIONS && !defined(DOXYGEN)
210
- public:
211
-  /** \deprecated Use: bool SdVolume::init(Sd2Card* dev);
212
-   * \param[in] dev The SD card where the volume is located.
213
-   * \return true for success or false for failure.
214
-   */
215
-  bool init(Sd2Card& dev) {return init(&dev);}  // NOLINT
216
-  /** \deprecated Use: bool SdVolume::init(Sd2Card* dev, uint8_t vol);
217
-   * \param[in] dev The SD card where the volume is located.
218
-   * \param[in] part The partition to be used.
219
-   * \return true for success or false for failure.
220
-   */
221
-  bool init(Sd2Card& dev, uint8_t part) {  // NOLINT
222
-    return init(&dev, part);
223
-  }
224
-#endif  // ALLOW_DEPRECATED_FUNCTIONS
189
+  bool readBlock(uint32_t block, uint8_t* dst) { return sdCard_->readBlock(block, dst); }
190
+  bool writeBlock(uint32_t block, const uint8_t* dst) { return sdCard_->writeBlock(block, dst); }
191
+
192
+  // Deprecated functions
193
+  #if ALLOW_DEPRECATED_FUNCTIONS
194
+    public:
195
+      /**
196
+       * \deprecated Use: bool SdVolume::init(Sd2Card* dev);
197
+       * \param[in] dev The SD card where the volume is located.
198
+       * \return true for success or false for failure.
199
+       */
200
+      bool init(Sd2Card& dev) { return init(&dev); }
201
+      /**
202
+       * \deprecated Use: bool SdVolume::init(Sd2Card* dev, uint8_t vol);
203
+       * \param[in] dev The SD card where the volume is located.
204
+       * \param[in] part The partition to be used.
205
+       * \return true for success or false for failure.
206
+       */
207
+      bool init(Sd2Card& dev, uint8_t part) { return init(&dev, part); }
208
+  #endif  // ALLOW_DEPRECATED_FUNCTIONS
225 209
 };
226
-#endif  // SdVolume
227
-#endif
210
+
211
+#endif // _SDVOLUME_H_

+ 4
- 4
Marlin/Version.h 파일 보기

@@ -35,7 +35,7 @@
35 35
   /**
36 36
    * Marlin release version identifier
37 37
    */
38
-  #define SHORT_BUILD_VERSION "1.1.4"
38
+  #define SHORT_BUILD_VERSION "1.1.7"
39 39
 
40 40
   /**
41 41
    * Verbose version identifier which should contain a reference to the location
@@ -48,7 +48,7 @@
48 48
    * here we define this default string as the date where the latest release
49 49
    * version was tagged.
50 50
    */
51
-  #define STRING_DISTRIBUTION_DATE "2017-07-04 12:00"
51
+  #define STRING_DISTRIBUTION_DATE "2017-12-15 12:00"
52 52
 
53 53
   /**
54 54
    * Required minimum Configuration.h and Configuration_adv.h file versions.
@@ -57,8 +57,8 @@
57 57
    * but not limited to: ADD, DELETE RENAME OR REPURPOSE any directive/option on
58 58
    * the configuration files.
59 59
    */
60
-  #define REQUIRED_CONFIGURATION_H_VERSION 010100
61
-  #define REQUIRED_CONFIGURATION_ADV_H_VERSION 010100
60
+  #define REQUIRED_CONFIGURATION_H_VERSION 010107
61
+  #define REQUIRED_CONFIGURATION_ADV_H_VERSION 010107
62 62
 
63 63
   /**
64 64
    * The protocol for communication to the host. Protocol indicates communication

+ 38
- 0
Marlin/bitmap_flags.h 파일 보기

@@ -0,0 +1,38 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016, 2017 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
+#ifndef _BITMAP_FLAGS_H_
24
+#define _BITMAP_FLAGS_H_
25
+
26
+#include "macros.h"
27
+
28
+/**
29
+ * These support functions allow the use of large bit arrays of flags that take very
30
+ * little RAM. Currently they are limited to being 16x16 in size. Changing the declaration
31
+ * to unsigned long will allow us to go to 32x32 if higher resolution meshes are needed
32
+ * in the future.
33
+ */
34
+FORCE_INLINE void bitmap_clear(uint16_t bits[16], const uint8_t x, const uint8_t y) { CBI(bits[y], x); }
35
+FORCE_INLINE void bitmap_set(uint16_t bits[16], const uint8_t x, const uint8_t y) { SBI(bits[y], x); }
36
+FORCE_INLINE bool is_bitmap_set(uint16_t bits[16], const uint8_t x, const uint8_t y) { return TEST(bits[y], x); }
37
+
38
+#endif // _BITMAP_FLAGS_H_

+ 8
- 8
Marlin/blinkm.cpp 파일 보기

@@ -21,26 +21,26 @@
21 21
  */
22 22
 
23 23
 /**
24
- * blinkm.cpp - Library for controlling a BlinkM over i2c
25
- * Created by Tim Koster, August 21 2013.
24
+ * blinkm.cpp - Control a BlinkM over i2c
26 25
  */
27 26
 
28
-#include "Marlin.h"
27
+#include "MarlinConfig.h"
29 28
 
30 29
 #if ENABLED(BLINKM)
31 30
 
32 31
 #include "blinkm.h"
32
+#include "leds.h"
33
+#include <Wire.h>
33 34
 
34
-void SendColors(byte red, byte grn, byte blu) {
35
+void blinkm_set_led_color(const LEDColor &color) {
35 36
   Wire.begin();
36 37
   Wire.beginTransmission(0x09);
37 38
   Wire.write('o');                    //to disable ongoing script, only needs to be used once
38 39
   Wire.write('n');
39
-  Wire.write(red);
40
-  Wire.write(grn);
41
-  Wire.write(blu);
40
+  Wire.write(color.r);
41
+  Wire.write(color.g);
42
+  Wire.write(color.b);
42 43
   Wire.endTransmission();
43 44
 }
44 45
 
45 46
 #endif // BLINKM
46
-

+ 9
- 5
Marlin/blinkm.h 파일 보기

@@ -21,11 +21,15 @@
21 21
  */
22 22
 
23 23
 /**
24
- * blinkm.h - Library for controlling a BlinkM over i2c
25
- * Created by Tim Koster, August 21 2013.
24
+ * blinkm.h - Control a BlinkM over i2c
26 25
  */
27 26
 
28
-#include "Arduino.h"
29
-#include "Wire.h"
27
+#ifndef _BLINKM_H_
28
+#define _BLINKM_H_
30 29
 
31
-void SendColors(byte red, byte grn, byte blu);
30
+struct LEDColor;
31
+typedef LEDColor LEDColor;
32
+
33
+void blinkm_set_led_color(const LEDColor &color);
34
+
35
+#endif // _BLINKM_H_

+ 121
- 72
Marlin/boards.h 파일 보기

@@ -25,78 +25,127 @@
25 25
 
26 26
 #define BOARD_UNKNOWN -1
27 27
 
28
-#define BOARD_GEN7_CUSTOM       10   // Gen7 custom (Alfons3 Version) "https://github.com/Alfons3/Generation_7_Electronics"
29
-#define BOARD_GEN7_12           11   // Gen7 v1.1, v1.2
30
-#define BOARD_GEN7_13           12   // Gen7 v1.3
31
-#define BOARD_GEN7_14           13   // Gen7 v1.4
32
-#define BOARD_CNCONTROLS_11     111  // Cartesio CN Controls V11
33
-#define BOARD_CNCONTROLS_12     112  // Cartesio CN Controls V12
34
-#define BOARD_CHEAPTRONIC       2    // Cheaptronic v1.0
35
-#define BOARD_CHEAPTRONIC_V2    21   // Cheaptronic v2.0
36
-#define BOARD_SETHI             20   // Sethi 3D_1
37
-#define BOARD_MIGHTYBOARD_REVE  200  // Makerbot Mightyboard Revision E
38
-#define BOARD_RAMPS_OLD         3    // MEGA/RAMPS up to 1.2
39
-#define BOARD_RAMPS_13_EFB      33   // RAMPS 1.3 (Power outputs: Hotend, Fan, Bed)
40
-#define BOARD_RAMPS_13_EEB      34   // RAMPS 1.3 (Power outputs: Hotend0, Hotend1, Bed)
41
-#define BOARD_RAMPS_13_EFF      35   // RAMPS 1.3 (Power outputs: Hotend, Fan0, Fan1)
42
-#define BOARD_RAMPS_13_EEF      36   // RAMPS 1.3 (Power outputs: Hotend0, Hotend1, Fan)
43
-#define BOARD_RAMPS_13_SF       38   // RAMPS 1.3 (Power outputs: Spindle, Controller Fan)
44
-#define BOARD_FELIX2            37   // Felix 2.0+ Electronics Board (RAMPS like)
45
-#define BOARD_RIGIDBOARD        42   // Invent-A-Part RigidBoard
46
-#define BOARD_RIGIDBOARD_V2     52   // Invent-A-Part RigidBoard V2
47
-#define BOARD_RAMPS_14_EFB      43   // RAMPS 1.4 (Power outputs: Hotend, Fan, Bed)
48
-#define BOARD_RAMPS_14_EEB      44   // RAMPS 1.4 (Power outputs: Hotend0, Hotend1, Bed)
49
-#define BOARD_RAMPS_14_EFF      45   // RAMPS 1.4 (Power outputs: Hotend, Fan0, Fan1)
50
-#define BOARD_RAMPS_14_EEF      46   // RAMPS 1.4 (Power outputs: Hotend0, Hotend1, Fan)
51
-#define BOARD_RAMPS_14_SF       48   // RAMPS 1.4 (Power outputs: Spindle, Controller Fan)
52
-#define BOARD_GEN6              5    // Gen6
53
-#define BOARD_GEN6_DELUXE       51   // Gen6 deluxe
54
-#define BOARD_SANGUINOLOLU_11   6    // Sanguinololu < 1.2
55
-#define BOARD_SANGUINOLOLU_12   62   // Sanguinololu 1.2 and above
56
-#define BOARD_MELZI             63   // Melzi
57
-#define BOARD_STB_11            64   // STB V1.1
58
-#define BOARD_AZTEEG_X1         65   // Azteeg X1
59
-#define BOARD_MELZI_MAKR3D      66   // Melzi with ATmega1284 (MaKr3d version)
60
-#define BOARD_AZTEEG_X3         67   // Azteeg X3
61
-#define BOARD_AZTEEG_X3_PRO     68   // Azteeg X3 Pro
62
-#define BOARD_ANET_10           69   // Anet 1.0 (Melzi clone)
63
-#define BOARD_ULTIMAKER         7    // Ultimaker
64
-#define BOARD_ULTIMAKER_OLD     71   // Ultimaker (Older electronics. Pre 1.5.4. This is rare)
65
-#define BOARD_ULTIMAIN_2        72   // Ultimainboard 2.x (Uses TEMP_SENSOR 20)
66
-#define BOARD_3DRAG             77   // 3Drag Controller
67
-#define BOARD_K8200             78   // Velleman K8200 Controller (derived from 3Drag Controller)
68
-#define BOARD_K8400             79   // Velleman K8400 Controller (derived from 3Drag Controller)
69
-#define BOARD_TEENSYLU          8    // Teensylu
70
-#define BOARD_RUMBA             80   // Rumba
71
-#define BOARD_PRINTRBOARD       81   // Printrboard (AT90USB1286)
72
-#define BOARD_PRINTRBOARD_REVF  811  // Printrboard Revision F (AT90USB1286)
73
-#define BOARD_BRAINWAVE         82   // Brainwave (AT90USB646)
74
-#define BOARD_SAV_MKI           83   // SAV Mk-I (AT90USB1286)
75
-#define BOARD_TEENSY2           84   // Teensy++2.0 (AT90USB1286) - CLI compile: HARDWARE_MOTHERBOARD=84  make
76
-#define BOARD_BRAINWAVE_PRO     85   // Brainwave Pro (AT90USB1286)
77
-#define BOARD_GEN3_PLUS         9    // Gen3+
78
-#define BOARD_GEN3_MONOLITHIC   22   // Gen3 Monolithic Electronics
79
-#define BOARD_MEGATRONICS       70   // Megatronics
80
-#define BOARD_MEGATRONICS_2     701  // Megatronics v2.0
81
-#define BOARD_MINITRONICS       702  // Minitronics v1.0/1.1
82
-#define BOARD_MEGATRONICS_3     703  // Megatronics v3.0
83
-#define BOARD_MEGATRONICS_31    704  // Megatronics v3.1
84
-#define BOARD_OMCA_A            90   // Alpha OMCA board
85
-#define BOARD_OMCA              91   // Final OMCA board
86
-#define BOARD_RAMBO             301  // Rambo
87
-#define BOARD_MINIRAMBO         302  // Mini-Rambo
88
-#define BOARD_SCOOVO_X9H        303  // abee Scoovo X9H
89
-#define BOARD_MEGACONTROLLER    310  // Mega controller
90
-#define BOARD_ELEFU_3           21   // Elefu Ra Board (v3)
91
-#define BOARD_5DPRINT           88   // 5DPrint D8 Driver Board
92
-#define BOARD_LEAPFROG          999  // Leapfrog
93
-#define BOARD_MKS_BASE          40   // MKS BASE 1.0
94
-#define BOARD_MKS_13            47   // MKS v1.3 or 1.4 (maybe higher)
95
-#define BOARD_SAINSMART_2IN1    49   // Sainsmart 2-in-1 board
96
-#define BOARD_BAM_DICE          401  // 2PrintBeta BAM&DICE with STK drivers
97
-#define BOARD_BAM_DICE_DUE      402  // 2PrintBeta BAM&DICE Due with STK drivers
98
-#define BOARD_BQ_ZUM_MEGA_3D    503  // bq ZUM Mega 3D
99
-#define BOARD_ZRIB_V20          504  // zrib V2.0 control board (Chinese knock off RAMPS replica)
28
+//
29
+// RAMPS 1.3 / 1.4 - ATmega1280, ATmega2560
30
+//
31
+
32
+#define BOARD_RAMPS_OLD         3     // MEGA/RAMPS up to 1.2
33
+
34
+#define BOARD_RAMPS_13_EFB      33    // RAMPS 1.3 (Power outputs: Hotend, Fan, Bed)
35
+#define BOARD_RAMPS_13_EEB      34    // RAMPS 1.3 (Power outputs: Hotend0, Hotend1, Bed)
36
+#define BOARD_RAMPS_13_EFF      35    // RAMPS 1.3 (Power outputs: Hotend, Fan0, Fan1)
37
+#define BOARD_RAMPS_13_EEF      36    // RAMPS 1.3 (Power outputs: Hotend0, Hotend1, Fan)
38
+#define BOARD_RAMPS_13_SF       38    // RAMPS 1.3 (Power outputs: Spindle, Controller Fan)
39
+
40
+#define BOARD_RAMPS_14_EFB      43    // RAMPS 1.4 (Power outputs: Hotend, Fan, Bed)
41
+#define BOARD_RAMPS_14_EEB      44    // RAMPS 1.4 (Power outputs: Hotend0, Hotend1, Bed)
42
+#define BOARD_RAMPS_14_EFF      45    // RAMPS 1.4 (Power outputs: Hotend, Fan0, Fan1)
43
+#define BOARD_RAMPS_14_EEF      46    // RAMPS 1.4 (Power outputs: Hotend0, Hotend1, Fan)
44
+#define BOARD_RAMPS_14_SF       48    // RAMPS 1.4 (Power outputs: Spindle, Controller Fan)
45
+
46
+#define BOARD_RAMPS_PLUS_EFB   143    // RAMPS Plus 3DYMY (Power outputs: Hotend, Fan, Bed)
47
+#define BOARD_RAMPS_PLUS_EEB   144    // RAMPS Plus 3DYMY (Power outputs: Hotend0, Hotend1, Bed)
48
+#define BOARD_RAMPS_PLUS_EFF   145    // RAMPS Plus 3DYMY (Power outputs: Hotend, Fan0, Fan1)
49
+#define BOARD_RAMPS_PLUS_EEF   146    // RAMPS Plus 3DYMY (Power outputs: Hotend0, Hotend1, Fan)
50
+#define BOARD_RAMPS_PLUS_SF    148    // RAMPS Plus 3DYMY (Power outputs: Spindle, Controller Fan)
51
+
52
+//
53
+// RAMPS Derivatives - ATmega1280, ATmega2560
54
+//
55
+
56
+#define BOARD_3DRAG             77    // 3Drag Controller
57
+#define BOARD_K8200             78    // Velleman K8200 Controller (derived from 3Drag Controller)
58
+#define BOARD_K8400             79    // Velleman K8400 Controller (derived from 3Drag Controller)
59
+#define BOARD_BAM_DICE          401   // 2PrintBeta BAM&DICE with STK drivers
60
+#define BOARD_BAM_DICE_DUE      402   // 2PrintBeta BAM&DICE Due with STK drivers
61
+#define BOARD_MKS_BASE          40    // MKS BASE 1.0
62
+#define BOARD_MKS_13            47    // MKS v1.3 or 1.4 (maybe higher)
63
+#define BOARD_MKS_GEN_L         53    // MKS GEN L
64
+#define BOARD_ZRIB_V20          504   // zrib V2.0 control board (Chinese knock off RAMPS replica)
65
+#define BOARD_FELIX2            37    // Felix 2.0+ Electronics Board (RAMPS like)
66
+#define BOARD_RIGIDBOARD        42    // Invent-A-Part RigidBoard
67
+#define BOARD_RIGIDBOARD_V2     52    // Invent-A-Part RigidBoard V2
68
+#define BOARD_SAINSMART_2IN1    49    // Sainsmart 2-in-1 board
69
+#define BOARD_ULTIMAKER         7     // Ultimaker
70
+#define BOARD_ULTIMAKER_OLD     71    // Ultimaker (Older electronics. Pre 1.5.4. This is rare)
71
+#define BOARD_AZTEEG_X3         67    // Azteeg X3
72
+#define BOARD_AZTEEG_X3_PRO     68    // Azteeg X3 Pro
73
+#define BOARD_ULTIMAIN_2        72    // Ultimainboard 2.x (Uses TEMP_SENSOR 20)
74
+#define BOARD_RUMBA             80    // Rumba
75
+#define BOARD_BQ_ZUM_MEGA_3D    503   // bq ZUM Mega 3D
76
+#define BOARD_MAKEBOARD_MINI    431   // MakeBoard Mini v2.1.2 is a control board sold by MicroMake
77
+
78
+//
79
+// Other ATmega1280, ATmega2560
80
+//
81
+
82
+#define BOARD_CNCONTROLS_11     111   // Cartesio CN Controls V11
83
+#define BOARD_CNCONTROLS_12     112   // Cartesio CN Controls V12
84
+#define BOARD_CHEAPTRONIC       2     // Cheaptronic v1.0
85
+#define BOARD_CHEAPTRONIC_V2    21    // Cheaptronic v2.0
86
+#define BOARD_MIGHTYBOARD_REVE  200   // Makerbot Mightyboard Revision E
87
+#define BOARD_MEGATRONICS       70    // Megatronics
88
+#define BOARD_MEGATRONICS_2     701   // Megatronics v2.0
89
+#define BOARD_MEGATRONICS_3     703   // Megatronics v3.0
90
+#define BOARD_MEGATRONICS_31    704   // Megatronics v3.1
91
+#define BOARD_RAMBO             301   // Rambo
92
+#define BOARD_MINIRAMBO         302   // Mini-Rambo
93
+#define BOARD_MINIRAMBO_10A     303   // Mini-Rambo 1.0a
94
+#define BOARD_ELEFU_3           21    // Elefu Ra Board (v3)
95
+#define BOARD_LEAPFROG          999   // Leapfrog
96
+#define BOARD_MEGACONTROLLER    310   // Mega controller
97
+#define BOARD_SCOOVO_X9H        321   // abee Scoovo X9H
98
+#define BOARD_GT2560_REV_A      74    // Geeetech GT2560 Rev. A
99
+#define BOARD_GT2560_REV_A_PLUS 75    // Geeetech GT2560 Rev. A+ (with auto level probe)
100
+
101
+//
102
+// ATmega1281, ATmega2561
103
+//
104
+
105
+#define BOARD_MINITRONICS       702   // Minitronics v1.0/1.1
106
+#define BOARD_SILVER_GATE       25    // Silvergate v1.0
107
+
108
+//
109
+// Sanguinololu and Derivatives - ATmega644P, ATmega1284P
110
+//
111
+
112
+#define BOARD_SANGUINOLOLU_11   6     // Sanguinololu < 1.2
113
+#define BOARD_SANGUINOLOLU_12   62    // Sanguinololu 1.2 and above
114
+#define BOARD_MELZI             63    // Melzi
115
+#define BOARD_MELZI_MAKR3D      66    // Melzi with ATmega1284 (MaKr3d version)
116
+#define BOARD_MELZI_CREALITY    89    // Melzi Creality3D board (for CR-10 etc)
117
+#define BOARD_STB_11            64    // STB V1.1
118
+#define BOARD_AZTEEG_X1         65    // Azteeg X1
119
+
120
+//
121
+// Other ATmega644P, ATmega644, ATmega1284P
122
+//
123
+
124
+#define BOARD_GEN3_MONOLITHIC   22    // Gen3 Monolithic Electronics
125
+#define BOARD_GEN3_PLUS         9     // Gen3+
126
+#define BOARD_GEN6              5     // Gen6
127
+#define BOARD_GEN6_DELUXE       51    // Gen6 deluxe
128
+#define BOARD_GEN7_CUSTOM       10    // Gen7 custom (Alfons3 Version) "https://github.com/Alfons3/Generation_7_Electronics"
129
+#define BOARD_GEN7_12           11    // Gen7 v1.1, v1.2
130
+#define BOARD_GEN7_13           12    // Gen7 v1.3
131
+#define BOARD_GEN7_14           13    // Gen7 v1.4
132
+#define BOARD_OMCA_A            90    // Alpha OMCA board
133
+#define BOARD_OMCA              91    // Final OMCA board
134
+#define BOARD_SETHI             20    // Sethi 3D_1
135
+#define BOARD_ANET_10           69    // Anet 1.0 (Melzi clone)
136
+
137
+//
138
+// Teensyduino - AT90USB1286, AT90USB1286P
139
+//
140
+
141
+#define BOARD_TEENSYLU          8     // Teensylu
142
+#define BOARD_PRINTRBOARD       81    // Printrboard (AT90USB1286)
143
+#define BOARD_PRINTRBOARD_REVF  811   // Printrboard Revision F (AT90USB1286)
144
+#define BOARD_BRAINWAVE         82    // Brainwave (AT90USB646)
145
+#define BOARD_BRAINWAVE_PRO     85    // Brainwave Pro (AT90USB1286)
146
+#define BOARD_SAV_MKI           83    // SAV Mk-I (AT90USB1286)
147
+#define BOARD_TEENSY2           84    // Teensy++2.0 (AT90USB1286) - CLI compile: HARDWARE_MOTHERBOARD=84  make
148
+#define BOARD_5DPRINT           88    // 5DPrint D8 Driver Board
100 149
 
101 150
 #define MB(board) (MOTHERBOARD==BOARD_##board)
102 151
 

+ 96
- 72
Marlin/cardreader.cpp 파일 보기

@@ -20,16 +20,16 @@
20 20
  *
21 21
  */
22 22
 
23
+#include "MarlinConfig.h"
24
+
25
+#if ENABLED(SDSUPPORT)
26
+
23 27
 #include "cardreader.h"
24 28
 
25 29
 #include "ultralcd.h"
26 30
 #include "stepper.h"
27 31
 #include "language.h"
28 32
 
29
-#include "Marlin.h"
30
-
31
-#if ENABLED(SDSUPPORT)
32
-
33 33
 #define LONGEST_FILENAME (longFilename[0] ? longFilename : filename)
34 34
 
35 35
 CardReader::CardReader() {
@@ -44,8 +44,9 @@ CardReader::CardReader() {
44 44
   sdprinting = cardOK = saving = logging = false;
45 45
   filesize = 0;
46 46
   sdpos = 0;
47
-  workDirDepth = 0;
48 47
   file_subcall_ctr = 0;
48
+
49
+  workDirDepth = 0;
49 50
   ZERO(workDirParents);
50 51
 
51 52
   autostart_stilltocheck = true; //the SD start is delayed, because otherwise the serial cannot answer fast enough to make contact with the host software.
@@ -73,9 +74,12 @@ char *createFilename(char *buffer, const dir_t &p) { //buffer > 12characters
73 74
 /**
74 75
  * Dive into a folder and recurse depth-first to perform a pre-set operation lsAction:
75 76
  *   LS_Count       - Add +1 to nrFiles for every file within the parent
76
- *   LS_GetFilename - Get the filename of the file indexed by nrFiles
77
+ *   LS_GetFilename - Get the filename of the file indexed by nrFile_index
77 78
  *   LS_SerialPrint - Print the full path and size of each file to serial output
78 79
  */
80
+
81
+uint16_t nrFile_index;
82
+
79 83
 void CardReader::lsDive(const char *prepend, SdFile parent, const char * const match/*=NULL*/) {
80 84
   dir_t p;
81 85
   uint8_t cnt = 0;
@@ -129,7 +133,7 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
129 133
 
130 134
       if (!filenameIsDir && (p.name[8] != 'G' || p.name[9] == '~')) continue;
131 135
 
132
-      switch (lsAction) {
136
+      switch (lsAction) {  // 1 based file count
133 137
         case LS_Count:
134 138
           nrFiles++;
135 139
           break;
@@ -147,7 +151,7 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
147 151
           if (match != NULL) {
148 152
             if (strcasecmp(match, filename) == 0) return;
149 153
           }
150
-          else if (cnt == nrFiles) return;
154
+          else if (cnt == nrFile_index) return;  // 0 based index
151 155
           cnt++;
152 156
           break;
153 157
       }
@@ -255,16 +259,7 @@ void CardReader::initsd() {
255 259
     SERIAL_ECHO_START();
256 260
     SERIAL_ECHOLNPGM(MSG_SD_CARD_OK);
257 261
   }
258
-  workDir = root;
259
-  curDir = &root;
260
-  #if ENABLED(SDCARD_SORT_ALPHA)
261
-    presort();
262
-  #endif
263
-  /**
264
-  if (!workDir.openRoot(&volume)) {
265
-    SERIAL_ECHOLNPGM(MSG_SD_WORKDIR_FAIL);
266
-  }
267
-  */
262
+  setroot();
268 263
 }
269 264
 
270 265
 void CardReader::setroot() {
@@ -310,26 +305,33 @@ void CardReader::openLogFile(char* name) {
310 305
   openFile(name, false);
311 306
 }
312 307
 
308
+void appendAtom(SdFile &file, char *& dst, uint8_t &cnt) {
309
+  file.getFilename(dst);
310
+  while (*dst && cnt < MAXPATHNAMELENGTH) { dst++; cnt++; }
311
+  if (cnt < MAXPATHNAMELENGTH) { *dst = '/'; dst++; cnt++; }
312
+}
313
+
313 314
 void CardReader::getAbsFilename(char *t) {
314
-  uint8_t cnt = 0;
315
-  *t = '/'; t++; cnt++;
316
-  for (uint8_t i = 0; i < workDirDepth; i++) {
317
-    workDirParents[i].getFilename(t); //SDBaseFile.getfilename!
318
-    while (*t && cnt < MAXPATHNAMELENGTH) { t++; cnt++; } //crawl counter forward.
315
+  *t++ = '/';                                               // Root folder
316
+  uint8_t cnt = 1;
317
+
318
+  for (uint8_t i = 0; i < workDirDepth; i++)                // Loop to current work dir
319
+    appendAtom(workDirParents[i], t, cnt);
320
+
321
+  if (cnt < MAXPATHNAMELENGTH - (FILENAME_LENGTH)) {
322
+    appendAtom(file, t, cnt);
323
+    --t;
319 324
   }
320
-  if (cnt < MAXPATHNAMELENGTH - (FILENAME_LENGTH))
321
-    file.getFilename(t);
322
-  else
323
-    t[0] = 0;
325
+  *t = '\0';
324 326
 }
325 327
 
326
-void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) {
328
+void CardReader::openFile(char* name, const bool read, const bool subcall/*=false*/) {
327 329
 
328 330
   if (!cardOK) return;
329 331
 
330 332
   uint8_t doing = 0;
331
-  if (isFileOpen()) { //replacing current file by new file, or subfile call
332
-    if (push_current) {
333
+  if (isFileOpen()) {                     // Replacing current file or doing a subroutine
334
+    if (subcall) {
333 335
       if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) {
334 336
         SERIAL_ERROR_START();
335 337
         SERIAL_ERRORPGM("trying to call sub-gcode files with too many levels. MAX level is:");
@@ -338,21 +340,24 @@ void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) {
338 340
         return;
339 341
       }
340 342
 
341
-      // Store current filename and position
343
+      // Store current filename (based on workDirParents) and position
342 344
       getAbsFilename(proc_filenames[file_subcall_ctr]);
345
+      filespos[file_subcall_ctr] = sdpos;
343 346
 
344 347
       SERIAL_ECHO_START();
345 348
       SERIAL_ECHOPAIR("SUBROUTINE CALL target:\"", name);
346 349
       SERIAL_ECHOPAIR("\" parent:\"", proc_filenames[file_subcall_ctr]);
347 350
       SERIAL_ECHOLNPAIR("\" pos", sdpos);
348
-      filespos[file_subcall_ctr] = sdpos;
349 351
       file_subcall_ctr++;
350 352
     }
351
-    else {
353
+    else
352 354
       doing = 1;
353
-    }
354 355
   }
355
-  else { // Opening fresh file
356
+  else if (subcall) {     // Returning from a subcall?
357
+    SERIAL_ECHO_START();
358
+    SERIAL_ECHOLNPGM("END SUBROUTINE");
359
+  }
360
+  else {                  // Opening fresh file
356 361
     doing = 2;
357 362
     file_subcall_ctr = 0; // Reset procedure depth in case user cancels print while in procedure
358 363
   }
@@ -360,7 +365,7 @@ void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) {
360 365
   if (doing) {
361 366
     SERIAL_ECHO_START();
362 367
     SERIAL_ECHOPGM("Now ");
363
-    SERIAL_ECHO(doing == 1 ? "doing" : "fresh");
368
+    serialprintPGM(doing == 1 ? PSTR("doing") : PSTR("fresh"));
364 369
     SERIAL_ECHOLNPAIR(" file: ", name);
365 370
   }
366 371
 
@@ -380,8 +385,7 @@ void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) {
380 385
       if (dirname_end != NULL && dirname_end > dirname_start) {
381 386
         char subdirname[FILENAME_LENGTH];
382 387
         strncpy(subdirname, dirname_start, dirname_end - dirname_start);
383
-        subdirname[dirname_end - dirname_start] = 0;
384
-        SERIAL_ECHOLN(subdirname);
388
+        subdirname[dirname_end - dirname_start] = '\0';
385 389
         if (!myDir.open(curDir, subdirname, O_READ)) {
386 390
           SERIAL_PROTOCOLPGM(MSG_SD_OPEN_FILE_FAIL);
387 391
           SERIAL_PROTOCOL(subdirname);
@@ -403,17 +407,15 @@ void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) {
403 407
       }
404 408
     }
405 409
   }
406
-  else { //relative path
407
-    curDir = &workDir;
408
-  }
410
+  else
411
+    curDir = &workDir; // Relative paths start in current directory
409 412
 
410 413
   if (read) {
411 414
     if (file.open(curDir, fname, O_READ)) {
412 415
       filesize = file.fileSize();
416
+      sdpos = 0;
413 417
       SERIAL_PROTOCOLPAIR(MSG_SD_FILE_OPENED, fname);
414 418
       SERIAL_PROTOCOLLNPAIR(MSG_SD_SIZE, filesize);
415
-      sdpos = 0;
416
-
417 419
       SERIAL_PROTOCOLLNPGM(MSG_SD_FILE_SELECTED);
418 420
       getfilename(0, fname);
419 421
       lcd_setstatus(longFilename[0] ? longFilename : fname);
@@ -438,14 +440,14 @@ void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) {
438 440
   }
439 441
 }
440 442
 
441
-void CardReader::removeFile(char* name) {
443
+void CardReader::removeFile(const char * const name) {
442 444
   if (!cardOK) return;
443 445
 
444 446
   stopSDPrint();
445 447
 
446 448
   SdFile myDir;
447 449
   curDir = &root;
448
-  char *fname = name;
450
+  const char *fname = name;
449 451
 
450 452
   char *dirname_start, *dirname_end;
451 453
   if (name[0] == '/') {
@@ -460,29 +462,23 @@ void CardReader::removeFile(char* name) {
460 462
         subdirname[dirname_end - dirname_start] = 0;
461 463
         SERIAL_ECHOLN(subdirname);
462 464
         if (!myDir.open(curDir, subdirname, O_READ)) {
463
-          SERIAL_PROTOCOLPAIR("open failed, File: ", subdirname);
465
+          SERIAL_PROTOCOLPAIR(MSG_SD_OPEN_FILE_FAIL, subdirname);
464 466
           SERIAL_PROTOCOLCHAR('.');
465 467
           SERIAL_EOL();
466 468
           return;
467 469
         }
468
-        else {
469
-          //SERIAL_ECHOLNPGM("dive ok");
470
-        }
471 470
 
472 471
         curDir = &myDir;
473 472
         dirname_start = dirname_end + 1;
474 473
       }
475
-      else { // the remainder after all /fsa/fdsa/ is the filename
474
+      else {
476 475
         fname = dirname_start;
477
-        //SERIAL_ECHOLNPGM("remainder");
478
-        //SERIAL_ECHOLN(fname);
479 476
         break;
480 477
       }
481 478
     }
482 479
   }
483
-  else { // relative path
480
+  else // Relative paths are rooted in the current directory
484 481
     curDir = &workDir;
485
-  }
486 482
 
487 483
   if (file.remove(curDir, fname)) {
488 484
     SERIAL_PROTOCOLPGM("File deleted:");
@@ -506,14 +502,13 @@ void CardReader::getStatus() {
506 502
     SERIAL_PROTOCOLCHAR('/');
507 503
     SERIAL_PROTOCOLLN(filesize);
508 504
   }
509
-  else {
505
+  else
510 506
     SERIAL_PROTOCOLLNPGM(MSG_SD_NOT_PRINTING);
511
-  }
512 507
 }
513 508
 
514 509
 void CardReader::write_command(char *buf) {
515 510
   char* begin = buf;
516
-  char* npos = 0;
511
+  char* npos = NULL;
517 512
   char* end = buf + strlen(buf) - 1;
518 513
 
519 514
   file.writeError = false;
@@ -532,7 +527,7 @@ void CardReader::write_command(char *buf) {
532 527
 }
533 528
 
534 529
 void CardReader::checkautostart(bool force) {
535
-  if (!force && (!autostart_stilltocheck || ELAPSED(millis(), next_autostart_ms)))
530
+  if (!force && (!autostart_stilltocheck || PENDING(millis(), next_autostart_ms)))
536 531
     return;
537 532
 
538 533
   autostart_stilltocheck = false;
@@ -595,7 +590,7 @@ void CardReader::getfilename(uint16_t nr, const char * const match/*=NULL*/) {
595 590
   #endif // SDSORT_CACHE_NAMES
596 591
   curDir = &workDir;
597 592
   lsAction = LS_GetFilename;
598
-  nrFiles = nr;
593
+  nrFile_index = nr;
599 594
   curDir->rewind();
600 595
   lsDive("", *curDir, match);
601 596
 }
@@ -611,33 +606,34 @@ uint16_t CardReader::getnrfilenames() {
611 606
 }
612 607
 
613 608
 void CardReader::chdir(const char * relpath) {
614
-  SdFile newfile;
609
+  SdFile newDir;
615 610
   SdFile *parent = &root;
616 611
 
617 612
   if (workDir.isOpen()) parent = &workDir;
618 613
 
619
-  if (!newfile.open(*parent, relpath, O_READ)) {
614
+  if (!newDir.open(*parent, relpath, O_READ)) {
620 615
     SERIAL_ECHO_START();
621 616
     SERIAL_ECHOPGM(MSG_SD_CANT_ENTER_SUBDIR);
622 617
     SERIAL_ECHOLN(relpath);
623 618
   }
624 619
   else {
620
+    workDir = newDir;
625 621
     if (workDirDepth < MAX_DIR_DEPTH)
626
-      workDirParents[workDirDepth++] = *parent;
627
-    workDir = newfile;
622
+      workDirParents[workDirDepth++] = workDir;
628 623
     #if ENABLED(SDCARD_SORT_ALPHA)
629 624
       presort();
630 625
     #endif
631 626
   }
632 627
 }
633 628
 
634
-void CardReader::updir() {
635
-  if (workDirDepth > 0) {
636
-    workDir = workDirParents[--workDirDepth];
629
+int8_t CardReader::updir() {
630
+  if (workDirDepth > 0) {                                               // At least 1 dir has been saved
631
+    workDir = --workDirDepth ? workDirParents[workDirDepth - 1] : root; // Use parent, or root if none
637 632
     #if ENABLED(SDCARD_SORT_ALPHA)
638 633
       presort();
639 634
     #endif
640 635
   }
636
+  return workDirDepth;
641 637
 }
642 638
 
643 639
 #if ENABLED(SDCARD_SORT_ALPHA)
@@ -696,7 +692,7 @@ void CardReader::updir() {
696 692
             sortnames = new char*[fileCnt];
697 693
           #endif
698 694
         #elif ENABLED(SDSORT_USES_STACK)
699
-          char sortnames[fileCnt][LONG_FILENAME_LENGTH];
695
+          char sortnames[fileCnt][SORTED_LONGNAME_MAXLEN];
700 696
         #endif
701 697
 
702 698
         // Folder sorting needs 1 bit per entry for flags.
@@ -735,7 +731,12 @@ void CardReader::updir() {
735 731
               #endif
736 732
             #else
737 733
               // Copy filenames into the static array
738
-              strcpy(sortnames[i], LONGEST_FILENAME);
734
+              #if SORTED_LONGNAME_MAXLEN != LONG_FILENAME_LENGTH
735
+                strncpy(sortnames[i], LONGEST_FILENAME, SORTED_LONGNAME_MAXLEN);
736
+                sortnames[i][SORTED_LONGNAME_MAXLEN - 1] = '\0';
737
+              #else
738
+                strncpy(sortnames[i], LONGEST_FILENAME, SORTED_LONGNAME_MAXLEN);
739
+              #endif
739 740
               #if ENABLED(SDSORT_CACHE_NAMES)
740 741
                 strcpy(sortshort[i], filename);
741 742
               #endif
@@ -826,12 +827,21 @@ void CardReader::updir() {
826 827
           #if ENABLED(SDSORT_DYNAMIC_RAM)
827 828
             sortnames = new char*[1];
828 829
             sortnames[0] = strdup(LONGEST_FILENAME); // malloc
829
-            sortshort = new char*[1];
830
-            sortshort[0] = strdup(filename);         // malloc
830
+            #if ENABLED(SDSORT_CACHE_NAMES)
831
+              sortshort = new char*[1];
832
+              sortshort[0] = strdup(filename);       // malloc
833
+            #endif
831 834
             isDir = new uint8_t[1];
832 835
           #else
833
-            strcpy(sortnames[0], LONGEST_FILENAME);
834
-            strcpy(sortshort[0], filename);
836
+            #if SORTED_LONGNAME_MAXLEN != LONG_FILENAME_LENGTH
837
+              strncpy(sortnames[0], LONGEST_FILENAME, SORTED_LONGNAME_MAXLEN);
838
+              sortnames[0][SORTED_LONGNAME_MAXLEN - 1] = '\0';
839
+            #else
840
+              strncpy(sortnames[0], LONGEST_FILENAME, SORTED_LONGNAME_MAXLEN);
841
+            #endif
842
+            #if ENABLED(SDSORT_CACHE_NAMES)
843
+              strcpy(sortshort[0], filename);
844
+            #endif
835 845
           #endif
836 846
           isDir[0] = filenameIsDir ? 0x01 : 0x00;
837 847
         #endif
@@ -860,6 +870,16 @@ void CardReader::updir() {
860 870
 
861 871
 #endif // SDCARD_SORT_ALPHA
862 872
 
873
+uint16_t CardReader::get_num_Files() {
874
+  return
875
+    #if ENABLED(SDCARD_SORT_ALPHA) && SDSORT_USES_RAM && SDSORT_CACHE_NAMES
876
+      nrFiles // no need to access the SD card for filenames
877
+    #else
878
+      getnrfilenames()
879
+    #endif
880
+  ;
881
+}
882
+
863 883
 void CardReader::printingHasFinished() {
864 884
   stepper.synchronize();
865 885
   file.close();
@@ -879,6 +899,10 @@ void CardReader::printingHasFinished() {
879 899
     #if ENABLED(SDCARD_SORT_ALPHA)
880 900
       presort();
881 901
     #endif
902
+
903
+    #if ENABLED(SD_REPRINT_LAST_SELECTED_FILE)
904
+      lcd_reselect_last_file();
905
+    #endif
882 906
   }
883 907
 }
884 908
 

+ 33
- 23
Marlin/cardreader.h 파일 보기

@@ -20,8 +20,8 @@
20 20
  *
21 21
  */
22 22
 
23
-#ifndef CARDREADER_H
24
-#define CARDREADER_H
23
+#ifndef _CARDREADER_H_
24
+#define _CARDREADER_H_
25 25
 
26 26
 #include "MarlinConfig.h"
27 27
 
@@ -30,7 +30,6 @@
30 30
 #define MAX_DIR_DEPTH 10          // Maximum folder depth
31 31
 
32 32
 #include "SdFile.h"
33
-
34 33
 #include "types.h"
35 34
 #include "enum.h"
36 35
 
@@ -40,13 +39,15 @@ public:
40 39
 
41 40
   void initsd();
42 41
   void write_command(char *buf);
43
-  //files auto[0-9].g on the sd card are performed in a row
44
-  //this is to delay autostart and hence the initialisaiton of the sd card to some seconds after the normal init, so the device is available quick after a reset
42
+  // Files auto[0-9].g on the sd card are performed in sequence.
43
+  // This is to delay autostart and hence the initialisation of
44
+  // the sd card to some seconds after the normal init, so the
45
+  // device is available soon after a reset.
45 46
 
46 47
   void checkautostart(bool x);
47
-  void openFile(char* name, bool read, bool push_current=false);
48
+  void openFile(char* name, const bool read, const bool subcall=false);
48 49
   void openLogFile(char* name);
49
-  void removeFile(char* name);
50
+  void removeFile(const char * const name);
50 51
   void closefile(bool store_location=false);
51 52
   void release();
52 53
   void openAndPrintFile(const char *name);
@@ -66,9 +67,11 @@ public:
66 67
 
67 68
   void ls();
68 69
   void chdir(const char *relpath);
69
-  void updir();
70
+  int8_t updir();
70 71
   void setroot();
71 72
 
73
+  uint16_t get_num_Files();
74
+
72 75
   #if ENABLED(SDCARD_SORT_ALPHA)
73 76
     void presort();
74 77
     void getfilename_sorted(const uint16_t nr);
@@ -111,6 +114,12 @@ private:
111 114
       uint8_t sort_order[SDSORT_LIMIT];
112 115
     #endif
113 116
 
117
+    #if ENABLED(SDSORT_USES_RAM) && ENABLED(SDSORT_CACHE_NAMES) && DISABLED(SDSORT_DYNAMIC_RAM)
118
+      #define SORTED_LONGNAME_MAXLEN ((SDSORT_CACHE_VFATS) * (FILENAME_LENGTH) + 1)
119
+    #else
120
+      #define SORTED_LONGNAME_MAXLEN LONG_FILENAME_LENGTH
121
+    #endif
122
+
114 123
     // Cache filenames to speed up SD menus.
115 124
     #if ENABLED(SDSORT_USES_RAM)
116 125
 
@@ -120,10 +129,10 @@ private:
120 129
           char **sortshort, **sortnames;
121 130
         #else
122 131
           char sortshort[SDSORT_LIMIT][FILENAME_LENGTH];
123
-          char sortnames[SDSORT_LIMIT][FILENAME_LENGTH];
132
+          char sortnames[SDSORT_LIMIT][SORTED_LONGNAME_MAXLEN];
124 133
         #endif
125 134
       #elif DISABLED(SDSORT_USES_STACK)
126
-        char sortnames[SDSORT_LIMIT][FILENAME_LENGTH];
135
+        char sortnames[SDSORT_LIMIT][SORTED_LONGNAME_MAXLEN];
127 136
       #endif
128 137
 
129 138
       // Folder sorting uses an isDir array when caching items.
@@ -148,8 +157,7 @@ private:
148 157
   uint8_t file_subcall_ctr;
149 158
   uint32_t filespos[SD_PROCEDURE_DEPTH];
150 159
   char proc_filenames[SD_PROCEDURE_DEPTH][MAXPATHNAMELENGTH];
151
-  uint32_t filesize;
152
-  uint32_t sdpos;
160
+  uint32_t filesize, sdpos;
153 161
 
154 162
   millis_t next_autostart_ms;
155 163
   bool autostart_stilltocheck; //the sd start is delayed, because otherwise the serial cannot answer fast enought to make contact with the hostsoftware.
@@ -164,25 +172,27 @@ private:
164 172
   #endif
165 173
 };
166 174
 
167
-extern CardReader card;
168
-
169
-#define IS_SD_PRINTING (card.sdprinting)
170
-
171 175
 #if PIN_EXISTS(SD_DETECT)
172 176
   #if ENABLED(SD_DETECT_INVERTED)
173
-    #define IS_SD_INSERTED (READ(SD_DETECT_PIN) != 0)
177
+    #define IS_SD_INSERTED (READ(SD_DETECT_PIN) == HIGH)
174 178
   #else
175
-    #define IS_SD_INSERTED (READ(SD_DETECT_PIN) == 0)
179
+    #define IS_SD_INSERTED (READ(SD_DETECT_PIN) == LOW)
176 180
   #endif
177 181
 #else
178
-  //No card detect line? Assume the card is inserted.
182
+  // No card detect line? Assume the card is inserted.
179 183
   #define IS_SD_INSERTED true
180 184
 #endif
181 185
 
182
-#else
183
-
184
-#define IS_SD_PRINTING (false)
186
+extern CardReader card;
185 187
 
186 188
 #endif // SDSUPPORT
187 189
 
188
-#endif // __CARDREADER_H
190
+#if ENABLED(SDSUPPORT)
191
+  #define IS_SD_PRINTING (card.sdprinting)
192
+  #define IS_SD_FILE_OPEN (card.isFileOpen())
193
+#else
194
+  #define IS_SD_PRINTING (false)
195
+  #define IS_SD_FILE_OPEN (false)
196
+#endif
197
+
198
+#endif // _CARDREADER_H_

+ 632
- 356
Marlin/configuration_store.cpp
파일 크기가 너무 크기때문에 변경 상태를 표시하지 않습니다.
파일 보기


+ 2
- 2
Marlin/configuration_store.h 파일 보기

@@ -52,10 +52,10 @@ class MarlinSettings {
52 52
     #endif
53 53
 
54 54
     #if DISABLED(DISABLE_M503)
55
-      static void report(bool forReplay=false);
55
+      static void report(const bool forReplay=false);
56 56
     #else
57 57
       FORCE_INLINE
58
-      static void report(bool forReplay=false) { UNUSED(forReplay); }
58
+      static void report(const bool forReplay=false) { UNUSED(forReplay); }
59 59
     #endif
60 60
 
61 61
   private:

+ 199
- 58
Marlin/dogm_bitmaps.h 파일 보기

@@ -38,10 +38,8 @@
38 38
   #if ENABLED(START_BMPHIGH)
39 39
     #define START_BMPWIDTH      112
40 40
     #define START_BMPHEIGHT      38
41
-    #define START_BMPBYTEWIDTH   14
42
-    #define START_BMPBYTES      532 // START_BMPWIDTH * START_BMPHEIGHT / 8
43 41
 
44
-    const unsigned char start_bmp[START_BMPBYTES] PROGMEM = {
42
+    const unsigned char start_bmp[] PROGMEM = {
45 43
       0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
46 44
       0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
47 45
       0x1E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0xFF, 0xFF,
@@ -83,10 +81,8 @@
83 81
   #else
84 82
     #define START_BMPWIDTH      56
85 83
     #define START_BMPHEIGHT     19
86
-    #define START_BMPBYTEWIDTH  7
87
-    #define START_BMPBYTES      133 // START_BMPWIDTH * START_BMPHEIGHT / 8
88 84
 
89
-    const unsigned char start_bmp[START_BMPBYTES] PROGMEM = {
85
+    const unsigned char start_bmp[] PROGMEM = {
90 86
       0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
91 87
       0x60, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF,
92 88
       0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF,
@@ -115,12 +111,55 @@
115 111
 // When only one extruder is selected, the "1" on the symbol will not
116 112
 // be displayed.
117 113
 
114
+#define STATUS_SCREENWIDTH     115 // Width in pixels
115
+#define STATUS_SCREENHEIGHT     19 // Height in pixels
116
+
118 117
 #if HAS_TEMP_BED
119
-  #if HOTENDS == 1
120
-    #define STATUS_SCREENWIDTH     115 //Width in pixels
121
-    #define STATUS_SCREENHEIGHT     19 //Height in pixels
122
-    #define STATUS_SCREENBYTEWIDTH  15 //Width in bytes
123
-    const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
118
+  #if HOTENDS == 0
119
+    const unsigned char status_screen0_bmp[] PROGMEM = {
120
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
121
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
122
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
123
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x47, 0x0E, 0x20,
124
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x4F, 0x0F, 0x20,
125
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5F, 0x0F, 0xA0,
126
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5E, 0x07, 0xA0,
127
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x40, 0x60, 0x20,
128
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x82, 0x00, 0x40, 0xF0, 0x20,
129
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x82, 0x00, 0x40, 0xF0, 0x20,
130
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x40, 0x60, 0x20,
131
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x82, 0x08, 0x00, 0x5E, 0x07, 0xA0,
132
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x04, 0x10, 0x00, 0x5F, 0x0F, 0xA0,
133
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x04, 0x10, 0x00, 0x4F, 0x0F, 0x20,
134
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x82, 0x08, 0x00, 0x47, 0x0E, 0x20,
135
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x63, 0x0C, 0x60,
136
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
137
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xE0,
138
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
139
+    };
140
+    const unsigned char status_screen1_bmp[] PROGMEM = {
141
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
142
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
143
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
144
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0xF8, 0x20,
145
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0xF0, 0x20,
146
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x60, 0x20,
147
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x58, 0x01, 0xA0,
148
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x5C, 0x63, 0xA0,
149
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x82, 0x00, 0x5E, 0xF7, 0xA0,
150
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x82, 0x00, 0x5E, 0xF7, 0xA0,
151
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x5C, 0x63, 0xA0,
152
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x82, 0x08, 0x00, 0x58, 0x01, 0xA0,
153
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x04, 0x10, 0x00, 0x40, 0x60, 0x20,
154
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x04, 0x10, 0x00, 0x40, 0xF0, 0x20,
155
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x82, 0x08, 0x00, 0x41, 0xF8, 0x20,
156
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x61, 0xF8, 0x60,
157
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
158
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xE0,
159
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
160
+    };
161
+  #elif HOTENDS == 1
162
+    const unsigned char status_screen0_bmp[] PROGMEM = {
124 163
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
125 164
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
126 165
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
@@ -142,10 +181,7 @@
142 181
       0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
143 182
     };
144 183
 
145
-    #define STATUS_SCREENWIDTH     115 //Width in pixels
146
-    #define STATUS_SCREENHEIGHT     19 //Height in pixels
147
-    #define STATUS_SCREENBYTEWIDTH  15 //Width in bytes
148
-    const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
184
+    const unsigned char status_screen1_bmp[] PROGMEM = {
149 185
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
150 186
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
151 187
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
@@ -167,10 +203,7 @@
167 203
       0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
168 204
     };
169 205
   #elif HOTENDS == 2
170
-    #define STATUS_SCREENWIDTH     115 //Width in pixels
171
-    #define STATUS_SCREENHEIGHT     19 //Height in pixels
172
-    #define STATUS_SCREENBYTEWIDTH  15 //Width in bytes
173
-    const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
206
+    const unsigned char status_screen0_bmp[] PROGMEM = {
174 207
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
175 208
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
176 209
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
@@ -192,10 +225,7 @@
192 225
       0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
193 226
     };
194 227
 
195
-    #define STATUS_SCREENWIDTH     115 //Width in pixels
196
-    #define STATUS_SCREENHEIGHT     19 //Height in pixels
197
-    #define STATUS_SCREENBYTEWIDTH  15 //Width in bytes
198
-    const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
228
+    const unsigned char status_screen1_bmp[] PROGMEM = {
199 229
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
200 230
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
201 231
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
@@ -217,10 +247,7 @@
217 247
       0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
218 248
     };
219 249
   #else
220
-    #define STATUS_SCREENWIDTH     115 //Width in pixels
221
-    #define STATUS_SCREENHEIGHT     19 //Height in pixels
222
-    #define STATUS_SCREENBYTEWIDTH  15 //Width in bytes
223
-    const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
250
+    const unsigned char status_screen0_bmp[] PROGMEM = {
224 251
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
225 252
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
226 253
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
@@ -242,10 +269,7 @@
242 269
       0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x06, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
243 270
     };
244 271
 
245
-    #define STATUS_SCREENWIDTH     115 //Width in pixels
246
-    #define STATUS_SCREENHEIGHT     19 //Height in pixels
247
-    #define STATUS_SCREENBYTEWIDTH  15 //Width in bytes
248
-    const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
272
+    const unsigned char status_screen1_bmp[] PROGMEM = {
249 273
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
250 274
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
251 275
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
@@ -266,13 +290,53 @@
266 290
       0x1E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x0F, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xE0,
267 291
       0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x06, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
268 292
     };
269
-  #endif // Extruders
293
+  #endif // HOTENDS
270 294
 #else
271
-  #if HOTENDS == 1
272
-    #define STATUS_SCREENWIDTH     115 //Width in pixels
273
-    #define STATUS_SCREENHEIGHT     19 //Height in pixels
274
-    #define STATUS_SCREENBYTEWIDTH  15 //Width in bytes
275
-    const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
295
+  #if HOTENDS == 0
296
+    const unsigned char status_screen0_bmp[] PROGMEM = {
297
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
298
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
299
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
300
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x47, 0x0E, 0x20,
301
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x4F, 0x0F, 0x20,
302
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5F, 0x0F, 0xA0,
303
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5E, 0x07, 0xA0,
304
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x60, 0x20,
305
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0xF0, 0x20,
306
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0xF0, 0x20,
307
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x60, 0x20,
308
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5E, 0x07, 0xA0,
309
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5F, 0x0F, 0xA0,
310
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x4F, 0x0F, 0x20,
311
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x47, 0x0E, 0x20,
312
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
313
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
314
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
315
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
316
+    };
317
+    const unsigned char status_screen1_bmp[] PROGMEM = {
318
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
319
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
320
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
321
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0xF8, 0x20,
322
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0xF0, 0x20,
323
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x60, 0x20,
324
+      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x58, 0x01, 0xA0,
325
+      0x7F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5C, 0x63, 0xA0,
326
+      0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5E, 0xF7, 0xA0,
327
+      0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5E, 0xF7, 0xA0,
328
+      0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5C, 0x63, 0xA0,
329
+      0x7F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x58, 0x01, 0xA0,
330
+      0x7F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x60, 0x20,
331
+      0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0xF0, 0x20,
332
+      0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0xF8, 0x20,
333
+      0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
334
+      0x3F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
335
+      0x1E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
336
+      0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
337
+    };
338
+  #elif HOTENDS == 1
339
+    const unsigned char status_screen0_bmp[] PROGMEM = {
276 340
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
277 341
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
278 342
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
@@ -294,10 +358,7 @@
294 358
       0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
295 359
     };
296 360
 
297
-    #define STATUS_SCREENWIDTH     115 //Width in pixels
298
-    #define STATUS_SCREENHEIGHT     19 //Height in pixels
299
-    #define STATUS_SCREENBYTEWIDTH  15 //Width in bytes
300
-    const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
361
+    const unsigned char status_screen1_bmp[] PROGMEM = {
301 362
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
302 363
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
303 364
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
@@ -319,10 +380,7 @@
319 380
       0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
320 381
     };
321 382
   #elif HOTENDS == 2
322
-    #define STATUS_SCREENWIDTH     115 //Width in pixels
323
-    #define STATUS_SCREENHEIGHT     19 //Height in pixels
324
-    #define STATUS_SCREENBYTEWIDTH  15 //Width in bytes
325
-    const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
383
+    const unsigned char status_screen0_bmp[] PROGMEM = {
326 384
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
327 385
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
328 386
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
@@ -344,10 +402,7 @@
344 402
       0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
345 403
     };
346 404
 
347
-    #define STATUS_SCREENWIDTH     115 //Width in pixels
348
-    #define STATUS_SCREENHEIGHT     19 //Height in pixels
349
-    #define STATUS_SCREENBYTEWIDTH  15 //Width in bytes
350
-    const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
405
+    const unsigned char status_screen1_bmp[] PROGMEM = {
351 406
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
352 407
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
353 408
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
@@ -369,10 +424,7 @@
369 424
       0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
370 425
     };
371 426
   #else
372
-    #define STATUS_SCREENWIDTH     115 //Width in pixels
373
-    #define STATUS_SCREENHEIGHT     19 //Height in pixels
374
-    #define STATUS_SCREENBYTEWIDTH  15 //Width in bytes
375
-    const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
427
+    const unsigned char status_screen0_bmp[] PROGMEM = {
376 428
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
377 429
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
378 430
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
@@ -394,10 +446,7 @@
394 446
       0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
395 447
     };
396 448
 
397
-    #define STATUS_SCREENWIDTH     115 //Width in pixels
398
-    #define STATUS_SCREENHEIGHT     19 //Height in pixels
399
-    #define STATUS_SCREENBYTEWIDTH  15 //Width in bytes
400
-    const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
449
+    const unsigned char status_screen1_bmp[] PROGMEM = {
401 450
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
402 451
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
403 452
       0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
@@ -418,5 +467,97 @@
418 467
       0x1E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
419 468
       0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
420 469
     };
421
-  #endif // Extruders
470
+  #endif // HOTENDS
422 471
 #endif // HAS_TEMP_BED
472
+
473
+#if ENABLED(BABYSTEP_ZPROBE_GFX_OVERLAY) || ENABLED(MESH_EDIT_GFX_OVERLAY)
474
+
475
+  const unsigned char cw_bmp[] PROGMEM = {
476
+    0x03,0xF8,0x00, // 000000111111100000000000
477
+    0x0F,0xF7,0x00, // 000011111111111000000000
478
+    0x17,0x0F,0x00, // 000111100000111100000000
479
+    0x38,0x07,0x00, // 001110000000011100000000
480
+    0x38,0x03,0x80, // 001110000000001110000000
481
+    0x70,0x03,0x80, // 011100000000001110000000
482
+    0x70,0x0F,0xE0, // 011100000000111111100000
483
+    0x70,0x07,0xC0, // 011100000000011111000000
484
+    0x70,0x03,0x80, // 011100000000001110000000
485
+    0x70,0x01,0x00, // 011100000000000100000000
486
+    0x70,0x00,0x00, // 011100000000000000000000
487
+    0x68,0x00,0x00, // 001110000000000000000000
488
+    0x38,0x07,0x00, // 001110000000011100000000
489
+    0x17,0x0F,0x00, // 000111100000111100000000
490
+    0x0F,0xFE,0x00, // 000011111111111000000000
491
+    0x03,0xF8,0x00  // 000000111111100000000000
492
+  };
493
+
494
+  const unsigned char ccw_bmp[] PROGMEM = {
495
+    0x00,0xFE,0x00, // 000000001111111000000000
496
+    0x03,0xFF,0x80, // 000000111111111110000000
497
+    0x07,0x83,0xC0, // 000001111000001111000000
498
+    0x0E,0x01,0xC0, // 000011100000000111000000
499
+    0x0E,0x00,0xE0, // 000011100000000011100000
500
+    0x1C,0x00,0xE0, // 000111000000000011100000
501
+    0x7F,0x00,0xE0, // 011111110000000011100000
502
+    0x3E,0x00,0xE0, // 001111100000000011100000
503
+    0x1C,0x00,0xE0, // 000111000000000011100000
504
+    0x08,0x00,0xE0, // 000010000000000011100000
505
+    0x00,0x00,0xE0, // 000000000000000011100000
506
+    0x00,0x01,0xC0, // 000000000000000111000000
507
+    0x0E,0x01,0xC0, // 000011100000000111000000
508
+    0x0F,0x07,0x80, // 000011110000011110000000
509
+    0x07,0xFF,0x00, // 000001111111111100000000
510
+    0x01,0xFC,0x00  // 000000011111110000000000
511
+  };
512
+
513
+  const unsigned char up_arrow_bmp[] PROGMEM = {
514
+    0x04,0x00, // 000001000000
515
+    0x0E,0x00, // 000011100000
516
+    0x1F,0x00, // 000111110000
517
+    0x3F,0x80, // 001111111000
518
+    0x7F,0xC0, // 011111111100
519
+    0x0E,0x00, // 000011100000
520
+    0x0E,0x00, // 000011100000
521
+    0x0E,0x00, // 000011100000
522
+    0x0E,0x00, // 000011100000
523
+    0x0E,0x00, // 000011100000
524
+    0x0E,0x00, // 000011100000
525
+    0x0E,0x00, // 000011100000
526
+    0x0E,0x00  // 000011100000
527
+  };
528
+
529
+  const unsigned char down_arrow_bmp[] PROGMEM = {
530
+    0x0E,0x00, // 000011100000
531
+    0x0E,0x00, // 000011100000
532
+    0x0E,0x00, // 000011100000
533
+    0x0E,0x00, // 000011100000
534
+    0x0E,0x00, // 000011100000
535
+    0x0E,0x00, // 000011100000
536
+    0x0E,0x00, // 000011100000
537
+    0x0E,0x00, // 000011100000
538
+    0x7F,0xC0, // 011111111100
539
+    0x3F,0x80, // 001111111000
540
+    0x1F,0x00, // 000111110000
541
+    0x0E,0x00, // 000011100000
542
+    0x04,0x00  // 000001000000
543
+  };
544
+
545
+  const unsigned char offset_bedline_bmp[] PROGMEM = {
546
+    0xFF,0xFF,0xFF // 111111111111111111111111
547
+  };
548
+
549
+  const unsigned char nozzle_bmp[] PROGMEM = {
550
+    0x7F,0x80, // 0111111110000000
551
+    0xFF,0xC0, // 1111111111000000
552
+    0xFF,0xC0, // 1111111111000000
553
+    0xFF,0xC0, // 1111111111000000
554
+    0x7F,0x80, // 0111111110000000
555
+    0x7F,0x80, // 0111111110000000
556
+    0xFF,0xC0, // 1111111111000000
557
+    0xFF,0xC0, // 1111111111000000
558
+    0xFF,0xC0, // 1111111111000000
559
+    0x3F,0x00, // 0011111100000000
560
+    0x1E,0x00, // 0001111000000000
561
+    0x0C,0x00  // 0000110000000000
562
+  };
563
+#endif // BABYSTEP_ZPROBE_GFX_OVERLAY || MESH_EDIT_GFX_OVERLAY

+ 252
- 164
Marlin/dogm_font_data_ISO10646_1.h 파일 보기

@@ -32,167 +32,255 @@
32 32
   Max Font    ascent = 8 descent=-1
33 33
 */
34 34
 #include <U8glib.h>
35
-const u8g_fntpgm_uint8_t ISO10646_1_5x7[2592] U8G_SECTION(".progmem.ISO10646_1_5x7") = {
36
-  0, 6, 9, 0, 254, 7, 1, 146, 3, 33, 32, 255, 255, 8, 255, 7,
37
-  255, 0, 0, 0, 6, 0, 0, 1, 7, 7, 6, 2, 0, 128, 128, 128,
38
-  128, 128, 0, 128, 3, 2, 2, 6, 1, 5, 160, 160, 5, 7, 7, 6,
39
-  0, 0, 80, 80, 248, 80, 248, 80, 80, 5, 7, 7, 6, 0, 0, 32,
40
-  120, 160, 112, 40, 240, 32, 5, 7, 7, 6, 0, 0, 192, 200, 16, 32,
41
-  64, 152, 24, 5, 7, 7, 6, 0, 0, 96, 144, 160, 64, 168, 144, 104,
42
-  2, 3, 3, 6, 1, 4, 192, 64, 128, 3, 7, 7, 6, 1, 0, 32,
43
-  64, 128, 128, 128, 64, 32, 3, 7, 7, 6, 1, 0, 128, 64, 32, 32,
44
-  32, 64, 128, 5, 5, 5, 6, 0, 1, 32, 168, 112, 168, 32, 5, 5,
45
-  5, 6, 0, 1, 32, 32, 248, 32, 32, 2, 3, 3, 6, 2, 255, 192,
46
-  64, 128, 5, 1, 1, 6, 0, 3, 248, 2, 2, 2, 6, 2, 0, 192,
47
-  192, 5, 5, 5, 6, 0, 1, 8, 16, 32, 64, 128, 5, 7, 7, 6,
48
-  0, 0, 112, 136, 136, 136, 136, 136, 112, 3, 7, 7, 6, 1, 0, 64,
49
-  192, 64, 64, 64, 64, 224, 5, 7, 7, 6, 0, 0, 112, 136, 8, 112,
50
-  128, 128, 248, 5, 7, 7, 6, 0, 0, 248, 16, 32, 16, 8, 8, 240,
51
-  5, 7, 7, 6, 0, 0, 16, 48, 80, 144, 248, 16, 16, 5, 7, 7,
52
-  6, 0, 0, 248, 128, 240, 8, 8, 136, 112, 5, 7, 7, 6, 0, 0,
53
-  112, 128, 128, 240, 136, 136, 112, 5, 7, 7, 6, 0, 0, 248, 8, 16,
54
-  32, 32, 32, 32, 5, 7, 7, 6, 0, 0, 112, 136, 136, 112, 136, 136,
55
-  112, 5, 7, 7, 6, 0, 0, 112, 136, 136, 120, 8, 8, 112, 2, 5,
56
-  5, 6, 2, 0, 192, 192, 0, 192, 192, 2, 6, 6, 6, 2, 255, 192,
57
-  192, 0, 192, 64, 128, 4, 7, 7, 6, 0, 0, 16, 32, 64, 128, 64,
58
-  32, 16, 5, 3, 3, 6, 0, 2, 248, 0, 248, 4, 7, 7, 6, 1,
59
-  0, 128, 64, 32, 16, 32, 64, 128, 5, 7, 7, 6, 0, 0, 112, 136,
60
-  8, 16, 32, 0, 32, 5, 7, 7, 6, 0, 0, 112, 136, 8, 104, 168,
61
-  168, 112, 5, 7, 7, 6, 0, 0, 112, 136, 136, 248, 136, 136, 136, 5,
62
-  7, 7, 6, 0, 0, 240, 136, 136, 240, 136, 136, 240, 5, 7, 7, 6,
63
-  0, 0, 112, 136, 128, 128, 128, 136, 112, 5, 7, 7, 6, 0, 0, 240,
64
-  136, 136, 136, 136, 136, 240, 5, 7, 7, 6, 0, 0, 248, 128, 128, 240,
65
-  128, 128, 248, 5, 7, 7, 6, 0, 0, 248, 128, 128, 240, 128, 128, 128,
66
-  5, 7, 7, 6, 0, 0, 112, 136, 128, 184, 136, 136, 112, 5, 7, 7,
67
-  6, 0, 0, 136, 136, 136, 248, 136, 136, 136, 1, 7, 7, 6, 2, 0,
68
-  128, 128, 128, 128, 128, 128, 128, 5, 7, 7, 6, 0, 0, 56, 16, 16,
69
-  16, 16, 144, 96, 5, 7, 7, 6, 0, 0, 136, 144, 160, 192, 160, 144,
70
-  136, 5, 7, 7, 6, 0, 0, 128, 128, 128, 128, 128, 128, 248, 5, 7,
71
-  7, 6, 0, 0, 136, 216, 168, 136, 136, 136, 136, 5, 7, 7, 6, 0,
72
-  0, 136, 136, 200, 168, 152, 136, 136, 5, 7, 7, 6, 0, 0, 112, 136,
73
-  136, 136, 136, 136, 112, 5, 7, 7, 6, 0, 0, 240, 136, 136, 240, 128,
74
-  128, 128, 5, 7, 7, 6, 0, 0, 112, 136, 136, 136, 168, 144, 104, 5,
75
-  7, 7, 6, 0, 0, 240, 136, 136, 240, 160, 144, 136, 5, 7, 7, 6,
76
-  0, 0, 120, 128, 128, 112, 8, 8, 240, 5, 7, 7, 6, 0, 0, 248,
77
-  32, 32, 32, 32, 32, 32, 5, 7, 7, 6, 0, 0, 136, 136, 136, 136,
78
-  136, 136, 112, 5, 7, 7, 6, 0, 0, 136, 136, 136, 136, 136, 80, 32,
79
-  5, 7, 7, 6, 0, 0, 136, 136, 136, 136, 136, 168, 80, 5, 7, 7,
80
-  6, 0, 0, 136, 136, 80, 32, 80, 136, 136, 5, 7, 7, 6, 0, 0,
81
-  136, 136, 136, 80, 32, 32, 32, 5, 7, 7, 6, 0, 0, 248, 8, 16,
82
-  32, 64, 128, 248, 3, 7, 7, 6, 1, 0, 224, 128, 128, 128, 128, 128,
83
-  224, 5, 5, 5, 6, 0, 1, 128, 64, 32, 16, 8, 3, 7, 7, 6,
84
-  1, 0, 224, 32, 32, 32, 32, 32, 224, 5, 3, 3, 6, 0, 4, 32,
85
-  80, 136, 5, 1, 1, 6, 0, 0, 248, 2, 2, 2, 6, 2, 5, 128,
86
-  64, 5, 5, 5, 6, 0, 0, 112, 8, 120, 136, 120, 5, 7, 7, 6,
87
-  0, 0, 128, 128, 176, 200, 136, 136, 240, 5, 5, 5, 6, 0, 0, 112,
88
-  128, 128, 136, 112, 5, 7, 7, 6, 0, 0, 8, 8, 104, 152, 136, 136,
89
-  120, 5, 5, 5, 6, 0, 0, 112, 136, 248, 128, 112, 5, 7, 7, 6,
90
-  0, 0, 48, 72, 224, 64, 64, 64, 64, 5, 6, 6, 6, 0, 255, 112,
91
-  136, 136, 120, 8, 112, 5, 7, 7, 6, 0, 0, 128, 128, 176, 200, 136,
92
-  136, 136, 1, 7, 7, 6, 2, 0, 128, 0, 128, 128, 128, 128, 128, 3,
93
-  8, 8, 6, 1, 255, 32, 0, 32, 32, 32, 32, 160, 64, 4, 7, 7,
94
-  6, 0, 0, 128, 128, 144, 160, 192, 160, 144, 3, 7, 7, 6, 1, 0,
95
-  192, 64, 64, 64, 64, 64, 224, 5, 5, 5, 6, 0, 0, 208, 168, 168,
96
-  168, 168, 5, 5, 5, 6, 0, 0, 176, 200, 136, 136, 136, 5, 5, 5,
97
-  6, 0, 0, 112, 136, 136, 136, 112, 5, 6, 6, 6, 0, 255, 240, 136,
98
-  136, 240, 128, 128, 5, 6, 6, 6, 0, 255, 120, 136, 136, 120, 8, 8,
99
-  5, 5, 5, 6, 0, 0, 176, 200, 128, 128, 128, 5, 5, 5, 6, 0,
100
-  0, 112, 128, 112, 8, 240, 4, 7, 7, 6, 0, 0, 64, 64, 224, 64,
101
-  64, 64, 48, 5, 5, 5, 6, 0, 0, 136, 136, 136, 152, 104, 5, 5,
102
-  5, 6, 0, 0, 136, 136, 136, 80, 32, 5, 5, 5, 6, 0, 0, 136,
103
-  136, 168, 168, 80, 5, 5, 5, 6, 0, 0, 136, 80, 32, 80, 136, 5,
104
-  6, 6, 6, 0, 255, 136, 136, 136, 120, 8, 112, 5, 5, 5, 6, 0,
105
-  0, 248, 16, 32, 64, 248, 3, 7, 7, 6, 1, 0, 32, 64, 64, 128,
106
-  64, 64, 32, 1, 7, 7, 6, 2, 0, 128, 128, 128, 128, 128, 128, 128,
107
-  3, 7, 7, 6, 1, 0, 128, 64, 64, 32, 64, 64, 128, 5, 2, 2,
108
-  6, 0, 2, 104, 144, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0,
109
-  0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0,
110
-  6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0,
111
-  0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0,
112
-  0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0,
113
-  6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0,
114
-  0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0,
115
-  0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0,
116
-  6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0,
117
-  0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0,
118
-  0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0,
119
-  6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0,
120
-  0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0,
121
-  0, 1, 7, 7, 6, 2, 0, 128, 0, 128, 128, 128, 128, 128, 5, 7,
122
-  7, 6, 0, 0, 32, 112, 168, 160, 168, 112, 32, 5, 7, 7, 6, 0,
123
-  0, 48, 64, 64, 224, 64, 80, 168, 5, 5, 5, 6, 0, 0, 136, 112,
124
-  80, 112, 136, 5, 7, 7, 6, 0, 0, 136, 80, 32, 248, 32, 248, 32,
125
-  1, 7, 7, 6, 2, 0, 128, 128, 128, 0, 128, 128, 128, 5, 8, 8,
126
-  6, 0, 0, 48, 72, 32, 80, 80, 32, 144, 96, 3, 1, 1, 6, 1,
127
-  7, 160, 5, 7, 7, 6, 0, 0, 248, 136, 184, 184, 184, 136, 248, 5,
128
-  7, 7, 6, 0, 1, 112, 8, 120, 136, 120, 0, 248, 5, 5, 5, 6,
129
-  0, 1, 40, 80, 160, 80, 40, 5, 3, 3, 6, 0, 1, 248, 8, 8,
130
-  2, 2, 2, 6, 2, 6, 64, 128, 5, 7, 7, 6, 0, 0, 248, 136,
131
-  168, 136, 152, 168, 248, 5, 1, 1, 6, 0, 6, 248, 4, 4, 4, 6,
132
-  0, 3, 96, 144, 144, 96, 5, 7, 7, 6, 0, 0, 32, 32, 248, 32,
133
-  32, 0, 248, 4, 5, 5, 6, 0, 3, 96, 144, 32, 64, 240, 3, 5,
134
-  5, 6, 0, 3, 224, 32, 224, 32, 224, 2, 2, 2, 6, 2, 6, 64,
135
-  128, 5, 8, 8, 6, 0, 255, 136, 136, 136, 136, 152, 232, 128, 128, 5,
136
-  7, 7, 6, 0, 0, 120, 152, 152, 120, 24, 24, 24, 2, 2, 2, 6,
137
-  2, 2, 192, 192, 2, 2, 2, 6, 2, 255, 64, 128, 3, 5, 5, 6,
138
-  0, 3, 64, 192, 64, 64, 224, 5, 7, 7, 6, 0, 1, 112, 136, 136,
139
-  136, 112, 0, 248, 5, 5, 5, 6, 0, 1, 160, 80, 40, 80, 160, 5,
140
-  7, 7, 6, 0, 0, 136, 144, 168, 88, 184, 8, 8, 5, 7, 7, 6,
141
-  0, 0, 136, 144, 184, 72, 152, 32, 56, 5, 8, 8, 6, 0, 0, 192,
142
-  64, 192, 72, 216, 56, 8, 8, 5, 7, 7, 6, 0, 0, 32, 0, 32,
143
-  64, 128, 136, 112, 5, 8, 8, 6, 0, 0, 64, 32, 0, 112, 136, 248,
144
-  136, 136, 5, 8, 8, 6, 0, 0, 16, 32, 0, 112, 136, 248, 136, 136,
145
-  5, 8, 8, 6, 0, 0, 32, 80, 0, 112, 136, 248, 136, 136, 5, 8,
146
-  8, 6, 0, 0, 104, 144, 0, 112, 136, 248, 136, 136, 5, 8, 8, 6,
147
-  0, 0, 80, 0, 112, 136, 136, 248, 136, 136, 5, 8, 8, 6, 0, 0,
148
-  32, 80, 32, 112, 136, 248, 136, 136, 5, 7, 7, 6, 0, 0, 56, 96,
149
-  160, 184, 224, 160, 184, 5, 8, 8, 6, 0, 255, 112, 136, 128, 128, 136,
150
-  112, 32, 96, 5, 8, 8, 6, 0, 0, 64, 32, 0, 248, 128, 240, 128,
151
-  248, 5, 8, 8, 6, 0, 0, 8, 16, 0, 248, 128, 240, 128, 248, 5,
152
-  8, 8, 6, 0, 0, 32, 80, 0, 248, 128, 240, 128, 248, 5, 7, 7,
153
-  6, 0, 0, 80, 0, 248, 128, 240, 128, 248, 3, 8, 8, 6, 1, 0,
154
-  128, 64, 0, 224, 64, 64, 64, 224, 3, 8, 8, 6, 1, 0, 32, 64,
155
-  0, 224, 64, 64, 64, 224, 3, 8, 8, 6, 1, 0, 64, 160, 0, 224,
156
-  64, 64, 64, 224, 3, 7, 7, 6, 1, 0, 160, 0, 224, 64, 64, 64,
157
-  224, 5, 7, 7, 6, 0, 0, 112, 72, 72, 232, 72, 72, 112, 5, 8,
158
-  8, 6, 0, 0, 104, 144, 0, 136, 200, 168, 152, 136, 5, 8, 8, 6,
159
-  0, 0, 64, 32, 112, 136, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0,
160
-  16, 32, 112, 136, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 32, 80,
161
-  0, 112, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 104, 144, 0, 112,
162
-  136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 80, 0, 112, 136, 136, 136,
163
-  136, 112, 5, 5, 5, 6, 0, 1, 136, 80, 32, 80, 136, 5, 8, 8,
164
-  6, 0, 255, 16, 112, 168, 168, 168, 168, 112, 64, 5, 8, 8, 6, 0,
165
-  0, 64, 32, 136, 136, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 16,
166
-  32, 136, 136, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 32, 80, 0,
167
-  136, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 80, 0, 136, 136, 136,
168
-  136, 136, 112, 5, 8, 8, 6, 0, 0, 16, 32, 136, 80, 32, 32, 32,
169
-  32, 5, 9, 9, 6, 0, 255, 192, 64, 112, 72, 72, 112, 64, 64, 224,
170
-  4, 8, 8, 6, 1, 255, 96, 144, 144, 160, 144, 144, 224, 128, 5, 8,
171
-  8, 6, 0, 0, 64, 32, 0, 112, 8, 120, 136, 120, 5, 8, 8, 6,
172
-  0, 0, 16, 32, 0, 112, 8, 120, 136, 120, 5, 8, 8, 6, 0, 0,
173
-  32, 80, 0, 112, 8, 120, 136, 120, 5, 8, 8, 6, 0, 0, 104, 144,
174
-  0, 112, 8, 120, 136, 120, 5, 7, 7, 6, 0, 0, 80, 0, 112, 8,
175
-  120, 136, 120, 5, 8, 8, 6, 0, 0, 32, 80, 32, 112, 8, 120, 136,
176
-  120, 5, 6, 6, 6, 0, 0, 208, 40, 120, 160, 168, 80, 5, 6, 6,
177
-  6, 0, 255, 112, 128, 136, 112, 32, 96, 5, 8, 8, 6, 0, 0, 64,
178
-  32, 0, 112, 136, 248, 128, 112, 5, 8, 8, 6, 0, 0, 16, 32, 0,
179
-  112, 136, 248, 128, 112, 5, 8, 8, 6, 0, 0, 32, 80, 0, 112, 136,
180
-  248, 128, 112, 5, 7, 7, 6, 0, 0, 80, 0, 112, 136, 248, 128, 112,
181
-  3, 8, 8, 6, 1, 0, 128, 64, 0, 64, 192, 64, 64, 224, 3, 8,
182
-  8, 6, 1, 0, 32, 64, 0, 64, 192, 64, 64, 224, 3, 8, 8, 6,
183
-  1, 0, 64, 160, 0, 64, 192, 64, 64, 224, 3, 7, 7, 6, 1, 0,
184
-  160, 0, 64, 192, 64, 64, 224, 5, 7, 7, 6, 0, 0, 160, 64, 160,
185
-  16, 120, 136, 112, 5, 8, 8, 6, 0, 0, 104, 144, 0, 176, 200, 136,
186
-  136, 136, 5, 8, 8, 6, 0, 0, 64, 32, 0, 112, 136, 136, 136, 112,
187
-  5, 8, 8, 6, 0, 0, 16, 32, 0, 112, 136, 136, 136, 112, 5, 8,
188
-  8, 6, 0, 0, 32, 80, 0, 112, 136, 136, 136, 112, 5, 8, 8, 6,
189
-  0, 0, 104, 144, 0, 112, 136, 136, 136, 112, 5, 7, 7, 6, 0, 0,
190
-  80, 0, 112, 136, 136, 136, 112, 5, 5, 5, 6, 0, 1, 32, 0, 248,
191
-  0, 32, 5, 7, 7, 6, 0, 255, 16, 112, 168, 168, 168, 112, 64, 5,
192
-  8, 8, 6, 0, 0, 64, 32, 0, 136, 136, 136, 152, 104, 5, 8, 8,
193
-  6, 0, 0, 16, 32, 0, 136, 136, 136, 152, 104, 5, 8, 8, 6, 0,
194
-  0, 32, 80, 0, 136, 136, 136, 152, 104, 5, 7, 7, 6, 0, 0, 80,
195
-  0, 136, 136, 136, 152, 104, 5, 9, 9, 6, 0, 255, 16, 32, 0, 136,
196
-  136, 136, 248, 8, 112, 4, 7, 7, 6, 1, 255, 192, 64, 96, 80, 96,
197
-  64, 224, 5, 8, 8, 6, 0, 255, 80, 0, 136, 136, 136, 120, 8, 112
198
-};
35
+
36
+#if defined(__AVR__) && ENABLED(NOT_EXTENDED_ISO10646_1_5X7)
37
+
38
+  //
39
+  // Reduced font (only symbols 32 - 127) - About 1400 bytes smaller
40
+  //
41
+  const u8g_fntpgm_uint8_t ISO10646_1_5x7[] U8G_SECTION(".progmem.ISO10646_1_5x7") = {
42
+    0,6,9,0,254,7,1,146,3,33,32,127,255,7,255,7,
43
+    255,0,0,0,6,0,0,1,7,7,6,2,0,128,128,128,
44
+    128,128,0,128,3,2,2,6,1,5,160,160,5,7,7,6,
45
+    0,0,80,80,248,80,248,80,80,5,7,7,6,0,0,32,
46
+    120,160,112,40,240,32,5,7,7,6,0,0,192,200,16,32,
47
+    64,152,24,5,7,7,6,0,0,96,144,160,64,168,144,104,
48
+    2,3,3,6,1,4,192,64,128,3,7,7,6,1,0,32,
49
+    64,128,128,128,64,32,3,7,7,6,1,0,128,64,32,32,
50
+    32,64,128,5,5,5,6,0,1,32,168,112,168,32,5,5,
51
+    5,6,0,1,32,32,248,32,32,2,3,3,6,2,255,192,
52
+    64,128,5,1,1,6,0,3,248,2,2,2,6,2,0,192,
53
+    192,5,5,5,6,0,1,8,16,32,64,128,5,7,7,6,
54
+    0,0,112,136,136,136,136,136,112,3,7,7,6,1,0,64,
55
+    192,64,64,64,64,224,5,7,7,6,0,0,112,136,8,112,
56
+    128,128,248,5,7,7,6,0,0,248,16,32,16,8,8,240,
57
+    5,7,7,6,0,0,16,48,80,144,248,16,16,5,7,7,
58
+    6,0,0,248,128,240,8,8,136,112,5,7,7,6,0,0,
59
+    112,128,128,240,136,136,112,5,7,7,6,0,0,248,8,16,
60
+    32,32,32,32,5,7,7,6,0,0,112,136,136,112,136,136,
61
+    112,5,7,7,6,0,0,112,136,136,120,8,8,112,2,5,
62
+    5,6,2,0,192,192,0,192,192,2,6,6,6,2,255,192,
63
+    192,0,192,64,128,4,7,7,6,0,0,16,32,64,128,64,
64
+    32,16,5,3,3,6,0,2,248,0,248,4,7,7,6,1,
65
+    0,128,64,32,16,32,64,128,5,7,7,6,0,0,112,136,
66
+    8,16,32,0,32,5,7,7,6,0,0,112,136,8,104,168,
67
+    168,112,5,7,7,6,0,0,112,136,136,248,136,136,136,5,
68
+    7,7,6,0,0,240,136,136,240,136,136,240,5,7,7,6,
69
+    0,0,112,136,128,128,128,136,112,5,7,7,6,0,0,240,
70
+    136,136,136,136,136,240,5,7,7,6,0,0,248,128,128,240,
71
+    128,128,248,5,7,7,6,0,0,248,128,128,240,128,128,128,
72
+    5,7,7,6,0,0,112,136,128,184,136,136,112,5,7,7,
73
+    6,0,0,136,136,136,248,136,136,136,1,7,7,6,2,0,
74
+    128,128,128,128,128,128,128,5,7,7,6,0,0,56,16,16,
75
+    16,16,144,96,5,7,7,6,0,0,136,144,160,192,160,144,
76
+    136,5,7,7,6,0,0,128,128,128,128,128,128,248,5,7,
77
+    7,6,0,0,136,216,168,136,136,136,136,5,7,7,6,0,
78
+    0,136,136,200,168,152,136,136,5,7,7,6,0,0,112,136,
79
+    136,136,136,136,112,5,7,7,6,0,0,240,136,136,240,128,
80
+    128,128,5,7,7,6,0,0,112,136,136,136,168,144,104,5,
81
+    7,7,6,0,0,240,136,136,240,160,144,136,5,7,7,6,
82
+    0,0,120,128,128,112,8,8,240,5,7,7,6,0,0,248,
83
+    32,32,32,32,32,32,5,7,7,6,0,0,136,136,136,136,
84
+    136,136,112,5,7,7,6,0,0,136,136,136,136,136,80,32,
85
+    5,7,7,6,0,0,136,136,136,136,136,168,80,5,7,7,
86
+    6,0,0,136,136,80,32,80,136,136,5,7,7,6,0,0,
87
+    136,136,136,80,32,32,32,5,7,7,6,0,0,248,8,16,
88
+    32,64,128,248,3,7,7,6,1,0,224,128,128,128,128,128,
89
+    224,5,5,5,6,0,1,128,64,32,16,8,3,7,7,6,
90
+    1,0,224,32,32,32,32,32,224,5,3,3,6,0,4,32,
91
+    80,136,5,1,1,6,0,0,248,2,2,2,6,2,5,128,
92
+    64,5,5,5,6,0,0,112,8,120,136,120,5,7,7,6,
93
+    0,0,128,128,176,200,136,136,240,5,5,5,6,0,0,112,
94
+    128,128,136,112,5,7,7,6,0,0,8,8,104,152,136,136,
95
+    120,5,5,5,6,0,0,112,136,248,128,112,5,7,7,6,
96
+    0,0,48,72,224,64,64,64,64,5,6,6,6,0,255,112,
97
+    136,136,120,8,112,5,7,7,6,0,0,128,128,176,200,136,
98
+    136,136,1,7,7,6,2,0,128,0,128,128,128,128,128,3,
99
+    8,8,6,1,255,32,0,32,32,32,32,160,64,4,7,7,
100
+    6,0,0,128,128,144,160,192,160,144,3,7,7,6,1,0,
101
+    192,64,64,64,64,64,224,5,5,5,6,0,0,208,168,168,
102
+    168,168,5,5,5,6,0,0,176,200,136,136,136,5,5,5,
103
+    6,0,0,112,136,136,136,112,5,6,6,6,0,255,240,136,
104
+    136,240,128,128,5,6,6,6,0,255,120,136,136,120,8,8,
105
+    5,5,5,6,0,0,176,200,128,128,128,5,5,5,6,0,
106
+    0,112,128,112,8,240,4,7,7,6,0,0,64,64,224,64,
107
+    64,64,48,5,5,5,6,0,0,136,136,136,152,104,5,5,
108
+    5,6,0,0,136,136,136,80,32,5,5,5,6,0,0,136,
109
+    136,168,168,80,5,5,5,6,0,0,136,80,32,80,136,5,
110
+    6,6,6,0,255,136,136,136,120,8,112,5,5,5,6,0,
111
+    0,248,16,32,64,248,3,7,7,6,1,0,32,64,64,128,
112
+    64,64,32,1,7,7,6,2,0,128,128,128,128,128,128,128,
113
+    3,7,7,6,1,0,128,64,64,32,64,64,128,5,2,2,
114
+    6,0,2,104,144,0,0,0,6,0,0};
115
+
116
+#else
117
+
118
+  //
119
+  // Extended (original) font (symbols 32 - 255)
120
+  //
121
+  const u8g_fntpgm_uint8_t ISO10646_1_5x7[] U8G_SECTION(".progmem.ISO10646_1_5x7") = {
122
+    0, 6, 9, 0, 254, 7, 1, 146, 3, 33, 32, 255, 255, 8, 255, 7,
123
+    255, 0, 0, 0, 6, 0, 0, 1, 7, 7, 6, 2, 0, 128, 128, 128,
124
+    128, 128, 0, 128, 3, 2, 2, 6, 1, 5, 160, 160, 5, 7, 7, 6,
125
+    0, 0, 80, 80, 248, 80, 248, 80, 80, 5, 7, 7, 6, 0, 0, 32,
126
+    120, 160, 112, 40, 240, 32, 5, 7, 7, 6, 0, 0, 192, 200, 16, 32,
127
+    64, 152, 24, 5, 7, 7, 6, 0, 0, 96, 144, 160, 64, 168, 144, 104,
128
+    2, 3, 3, 6, 1, 4, 192, 64, 128, 3, 7, 7, 6, 1, 0, 32,
129
+    64, 128, 128, 128, 64, 32, 3, 7, 7, 6, 1, 0, 128, 64, 32, 32,
130
+    32, 64, 128, 5, 5, 5, 6, 0, 1, 32, 168, 112, 168, 32, 5, 5,
131
+    5, 6, 0, 1, 32, 32, 248, 32, 32, 2, 3, 3, 6, 2, 255, 192,
132
+    64, 128, 5, 1, 1, 6, 0, 3, 248, 2, 2, 2, 6, 2, 0, 192,
133
+    192, 5, 5, 5, 6, 0, 1, 8, 16, 32, 64, 128, 5, 7, 7, 6,
134
+    0, 0, 112, 136, 136, 136, 136, 136, 112, 3, 7, 7, 6, 1, 0, 64,
135
+    192, 64, 64, 64, 64, 224, 5, 7, 7, 6, 0, 0, 112, 136, 8, 112,
136
+    128, 128, 248, 5, 7, 7, 6, 0, 0, 248, 16, 32, 16, 8, 8, 240,
137
+    5, 7, 7, 6, 0, 0, 16, 48, 80, 144, 248, 16, 16, 5, 7, 7,
138
+    6, 0, 0, 248, 128, 240, 8, 8, 136, 112, 5, 7, 7, 6, 0, 0,
139
+    112, 128, 128, 240, 136, 136, 112, 5, 7, 7, 6, 0, 0, 248, 8, 16,
140
+    32, 32, 32, 32, 5, 7, 7, 6, 0, 0, 112, 136, 136, 112, 136, 136,
141
+    112, 5, 7, 7, 6, 0, 0, 112, 136, 136, 120, 8, 8, 112, 2, 5,
142
+    5, 6, 2, 0, 192, 192, 0, 192, 192, 2, 6, 6, 6, 2, 255, 192,
143
+    192, 0, 192, 64, 128, 4, 7, 7, 6, 0, 0, 16, 32, 64, 128, 64,
144
+    32, 16, 5, 3, 3, 6, 0, 2, 248, 0, 248, 4, 7, 7, 6, 1,
145
+    0, 128, 64, 32, 16, 32, 64, 128, 5, 7, 7, 6, 0, 0, 112, 136,
146
+    8, 16, 32, 0, 32, 5, 7, 7, 6, 0, 0, 112, 136, 8, 104, 168,
147
+    168, 112, 5, 7, 7, 6, 0, 0, 112, 136, 136, 248, 136, 136, 136, 5,
148
+    7, 7, 6, 0, 0, 240, 136, 136, 240, 136, 136, 240, 5, 7, 7, 6,
149
+    0, 0, 112, 136, 128, 128, 128, 136, 112, 5, 7, 7, 6, 0, 0, 240,
150
+    136, 136, 136, 136, 136, 240, 5, 7, 7, 6, 0, 0, 248, 128, 128, 240,
151
+    128, 128, 248, 5, 7, 7, 6, 0, 0, 248, 128, 128, 240, 128, 128, 128,
152
+    5, 7, 7, 6, 0, 0, 112, 136, 128, 184, 136, 136, 112, 5, 7, 7,
153
+    6, 0, 0, 136, 136, 136, 248, 136, 136, 136, 1, 7, 7, 6, 2, 0,
154
+    128, 128, 128, 128, 128, 128, 128, 5, 7, 7, 6, 0, 0, 56, 16, 16,
155
+    16, 16, 144, 96, 5, 7, 7, 6, 0, 0, 136, 144, 160, 192, 160, 144,
156
+    136, 5, 7, 7, 6, 0, 0, 128, 128, 128, 128, 128, 128, 248, 5, 7,
157
+    7, 6, 0, 0, 136, 216, 168, 136, 136, 136, 136, 5, 7, 7, 6, 0,
158
+    0, 136, 136, 200, 168, 152, 136, 136, 5, 7, 7, 6, 0, 0, 112, 136,
159
+    136, 136, 136, 136, 112, 5, 7, 7, 6, 0, 0, 240, 136, 136, 240, 128,
160
+    128, 128, 5, 7, 7, 6, 0, 0, 112, 136, 136, 136, 168, 144, 104, 5,
161
+    7, 7, 6, 0, 0, 240, 136, 136, 240, 160, 144, 136, 5, 7, 7, 6,
162
+    0, 0, 120, 128, 128, 112, 8, 8, 240, 5, 7, 7, 6, 0, 0, 248,
163
+    32, 32, 32, 32, 32, 32, 5, 7, 7, 6, 0, 0, 136, 136, 136, 136,
164
+    136, 136, 112, 5, 7, 7, 6, 0, 0, 136, 136, 136, 136, 136, 80, 32,
165
+    5, 7, 7, 6, 0, 0, 136, 136, 136, 136, 136, 168, 80, 5, 7, 7,
166
+    6, 0, 0, 136, 136, 80, 32, 80, 136, 136, 5, 7, 7, 6, 0, 0,
167
+    136, 136, 136, 80, 32, 32, 32, 5, 7, 7, 6, 0, 0, 248, 8, 16,
168
+    32, 64, 128, 248, 3, 7, 7, 6, 1, 0, 224, 128, 128, 128, 128, 128,
169
+    224, 5, 5, 5, 6, 0, 1, 128, 64, 32, 16, 8, 3, 7, 7, 6,
170
+    1, 0, 224, 32, 32, 32, 32, 32, 224, 5, 3, 3, 6, 0, 4, 32,
171
+    80, 136, 5, 1, 1, 6, 0, 0, 248, 2, 2, 2, 6, 2, 5, 128,
172
+    64, 5, 5, 5, 6, 0, 0, 112, 8, 120, 136, 120, 5, 7, 7, 6,
173
+    0, 0, 128, 128, 176, 200, 136, 136, 240, 5, 5, 5, 6, 0, 0, 112,
174
+    128, 128, 136, 112, 5, 7, 7, 6, 0, 0, 8, 8, 104, 152, 136, 136,
175
+    120, 5, 5, 5, 6, 0, 0, 112, 136, 248, 128, 112, 5, 7, 7, 6,
176
+    0, 0, 48, 72, 224, 64, 64, 64, 64, 5, 6, 6, 6, 0, 255, 112,
177
+    136, 136, 120, 8, 112, 5, 7, 7, 6, 0, 0, 128, 128, 176, 200, 136,
178
+    136, 136, 1, 7, 7, 6, 2, 0, 128, 0, 128, 128, 128, 128, 128, 3,
179
+    8, 8, 6, 1, 255, 32, 0, 32, 32, 32, 32, 160, 64, 4, 7, 7,
180
+    6, 0, 0, 128, 128, 144, 160, 192, 160, 144, 3, 7, 7, 6, 1, 0,
181
+    192, 64, 64, 64, 64, 64, 224, 5, 5, 5, 6, 0, 0, 208, 168, 168,
182
+    168, 168, 5, 5, 5, 6, 0, 0, 176, 200, 136, 136, 136, 5, 5, 5,
183
+    6, 0, 0, 112, 136, 136, 136, 112, 5, 6, 6, 6, 0, 255, 240, 136,
184
+    136, 240, 128, 128, 5, 6, 6, 6, 0, 255, 120, 136, 136, 120, 8, 8,
185
+    5, 5, 5, 6, 0, 0, 176, 200, 128, 128, 128, 5, 5, 5, 6, 0,
186
+    0, 112, 128, 112, 8, 240, 4, 7, 7, 6, 0, 0, 64, 64, 224, 64,
187
+    64, 64, 48, 5, 5, 5, 6, 0, 0, 136, 136, 136, 152, 104, 5, 5,
188
+    5, 6, 0, 0, 136, 136, 136, 80, 32, 5, 5, 5, 6, 0, 0, 136,
189
+    136, 168, 168, 80, 5, 5, 5, 6, 0, 0, 136, 80, 32, 80, 136, 5,
190
+    6, 6, 6, 0, 255, 136, 136, 136, 120, 8, 112, 5, 5, 5, 6, 0,
191
+    0, 248, 16, 32, 64, 248, 3, 7, 7, 6, 1, 0, 32, 64, 64, 128,
192
+    64, 64, 32, 1, 7, 7, 6, 2, 0, 128, 128, 128, 128, 128, 128, 128,
193
+    3, 7, 7, 6, 1, 0, 128, 64, 64, 32, 64, 64, 128, 5, 2, 2,
194
+    6, 0, 2, 104, 144, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0,
195
+    0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0,
196
+    6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0,
197
+    0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0,
198
+    0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0,
199
+    6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0,
200
+    0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0,
201
+    0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0,
202
+    6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0,
203
+    0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0,
204
+    0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0,
205
+    6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0,
206
+    0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0,
207
+    0, 1, 7, 7, 6, 2, 0, 128, 0, 128, 128, 128, 128, 128, 5, 7,
208
+    7, 6, 0, 0, 32, 112, 168, 160, 168, 112, 32, 5, 7, 7, 6, 0,
209
+    0, 48, 64, 64, 224, 64, 80, 168, 5, 5, 5, 6, 0, 0, 136, 112,
210
+    80, 112, 136, 5, 7, 7, 6, 0, 0, 136, 80, 32, 248, 32, 248, 32,
211
+    1, 7, 7, 6, 2, 0, 128, 128, 128, 0, 128, 128, 128, 5, 8, 8,
212
+    6, 0, 0, 48, 72, 32, 80, 80, 32, 144, 96, 3, 1, 1, 6, 1,
213
+    7, 160, 5, 7, 7, 6, 0, 0, 248, 136, 184, 184, 184, 136, 248, 5,
214
+    7, 7, 6, 0, 1, 112, 8, 120, 136, 120, 0, 248, 5, 5, 5, 6,
215
+    0, 1, 40, 80, 160, 80, 40, 5, 3, 3, 6, 0, 1, 248, 8, 8,
216
+    2, 2, 2, 6, 2, 6, 64, 128, 5, 7, 7, 6, 0, 0, 248, 136,
217
+    168, 136, 152, 168, 248, 5, 1, 1, 6, 0, 6, 248, 4, 4, 4, 6,
218
+    0, 3, 96, 144, 144, 96, 5, 7, 7, 6, 0, 0, 32, 32, 248, 32,
219
+    32, 0, 248, 4, 5, 5, 6, 0, 3, 96, 144, 32, 64, 240, 3, 5,
220
+    5, 6, 0, 3, 224, 32, 224, 32, 224, 2, 2, 2, 6, 2, 6, 64,
221
+    128, 5, 8, 8, 6, 0, 255, 136, 136, 136, 136, 152, 232, 128, 128, 5,
222
+    7, 7, 6, 0, 0, 120, 152, 152, 120, 24, 24, 24, 2, 2, 2, 6,
223
+    2, 2, 192, 192, 2, 2, 2, 6, 2, 255, 64, 128, 3, 5, 5, 6,
224
+    0, 3, 64, 192, 64, 64, 224, 5, 7, 7, 6, 0, 1, 112, 136, 136,
225
+    136, 112, 0, 248, 5, 5, 5, 6, 0, 1, 160, 80, 40, 80, 160, 5,
226
+    7, 7, 6, 0, 0, 136, 144, 168, 88, 184, 8, 8, 5, 7, 7, 6,
227
+    0, 0, 136, 144, 184, 72, 152, 32, 56, 5, 8, 8, 6, 0, 0, 192,
228
+    64, 192, 72, 216, 56, 8, 8, 5, 7, 7, 6, 0, 0, 32, 0, 32,
229
+    64, 128, 136, 112, 5, 8, 8, 6, 0, 0, 64, 32, 0, 112, 136, 248,
230
+    136, 136, 5, 8, 8, 6, 0, 0, 16, 32, 0, 112, 136, 248, 136, 136,
231
+    5, 8, 8, 6, 0, 0, 32, 80, 0, 112, 136, 248, 136, 136, 5, 8,
232
+    8, 6, 0, 0, 104, 144, 0, 112, 136, 248, 136, 136, 5, 8, 8, 6,
233
+    0, 0, 80, 0, 112, 136, 136, 248, 136, 136, 5, 8, 8, 6, 0, 0,
234
+    32, 80, 32, 112, 136, 248, 136, 136, 5, 7, 7, 6, 0, 0, 56, 96,
235
+    160, 184, 224, 160, 184, 5, 8, 8, 6, 0, 255, 112, 136, 128, 128, 136,
236
+    112, 32, 96, 5, 8, 8, 6, 0, 0, 64, 32, 0, 248, 128, 240, 128,
237
+    248, 5, 8, 8, 6, 0, 0, 8, 16, 0, 248, 128, 240, 128, 248, 5,
238
+    8, 8, 6, 0, 0, 32, 80, 0, 248, 128, 240, 128, 248, 5, 7, 7,
239
+    6, 0, 0, 80, 0, 248, 128, 240, 128, 248, 3, 8, 8, 6, 1, 0,
240
+    128, 64, 0, 224, 64, 64, 64, 224, 3, 8, 8, 6, 1, 0, 32, 64,
241
+    0, 224, 64, 64, 64, 224, 3, 8, 8, 6, 1, 0, 64, 160, 0, 224,
242
+    64, 64, 64, 224, 3, 7, 7, 6, 1, 0, 160, 0, 224, 64, 64, 64,
243
+    224, 5, 7, 7, 6, 0, 0, 112, 72, 72, 232, 72, 72, 112, 5, 8,
244
+    8, 6, 0, 0, 104, 144, 0, 136, 200, 168, 152, 136, 5, 8, 8, 6,
245
+    0, 0, 64, 32, 112, 136, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0,
246
+    16, 32, 112, 136, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 32, 80,
247
+    0, 112, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 104, 144, 0, 112,
248
+    136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 80, 0, 112, 136, 136, 136,
249
+    136, 112, 5, 5, 5, 6, 0, 1, 136, 80, 32, 80, 136, 5, 8, 8,
250
+    6, 0, 255, 16, 112, 168, 168, 168, 168, 112, 64, 5, 8, 8, 6, 0,
251
+    0, 64, 32, 136, 136, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 16,
252
+    32, 136, 136, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 32, 80, 0,
253
+    136, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 80, 0, 136, 136, 136,
254
+    136, 136, 112, 5, 8, 8, 6, 0, 0, 16, 32, 136, 80, 32, 32, 32,
255
+    32, 5, 9, 9, 6, 0, 255, 192, 64, 112, 72, 72, 112, 64, 64, 224,
256
+    4, 8, 8, 6, 1, 255, 96, 144, 144, 160, 144, 144, 224, 128, 5, 8,
257
+    8, 6, 0, 0, 64, 32, 0, 112, 8, 120, 136, 120, 5, 8, 8, 6,
258
+    0, 0, 16, 32, 0, 112, 8, 120, 136, 120, 5, 8, 8, 6, 0, 0,
259
+    32, 80, 0, 112, 8, 120, 136, 120, 5, 8, 8, 6, 0, 0, 104, 144,
260
+    0, 112, 8, 120, 136, 120, 5, 7, 7, 6, 0, 0, 80, 0, 112, 8,
261
+    120, 136, 120, 5, 8, 8, 6, 0, 0, 32, 80, 32, 112, 8, 120, 136,
262
+    120, 5, 6, 6, 6, 0, 0, 208, 40, 120, 160, 168, 80, 5, 6, 6,
263
+    6, 0, 255, 112, 128, 136, 112, 32, 96, 5, 8, 8, 6, 0, 0, 64,
264
+    32, 0, 112, 136, 248, 128, 112, 5, 8, 8, 6, 0, 0, 16, 32, 0,
265
+    112, 136, 248, 128, 112, 5, 8, 8, 6, 0, 0, 32, 80, 0, 112, 136,
266
+    248, 128, 112, 5, 7, 7, 6, 0, 0, 80, 0, 112, 136, 248, 128, 112,
267
+    3, 8, 8, 6, 1, 0, 128, 64, 0, 64, 192, 64, 64, 224, 3, 8,
268
+    8, 6, 1, 0, 32, 64, 0, 64, 192, 64, 64, 224, 3, 8, 8, 6,
269
+    1, 0, 64, 160, 0, 64, 192, 64, 64, 224, 3, 7, 7, 6, 1, 0,
270
+    160, 0, 64, 192, 64, 64, 224, 5, 7, 7, 6, 0, 0, 160, 64, 160,
271
+    16, 120, 136, 112, 5, 8, 8, 6, 0, 0, 104, 144, 0, 176, 200, 136,
272
+    136, 136, 5, 8, 8, 6, 0, 0, 64, 32, 0, 112, 136, 136, 136, 112,
273
+    5, 8, 8, 6, 0, 0, 16, 32, 0, 112, 136, 136, 136, 112, 5, 8,
274
+    8, 6, 0, 0, 32, 80, 0, 112, 136, 136, 136, 112, 5, 8, 8, 6,
275
+    0, 0, 104, 144, 0, 112, 136, 136, 136, 112, 5, 7, 7, 6, 0, 0,
276
+    80, 0, 112, 136, 136, 136, 112, 5, 5, 5, 6, 0, 1, 32, 0, 248,
277
+    0, 32, 5, 7, 7, 6, 0, 255, 16, 112, 168, 168, 168, 112, 64, 5,
278
+    8, 8, 6, 0, 0, 64, 32, 0, 136, 136, 136, 152, 104, 5, 8, 8,
279
+    6, 0, 0, 16, 32, 0, 136, 136, 136, 152, 104, 5, 8, 8, 6, 0,
280
+    0, 32, 80, 0, 136, 136, 136, 152, 104, 5, 7, 7, 6, 0, 0, 80,
281
+    0, 136, 136, 136, 152, 104, 5, 9, 9, 6, 0, 255, 16, 32, 0, 136,
282
+    136, 136, 248, 8, 112, 4, 7, 7, 6, 1, 255, 192, 64, 96, 80, 96,
283
+    64, 224, 5, 8, 8, 6, 0, 255, 80, 0, 136, 136, 136, 120, 8, 112
284
+  };
285
+
286
+#endif

+ 151
- 0
Marlin/dogm_font_data_ISO10646_SK.h 파일 보기

@@ -0,0 +1,151 @@
1
+/*
2
+  Fontname: ISO10646_SK
3
+  Copyright: A. Hardtung, modified by Roman Moravcik
4
+  Capital A Height: 7, '1' Height: 7
5
+  Calculated Max Values w= 6 h= 9 x= 2 y= 7 dx= 6 dy= 0 ascent= 8 len= 9
6
+  Font Bounding box     w= 6 h= 9 x= 0 y=-2
7
+  Calculated Min Values           x= 0 y=-1 dx= 0 dy= 0
8
+  Pure Font   ascent = 7 descent=-1
9
+  X Font      ascent = 7 descent=-1
10
+  Max Font    ascent = 8 descent=-1
11
+*/
12
+#include <U8glib.h>
13
+const u8g_fntpgm_uint8_t ISO10646_SK[2203] U8G_SECTION(".progmem.ISO10646_SK") = {
14
+  0,6,9,0,254,7,1,146,3,33,32,255,255,8,255,7,
15
+  255,0,0,0,6,0,0,1,7,7,6,2,0,128,128,128,
16
+  128,128,0,128,3,2,2,6,1,5,160,160,5,7,7,6,
17
+  0,0,80,80,248,80,248,80,80,5,7,7,6,0,0,32,
18
+  120,160,112,40,240,32,5,7,7,6,0,0,192,200,16,32,
19
+  64,152,24,5,7,7,6,0,0,96,144,160,64,168,144,104,
20
+  2,3,3,6,1,4,192,64,128,3,7,7,6,1,0,32,
21
+  64,128,128,128,64,32,3,7,7,6,1,0,128,64,32,32,
22
+  32,64,128,5,5,5,6,0,1,32,168,112,168,32,5,5,
23
+  5,6,0,1,32,32,248,32,32,2,3,3,6,2,255,192,
24
+  64,128,5,1,1,6,0,3,248,2,2,2,6,2,0,192,
25
+  192,5,5,5,6,0,1,8,16,32,64,128,5,7,7,6,
26
+  0,0,112,136,136,136,136,136,112,3,7,7,6,1,0,64,
27
+  192,64,64,64,64,224,5,7,7,6,0,0,112,136,8,112,
28
+  128,128,248,5,7,7,6,0,0,248,16,32,16,8,8,240,
29
+  5,7,7,6,0,0,16,48,80,144,248,16,16,5,7,7,
30
+  6,0,0,248,128,240,8,8,136,112,5,7,7,6,0,0,
31
+  112,128,128,240,136,136,112,5,7,7,6,0,0,248,8,16,
32
+  32,32,32,32,5,7,7,6,0,0,112,136,136,112,136,136,
33
+  112,5,7,7,6,0,0,112,136,136,120,8,8,112,2,5,
34
+  5,6,2,0,192,192,0,192,192,2,6,6,6,2,255,192,
35
+  192,0,192,64,128,4,7,7,6,0,0,16,32,64,128,64,
36
+  32,16,5,3,3,6,0,2,248,0,248,4,7,7,6,1,
37
+  0,128,64,32,16,32,64,128,5,7,7,6,0,0,112,136,
38
+  8,16,32,0,32,5,7,7,6,0,0,112,136,8,104,168,
39
+  168,112,5,7,7,6,0,0,112,136,136,248,136,136,136,5,
40
+  7,7,6,0,0,240,136,136,240,136,136,240,5,7,7,6,
41
+  0,0,112,136,128,128,128,136,112,5,7,7,6,0,0,240,
42
+  136,136,136,136,136,240,5,7,7,6,0,0,248,128,128,240,
43
+  128,128,248,5,7,7,6,0,0,248,128,128,240,128,128,128,
44
+  5,7,7,6,0,0,112,136,128,184,136,136,112,5,7,7,
45
+  6,0,0,136,136,136,248,136,136,136,1,7,7,6,2,0,
46
+  128,128,128,128,128,128,128,5,7,7,6,0,0,56,16,16,
47
+  16,16,144,96,5,7,7,6,0,0,136,144,160,192,160,144,
48
+  136,5,7,7,6,0,0,128,128,128,128,128,128,248,5,7,
49
+  7,6,0,0,136,216,168,136,136,136,136,5,7,7,6,0,
50
+  0,136,136,200,168,152,136,136,5,7,7,6,0,0,112,136,
51
+  136,136,136,136,112,5,7,7,6,0,0,240,136,136,240,128,
52
+  128,128,5,7,7,6,0,0,112,136,136,136,168,144,104,5,
53
+  7,7,6,0,0,240,136,136,240,160,144,136,5,7,7,6,
54
+  0,0,120,128,128,112,8,8,240,5,7,7,6,0,0,248,
55
+  32,32,32,32,32,32,5,7,7,6,0,0,136,136,136,136,
56
+  136,136,112,5,7,7,6,0,0,136,136,136,136,136,80,32,
57
+  5,7,7,6,0,0,136,136,136,136,136,168,80,5,7,7,
58
+  6,0,0,136,136,80,32,80,136,136,5,7,7,6,0,0,
59
+  136,136,136,80,32,32,32,5,7,7,6,0,0,248,8,16,
60
+  32,64,128,248,3,7,7,6,1,0,224,128,128,128,128,128,
61
+  224,5,5,5,6,0,1,128,64,32,16,8,3,7,7,6,
62
+  1,0,224,32,32,32,32,32,224,5,3,3,6,0,4,32,
63
+  80,136,5,1,1,6,0,0,248,2,2,2,6,2,5,128,
64
+  64,5,5,5,6,0,0,112,8,120,136,120,5,7,7,6,
65
+  0,0,128,128,176,200,136,136,240,5,5,5,6,0,0,112,
66
+  128,128,136,112,5,7,7,6,0,0,8,8,104,152,136,136,
67
+  120,5,5,5,6,0,0,112,136,248,128,112,5,7,7,6,
68
+  0,0,48,72,224,64,64,64,64,5,6,6,6,0,255,112,
69
+  136,136,120,8,112,5,7,7,6,0,0,128,128,176,200,136,
70
+  136,136,1,7,7,6,2,0,128,0,128,128,128,128,128,3,
71
+  8,8,6,1,255,32,0,32,32,32,32,160,64,4,7,7,
72
+  6,0,0,128,128,144,160,192,160,144,3,7,7,6,1,0,
73
+  192,64,64,64,64,64,224,5,5,5,6,0,0,208,168,168,
74
+  168,168,5,5,5,6,0,0,176,200,136,136,136,5,5,5,
75
+  6,0,0,112,136,136,136,112,5,6,6,6,0,255,240,136,
76
+  136,240,128,128,5,6,6,6,0,255,120,136,136,120,8,8,
77
+  5,5,5,6,0,0,176,200,128,128,128,5,5,5,6,0,
78
+  0,112,128,112,8,240,4,7,7,6,0,0,64,64,224,64,
79
+  64,64,48,5,5,5,6,0,0,136,136,136,152,104,5,5,
80
+  5,6,0,0,136,136,136,80,32,5,5,5,6,0,0,136,
81
+  136,168,168,80,5,5,5,6,0,0,136,80,32,80,136,5,
82
+  6,6,6,0,255,136,136,136,120,8,112,5,5,5,6,0,
83
+  0,248,16,32,64,248,3,7,7,6,1,0,32,64,64,128,
84
+  64,64,32,1,7,7,6,2,0,128,128,128,128,128,128,128,
85
+  3,7,7,6,1,0,128,64,64,32,64,64,128,5,2,2,
86
+  6,0,2,104,144,0,0,0,6,0,0,5,8,8,6,0,
87
+  0,16,32,112,136,136,248,136,136,5,8,8,6,0,0,80,
88
+  0,112,136,136,248,136,136,5,8,8,6,0,0,8,16,248,
89
+  128,128,240,128,248,3,8,8,6,1,0,32,64,224,64,64,
90
+  64,64,224,5,8,8,6,0,0,16,32,112,136,136,136,136,
91
+  112,5,8,8,6,0,0,32,80,112,136,136,136,136,112,5,
92
+  8,8,6,0,0,16,32,136,136,136,136,136,112,5,8,8,
93
+  6,0,0,16,32,136,136,80,32,32,32,5,8,8,6,0,
94
+  0,16,32,0,112,8,120,136,120,5,7,7,6,0,0,80,
95
+  0,112,8,120,136,120,5,8,8,6,0,0,16,32,0,112,
96
+  136,248,128,112,2,8,8,6,2,0,64,128,0,128,128,128,
97
+  128,128,5,8,8,6,0,0,16,32,0,112,136,136,136,112,
98
+  5,8,8,6,0,0,32,80,0,112,136,136,136,112,5,8,
99
+  8,6,0,0,16,32,0,136,136,136,152,104,5,9,9,6,
100
+  0,255,16,32,0,136,136,136,120,8,112,5,8,8,6,0,
101
+  0,80,32,112,136,128,128,136,112,5,8,8,6,0,0,80,
102
+  32,0,112,128,128,136,112,5,8,8,6,0,0,80,32,240,
103
+  136,136,136,136,240,6,8,8,6,0,0,4,20,24,112,144,
104
+  144,144,112,5,8,8,6,0,0,16,32,128,128,128,128,128,
105
+  248,3,8,8,6,1,0,32,64,0,192,64,64,64,224,5,
106
+  8,8,6,0,0,16,144,160,128,128,128,128,248,5,8,8,
107
+  6,1,0,8,200,80,64,64,64,64,224,5,8,8,6,0,
108
+  0,80,32,136,200,168,152,136,136,5,8,8,6,0,0,80,
109
+  32,0,176,200,136,136,136,5,8,8,6,0,0,16,32,240,
110
+  136,240,160,144,136,5,8,8,6,0,0,16,32,0,176,200,
111
+  128,128,128,5,8,8,6,0,0,80,32,120,128,128,112,8,
112
+  240,5,8,8,6,0,0,80,32,0,112,128,112,8,240,5,
113
+  8,8,6,0,0,80,32,248,32,32,32,32,32,6,8,8,
114
+  6,0,0,4,68,72,224,64,64,64,48,5,8,8,6,0,
115
+  0,80,32,248,8,48,64,128,248,5,8,8,6,0,0,80,
116
+  32,0,248,16,32,64,248,0,0,0,6,0,0,0,0,0,
117
+  6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
118
+  0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
119
+  0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
120
+  6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
121
+  0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
122
+  0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
123
+  6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
124
+  0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
125
+  0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
126
+  6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
127
+  0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
128
+  0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
129
+  6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
130
+  0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
131
+  0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
132
+  6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
133
+  0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
134
+  0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
135
+  6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
136
+  0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
137
+  0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
138
+  6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
139
+  0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
140
+  0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
141
+  6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
142
+  0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
143
+  0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
144
+  6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
145
+  0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
146
+  0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
147
+  6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
148
+  0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
149
+  0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
150
+  6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
151
+  0,0,6,0,0,0,0,0,6,0,0};

+ 49
- 9
Marlin/endstop_interrupts.h 파일 보기

@@ -111,7 +111,7 @@ void endstop_ISR(void) { endstop_ISR_worker(); }
111 111
 void setup_endstop_interrupts( void ) {
112 112
 
113 113
   #if HAS_X_MAX
114
-    #if (digitalPinToInterrupt(X_MAX_PIN) != NOT_AN_INTERRUPT) // if pin has an external interrupt
114
+    #if digitalPinToInterrupt(X_MAX_PIN) != NOT_AN_INTERRUPT // if pin has an external interrupt
115 115
       attachInterrupt(digitalPinToInterrupt(X_MAX_PIN), endstop_ISR, CHANGE); // assign it
116 116
     #else
117 117
       // Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
@@ -121,7 +121,7 @@ void setup_endstop_interrupts( void ) {
121 121
   #endif
122 122
 
123 123
   #if HAS_X_MIN
124
-    #if (digitalPinToInterrupt(X_MIN_PIN) != NOT_AN_INTERRUPT)
124
+    #if digitalPinToInterrupt(X_MIN_PIN) != NOT_AN_INTERRUPT
125 125
       attachInterrupt(digitalPinToInterrupt(X_MIN_PIN), endstop_ISR, CHANGE);
126 126
     #else
127 127
       // Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
@@ -131,7 +131,7 @@ void setup_endstop_interrupts( void ) {
131 131
   #endif
132 132
 
133 133
   #if HAS_Y_MAX
134
-    #if (digitalPinToInterrupt(Y_MAX_PIN) != NOT_AN_INTERRUPT)
134
+    #if digitalPinToInterrupt(Y_MAX_PIN) != NOT_AN_INTERRUPT
135 135
       attachInterrupt(digitalPinToInterrupt(Y_MAX_PIN), endstop_ISR, CHANGE);
136 136
     #else
137 137
       // Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
@@ -141,7 +141,7 @@ void setup_endstop_interrupts( void ) {
141 141
   #endif
142 142
 
143 143
   #if HAS_Y_MIN
144
-    #if (digitalPinToInterrupt(Y_MIN_PIN) != NOT_AN_INTERRUPT)
144
+    #if digitalPinToInterrupt(Y_MIN_PIN) != NOT_AN_INTERRUPT
145 145
       attachInterrupt(digitalPinToInterrupt(Y_MIN_PIN), endstop_ISR, CHANGE);
146 146
     #else
147 147
       // Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
@@ -151,7 +151,7 @@ void setup_endstop_interrupts( void ) {
151 151
   #endif
152 152
 
153 153
   #if HAS_Z_MAX
154
-    #if (digitalPinToInterrupt(Z_MAX_PIN) != NOT_AN_INTERRUPT)
154
+    #if digitalPinToInterrupt(Z_MAX_PIN) != NOT_AN_INTERRUPT
155 155
       attachInterrupt(digitalPinToInterrupt(Z_MAX_PIN), endstop_ISR, CHANGE);
156 156
     #else
157 157
       // Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
@@ -161,7 +161,7 @@ void setup_endstop_interrupts( void ) {
161 161
   #endif
162 162
 
163 163
   #if HAS_Z_MIN
164
-    #if (digitalPinToInterrupt(Z_MIN_PIN) != NOT_AN_INTERRUPT)
164
+    #if digitalPinToInterrupt(Z_MIN_PIN) != NOT_AN_INTERRUPT
165 165
       attachInterrupt(digitalPinToInterrupt(Z_MIN_PIN), endstop_ISR, CHANGE);
166 166
     #else
167 167
       // Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
@@ -170,8 +170,48 @@ void setup_endstop_interrupts( void ) {
170 170
     #endif
171 171
   #endif
172 172
 
173
+  #if HAS_X2_MAX
174
+    #if (digitalPinToInterrupt(X2_MAX_PIN) != NOT_AN_INTERRUPT)
175
+      attachInterrupt(digitalPinToInterrupt(X2_MAX_PIN), endstop_ISR, CHANGE);
176
+    #else
177
+      // Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
178
+      static_assert(digitalPinToPCICR(X2_MAX_PIN) != NULL, "X2_MAX_PIN is not interrupt-capable");
179
+      pciSetup(X2_MAX_PIN);
180
+    #endif
181
+  #endif
182
+
183
+  #if HAS_X2_MIN
184
+    #if (digitalPinToInterrupt(X2_MIN_PIN) != NOT_AN_INTERRUPT)
185
+      attachInterrupt(digitalPinToInterrupt(X2_MIN_PIN), endstop_ISR, CHANGE);
186
+    #else
187
+      // Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
188
+      static_assert(digitalPinToPCICR(X2_MIN_PIN) != NULL, "X2_MIN_PIN is not interrupt-capable");
189
+      pciSetup(X2_MIN_PIN);
190
+    #endif
191
+  #endif
192
+
193
+  #if HAS_Y2_MAX
194
+    #if (digitalPinToInterrupt(Y2_MAX_PIN) != NOT_AN_INTERRUPT)
195
+      attachInterrupt(digitalPinToInterrupt(Y2_MAX_PIN), endstop_ISR, CHANGE);
196
+    #else
197
+      // Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
198
+      static_assert(digitalPinToPCICR(Y2_MAX_PIN) != NULL, "Y2_MAX_PIN is not interrupt-capable");
199
+      pciSetup(Y2_MAX_PIN);
200
+    #endif
201
+  #endif
202
+
203
+  #if HAS_Y2_MIN
204
+    #if (digitalPinToInterrupt(Y2_MIN_PIN) != NOT_AN_INTERRUPT)
205
+      attachInterrupt(digitalPinToInterrupt(Y2_MIN_PIN), endstop_ISR, CHANGE);
206
+    #else
207
+      // Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
208
+      static_assert(digitalPinToPCICR(Y2_MIN_PIN) != NULL, "Y2_MIN_PIN is not interrupt-capable");
209
+      pciSetup(Y2_MIN_PIN);
210
+    #endif
211
+  #endif
212
+
173 213
   #if HAS_Z2_MAX
174
-    #if (digitalPinToInterrupt(Z2_MAX_PIN) != NOT_AN_INTERRUPT)
214
+    #if digitalPinToInterrupt(Z2_MAX_PIN) != NOT_AN_INTERRUPT
175 215
       attachInterrupt(digitalPinToInterrupt(Z2_MAX_PIN), endstop_ISR, CHANGE);
176 216
     #else
177 217
       // Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
@@ -181,7 +221,7 @@ void setup_endstop_interrupts( void ) {
181 221
   #endif
182 222
 
183 223
   #if HAS_Z2_MIN
184
-    #if (digitalPinToInterrupt(Z2_MIN_PIN) != NOT_AN_INTERRUPT)
224
+    #if digitalPinToInterrupt(Z2_MIN_PIN) != NOT_AN_INTERRUPT
185 225
       attachInterrupt(digitalPinToInterrupt(Z2_MIN_PIN), endstop_ISR, CHANGE);
186 226
     #else
187 227
       // Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
@@ -191,7 +231,7 @@ void setup_endstop_interrupts( void ) {
191 231
   #endif
192 232
 
193 233
   #if HAS_Z_MIN_PROBE_PIN
194
-    #if (digitalPinToInterrupt(Z_MIN_PROBE_PIN) != NOT_AN_INTERRUPT)
234
+    #if digitalPinToInterrupt(Z_MIN_PROBE_PIN) != NOT_AN_INTERRUPT
195 235
       attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_PIN), endstop_ISR, CHANGE);
196 236
     #else
197 237
       // Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!

+ 137
- 61
Marlin/endstops.cpp 파일 보기

@@ -38,17 +38,10 @@ Endstops endstops;
38 38
 
39 39
 // public:
40 40
 
41
-bool  Endstops::enabled = true,
42
-      Endstops::enabled_globally =
43
-        #if ENABLED(ENDSTOPS_ALWAYS_ON_DEFAULT)
44
-          (true)
45
-        #else
46
-          (false)
47
-        #endif
48
-      ;
41
+bool Endstops::enabled, Endstops::enabled_globally; // Initialized by settings.load()
49 42
 volatile char Endstops::endstop_hit_bits; // use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT value
50 43
 
51
-#if ENABLED(Z_DUAL_ENDSTOPS)
44
+#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
52 45
   uint16_t
53 46
 #else
54 47
   byte
@@ -74,6 +67,14 @@ void Endstops::init() {
74 67
     #endif
75 68
   #endif
76 69
 
70
+  #if HAS_X2_MIN
71
+    #if ENABLED(ENDSTOPPULLUP_XMIN)
72
+      SET_INPUT_PULLUP(X2_MIN_PIN);
73
+    #else
74
+      SET_INPUT(X2_MIN_PIN);
75
+    #endif
76
+  #endif
77
+
77 78
   #if HAS_Y_MIN
78 79
     #if ENABLED(ENDSTOPPULLUP_YMIN)
79 80
       SET_INPUT_PULLUP(Y_MIN_PIN);
@@ -82,6 +83,14 @@ void Endstops::init() {
82 83
     #endif
83 84
   #endif
84 85
 
86
+  #if HAS_Y2_MIN
87
+    #if ENABLED(ENDSTOPPULLUP_YMIN)
88
+      SET_INPUT_PULLUP(Y2_MIN_PIN);
89
+    #else
90
+      SET_INPUT(Y2_MIN_PIN);
91
+    #endif
92
+  #endif
93
+
85 94
   #if HAS_Z_MIN
86 95
     #if ENABLED(ENDSTOPPULLUP_ZMIN)
87 96
       SET_INPUT_PULLUP(Z_MIN_PIN);
@@ -106,6 +115,14 @@ void Endstops::init() {
106 115
     #endif
107 116
   #endif
108 117
 
118
+  #if HAS_X2_MAX
119
+    #if ENABLED(ENDSTOPPULLUP_XMAX)
120
+      SET_INPUT_PULLUP(X2_MAX_PIN);
121
+    #else
122
+      SET_INPUT(X2_MAX_PIN);
123
+    #endif
124
+  #endif
125
+
109 126
   #if HAS_Y_MAX
110 127
     #if ENABLED(ENDSTOPPULLUP_YMAX)
111 128
       SET_INPUT_PULLUP(Y_MAX_PIN);
@@ -114,6 +131,14 @@ void Endstops::init() {
114 131
     #endif
115 132
   #endif
116 133
 
134
+  #if HAS_Y2_MAX
135
+    #if ENABLED(ENDSTOPPULLUP_YMAX)
136
+      SET_INPUT_PULLUP(Y2_MAX_PIN);
137
+    #else
138
+      SET_INPUT(Y2_MAX_PIN);
139
+    #endif
140
+  #endif
141
+
117 142
   #if HAS_Z_MAX
118 143
     #if ENABLED(ENDSTOPPULLUP_ZMAX)
119 144
       SET_INPUT_PULLUP(Z_MAX_PIN);
@@ -192,37 +217,45 @@ void Endstops::report_state() {
192 217
 
193 218
 void Endstops::M119() {
194 219
   SERIAL_PROTOCOLLNPGM(MSG_M119_REPORT);
220
+  #define ES_REPORT(AXIS) do{ \
221
+    SERIAL_PROTOCOLPGM(MSG_##AXIS); \
222
+    SERIAL_PROTOCOLLN(((READ(AXIS##_PIN)^AXIS##_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN)); \
223
+  }while(0)
195 224
   #if HAS_X_MIN
196
-    SERIAL_PROTOCOLPGM(MSG_X_MIN);
197
-    SERIAL_PROTOCOLLN(((READ(X_MIN_PIN)^X_MIN_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
225
+    ES_REPORT(X_MIN);
226
+  #endif
227
+  #if HAS_X2_MIN
228
+    ES_REPORT(X2_MIN);
198 229
   #endif
199 230
   #if HAS_X_MAX
200
-    SERIAL_PROTOCOLPGM(MSG_X_MAX);
201
-    SERIAL_PROTOCOLLN(((READ(X_MAX_PIN)^X_MAX_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
231
+    ES_REPORT(X_MAX);
232
+  #endif
233
+  #if HAS_X2_MAX
234
+    ES_REPORT(X2_MAX);
202 235
   #endif
203 236
   #if HAS_Y_MIN
204
-    SERIAL_PROTOCOLPGM(MSG_Y_MIN);
205
-    SERIAL_PROTOCOLLN(((READ(Y_MIN_PIN)^Y_MIN_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
237
+    ES_REPORT(Y_MIN);
238
+  #endif
239
+  #if HAS_Y2_MIN
240
+    ES_REPORT(Y2_MIN);
206 241
   #endif
207 242
   #if HAS_Y_MAX
208
-    SERIAL_PROTOCOLPGM(MSG_Y_MAX);
209
-    SERIAL_PROTOCOLLN(((READ(Y_MAX_PIN)^Y_MAX_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
243
+    ES_REPORT(Y_MAX);
244
+  #endif
245
+  #if HAS_Y2_MAX
246
+    ES_REPORT(Y2_MAX);
210 247
   #endif
211 248
   #if HAS_Z_MIN
212
-    SERIAL_PROTOCOLPGM(MSG_Z_MIN);
213
-    SERIAL_PROTOCOLLN(((READ(Z_MIN_PIN)^Z_MIN_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
249
+    ES_REPORT(Z_MIN);
214 250
   #endif
215 251
   #if HAS_Z2_MIN
216
-    SERIAL_PROTOCOLPGM(MSG_Z2_MIN);
217
-    SERIAL_PROTOCOLLN(((READ(Z2_MIN_PIN)^Z2_MIN_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
252
+    ES_REPORT(Z2_MIN);
218 253
   #endif
219 254
   #if HAS_Z_MAX
220
-    SERIAL_PROTOCOLPGM(MSG_Z_MAX);
221
-    SERIAL_PROTOCOLLN(((READ(Z_MAX_PIN)^Z_MAX_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
255
+    ES_REPORT(Z_MAX);
222 256
   #endif
223 257
   #if HAS_Z2_MAX
224
-    SERIAL_PROTOCOLPGM(MSG_Z2_MAX);
225
-    SERIAL_PROTOCOLLN(((READ(Z2_MAX_PIN)^Z2_MAX_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
258
+    ES_REPORT(Z2_MAX);
226 259
   #endif
227 260
   #if ENABLED(Z_MIN_PROBE_ENDSTOP)
228 261
     SERIAL_PROTOCOLPGM(MSG_Z_PROBE);
@@ -234,9 +267,27 @@ void Endstops::M119() {
234 267
   #endif
235 268
 } // Endstops::M119
236 269
 
270
+#if ENABLED(X_DUAL_ENDSTOPS)
271
+  void Endstops::test_dual_x_endstops(const EndstopEnum es1, const EndstopEnum es2) {
272
+    byte x_test = TEST_ENDSTOP(es1) | (TEST_ENDSTOP(es2) << 1); // bit 0 for X, bit 1 for X2
273
+    if (x_test && stepper.current_block->steps[X_AXIS] > 0) {
274
+      SBI(endstop_hit_bits, X_MIN);
275
+      if (!stepper.performing_homing || (x_test == 0x3))  //if not performing home or if both endstops were trigged during homing...
276
+        stepper.kill_current_block();
277
+    }
278
+  }
279
+#endif
280
+#if ENABLED(Y_DUAL_ENDSTOPS)
281
+  void Endstops::test_dual_y_endstops(const EndstopEnum es1, const EndstopEnum es2) {
282
+    byte y_test = TEST_ENDSTOP(es1) | (TEST_ENDSTOP(es2) << 1); // bit 0 for Y, bit 1 for Y2
283
+    if (y_test && stepper.current_block->steps[Y_AXIS] > 0) {
284
+      SBI(endstop_hit_bits, Y_MIN);
285
+      if (!stepper.performing_homing || (y_test == 0x3))  //if not performing home or if both endstops were trigged during homing...
286
+        stepper.kill_current_block();
287
+    }
288
+  }
289
+#endif
237 290
 #if ENABLED(Z_DUAL_ENDSTOPS)
238
-
239
-  // Pass the result of the endstop test
240 291
   void Endstops::test_dual_z_endstops(const EndstopEnum es1, const EndstopEnum es2) {
241 292
     byte z_test = TEST_ENDSTOP(es1) | (TEST_ENDSTOP(es2) << 1); // bit 0 for Z, bit 1 for Z2
242 293
     if (z_test && stepper.current_block->steps[Z_AXIS] > 0) {
@@ -245,7 +296,6 @@ void Endstops::M119() {
245 296
         stepper.kill_current_block();
246 297
     }
247 298
   }
248
-
249 299
 #endif
250 300
 
251 301
 // Check endstops - Called from ISR!
@@ -254,7 +304,7 @@ void Endstops::update() {
254 304
   #define _ENDSTOP(AXIS, MINMAX) AXIS ##_## MINMAX
255 305
   #define _ENDSTOP_PIN(AXIS, MINMAX) AXIS ##_## MINMAX ##_PIN
256 306
   #define _ENDSTOP_INVERTING(AXIS, MINMAX) AXIS ##_## MINMAX ##_ENDSTOP_INVERTING
257
-  #define _ENDSTOP_HIT(AXIS) SBI(endstop_hit_bits, _ENDSTOP(AXIS, MIN))
307
+  #define _ENDSTOP_HIT(AXIS, MINMAX) SBI(endstop_hit_bits, _ENDSTOP(AXIS, MINMAX))
258 308
 
259 309
   // UPDATE_ENDSTOP_BIT: set the current endstop bits for an endstop to its status
260 310
   #define UPDATE_ENDSTOP_BIT(AXIS, MINMAX) SET_BIT(current_endstop_bits, _ENDSTOP(AXIS, MINMAX), (READ(_ENDSTOP_PIN(AXIS, MINMAX)) != _ENDSTOP_INVERTING(AXIS, MINMAX)))
@@ -264,19 +314,19 @@ void Endstops::update() {
264 314
   #define UPDATE_ENDSTOP(AXIS,MINMAX) do { \
265 315
       UPDATE_ENDSTOP_BIT(AXIS, MINMAX); \
266 316
       if (TEST_ENDSTOP(_ENDSTOP(AXIS, MINMAX)) && stepper.current_block->steps[_AXIS(AXIS)] > 0) { \
267
-        _ENDSTOP_HIT(AXIS); \
317
+        _ENDSTOP_HIT(AXIS, MINMAX); \
268 318
         stepper.endstop_triggered(_AXIS(AXIS)); \
269 319
       } \
270
-    } while(0)
320
+    }while(0)
271 321
 
272 322
   #if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && !(CORE_IS_XY || CORE_IS_XZ)
273 323
     // If G38 command is active check Z_MIN_PROBE for ALL movement
274 324
     if (G38_move) {
275 325
       UPDATE_ENDSTOP_BIT(Z, MIN_PROBE);
276 326
       if (TEST_ENDSTOP(_ENDSTOP(Z, MIN_PROBE))) {
277
-        if      (stepper.current_block->steps[_AXIS(X)] > 0) { _ENDSTOP_HIT(X); stepper.endstop_triggered(_AXIS(X)); }
278
-        else if (stepper.current_block->steps[_AXIS(Y)] > 0) { _ENDSTOP_HIT(Y); stepper.endstop_triggered(_AXIS(Y)); }
279
-        else if (stepper.current_block->steps[_AXIS(Z)] > 0) { _ENDSTOP_HIT(Z); stepper.endstop_triggered(_AXIS(Z)); }
327
+        if      (stepper.current_block->steps[_AXIS(X)] > 0) { _ENDSTOP_HIT(X, MIN); stepper.endstop_triggered(_AXIS(X)); }
328
+        else if (stepper.current_block->steps[_AXIS(Y)] > 0) { _ENDSTOP_HIT(Y, MIN); stepper.endstop_triggered(_AXIS(Y)); }
329
+        else if (stepper.current_block->steps[_AXIS(Z)] > 0) { _ENDSTOP_HIT(Z, MIN); stepper.endstop_triggered(_AXIS(Z)); }
280 330
         G38_endstop_hit = true;
281 331
       }
282 332
     }
@@ -364,18 +414,36 @@ void Endstops::update() {
364 414
   /**
365 415
    * Check and update endstops according to conditions
366 416
    */
367
-
368 417
   if (X_MOVE_TEST) {
369
-    if (stepper.motor_direction(X_AXIS_HEAD)) {
370
-      if (X_MIN_TEST) { // -direction
371
-        #if HAS_X_MIN
372
-          UPDATE_ENDSTOP(X, MIN);
418
+    if (stepper.motor_direction(X_AXIS_HEAD)) { // -direction
419
+      #if HAS_X_MIN
420
+        #if ENABLED(X_DUAL_ENDSTOPS)
421
+          UPDATE_ENDSTOP_BIT(X, MIN);
422
+          #if HAS_X2_MIN
423
+            UPDATE_ENDSTOP_BIT(X2, MIN);
424
+          #else
425
+            COPY_BIT(current_endstop_bits, X_MIN, X2_MIN);
426
+          #endif
427
+          test_dual_x_endstops(X_MIN, X2_MIN);
428
+        #else
429
+          if (X_MIN_TEST) UPDATE_ENDSTOP(X, MIN);
373 430
         #endif
374
-      }
431
+      #endif
375 432
     }
376
-    else if (X_MAX_TEST) { // +direction
433
+    else { // +direction
377 434
       #if HAS_X_MAX
378
-        UPDATE_ENDSTOP(X, MAX);
435
+        #if ENABLED(X_DUAL_ENDSTOPS)
436
+          UPDATE_ENDSTOP_BIT(X, MAX);
437
+          #if HAS_X2_MAX
438
+            UPDATE_ENDSTOP_BIT(X2, MAX);
439
+          #else
440
+            COPY_BIT(current_endstop_bits, X_MAX, X2_MAX);
441
+          #endif
442
+          test_dual_x_endstops(X_MAX, X2_MAX);
443
+        #else
444
+          if (X_MIN_TEST) UPDATE_ENDSTOP(X, MAX);
445
+        #endif
446
+
379 447
       #endif
380 448
     }
381 449
   }
@@ -383,12 +451,32 @@ void Endstops::update() {
383 451
   if (Y_MOVE_TEST) {
384 452
     if (stepper.motor_direction(Y_AXIS_HEAD)) { // -direction
385 453
       #if HAS_Y_MIN
386
-        UPDATE_ENDSTOP(Y, MIN);
454
+        #if ENABLED(Y_DUAL_ENDSTOPS)
455
+          UPDATE_ENDSTOP_BIT(Y, MIN);
456
+          #if HAS_Y2_MIN
457
+            UPDATE_ENDSTOP_BIT(Y2, MIN);
458
+          #else
459
+            COPY_BIT(current_endstop_bits, Y_MIN, Y2_MIN);
460
+          #endif
461
+          test_dual_y_endstops(Y_MIN, Y2_MIN);
462
+        #else
463
+          UPDATE_ENDSTOP(Y, MIN);
464
+        #endif
387 465
       #endif
388 466
     }
389 467
     else { // +direction
390 468
       #if HAS_Y_MAX
391
-        UPDATE_ENDSTOP(Y, MAX);
469
+        #if ENABLED(Y_DUAL_ENDSTOPS)
470
+          UPDATE_ENDSTOP_BIT(Y, MAX);
471
+          #if HAS_Y2_MAX
472
+            UPDATE_ENDSTOP_BIT(Y2, MAX);
473
+          #else
474
+            COPY_BIT(current_endstop_bits, Y_MAX, Y2_MAX);
475
+          #endif
476
+          test_dual_y_endstops(Y_MAX, Y2_MAX);
477
+        #else
478
+          UPDATE_ENDSTOP(Y, MAX);
479
+        #endif
392 480
       #endif
393 481
     }
394 482
   }
@@ -397,27 +485,21 @@ void Endstops::update() {
397 485
     if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up.
398 486
       #if HAS_Z_MIN
399 487
         #if ENABLED(Z_DUAL_ENDSTOPS)
400
-
401 488
           UPDATE_ENDSTOP_BIT(Z, MIN);
402 489
           #if HAS_Z2_MIN
403 490
             UPDATE_ENDSTOP_BIT(Z2, MIN);
404 491
           #else
405 492
             COPY_BIT(current_endstop_bits, Z_MIN, Z2_MIN);
406 493
           #endif
407
-
408 494
           test_dual_z_endstops(Z_MIN, Z2_MIN);
409
-
410
-        #else // !Z_DUAL_ENDSTOPS
411
-
495
+        #else
412 496
           #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
413 497
             if (z_probe_enabled) UPDATE_ENDSTOP(Z, MIN);
414 498
           #else
415 499
             UPDATE_ENDSTOP(Z, MIN);
416 500
           #endif
417
-
418
-        #endif // !Z_DUAL_ENDSTOPS
419
-
420
-      #endif // HAS_Z_MIN
501
+        #endif
502
+      #endif
421 503
 
422 504
       // When closing the gap check the enabled probe
423 505
       #if ENABLED(Z_MIN_PROBE_ENDSTOP)
@@ -429,27 +511,21 @@ void Endstops::update() {
429 511
     }
430 512
     else { // Z +direction. Gantry up, bed down.
431 513
       #if HAS_Z_MAX
432
-
433 514
         // Check both Z dual endstops
434 515
         #if ENABLED(Z_DUAL_ENDSTOPS)
435
-
436 516
           UPDATE_ENDSTOP_BIT(Z, MAX);
437 517
           #if HAS_Z2_MAX
438 518
             UPDATE_ENDSTOP_BIT(Z2, MAX);
439 519
           #else
440 520
             COPY_BIT(current_endstop_bits, Z_MAX, Z2_MAX);
441 521
           #endif
442
-
443 522
           test_dual_z_endstops(Z_MAX, Z2_MAX);
444
-
445 523
         // If this pin is not hijacked for the bed probe
446 524
         // then it belongs to the Z endstop
447 525
         #elif DISABLED(Z_MIN_PROBE_ENDSTOP) || Z_MAX_PIN != Z_MIN_PROBE_PIN
448
-
449 526
           UPDATE_ENDSTOP(Z, MAX);
450
-
451
-        #endif // !Z_MIN_PROBE_PIN...
452
-      #endif // Z_MAX_PIN
527
+        #endif
528
+      #endif
453 529
     }
454 530
   }
455 531
 

+ 17
- 2
Marlin/endstops.h 파일 보기

@@ -28,6 +28,7 @@
28 28
 #define ENDSTOPS_H
29 29
 
30 30
 #include "enum.h"
31
+#include "MarlinConfig.h"
31 32
 
32 33
 class Endstops {
33 34
 
@@ -36,14 +37,22 @@ class Endstops {
36 37
     static bool enabled, enabled_globally;
37 38
     static volatile char endstop_hit_bits; // use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT value
38 39
 
39
-    #if ENABLED(Z_DUAL_ENDSTOPS)
40
+    #if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
40 41
       static uint16_t
41 42
     #else
42 43
       static byte
43 44
     #endif
44 45
         current_endstop_bits, old_endstop_bits;
45 46
 
46
-    Endstops() {};
47
+    Endstops() {
48
+      enable_globally(
49
+        #if ENABLED(ENDSTOPS_ALWAYS_ON_DEFAULT)
50
+          true
51
+        #else
52
+          false
53
+        #endif
54
+      );
55
+    };
47 56
 
48 57
     /**
49 58
      * Initialize the endstop pins
@@ -85,6 +94,12 @@ class Endstops {
85 94
 
86 95
   private:
87 96
 
97
+    #if ENABLED(X_DUAL_ENDSTOPS)
98
+      static void test_dual_x_endstops(const EndstopEnum es1, const EndstopEnum es2);
99
+    #endif
100
+    #if ENABLED(Y_DUAL_ENDSTOPS)
101
+      static void test_dual_y_endstops(const EndstopEnum es1, const EndstopEnum es2);
102
+    #endif
88 103
     #if ENABLED(Z_DUAL_ENDSTOPS)
89 104
       static void test_dual_z_endstops(const EndstopEnum es1, const EndstopEnum es2);
90 105
     #endif

+ 4
- 0
Marlin/enum.h 파일 보기

@@ -93,6 +93,10 @@ enum EndstopEnum {
93 93
   X_MAX,
94 94
   Y_MAX,
95 95
   Z_MAX,
96
+  X2_MIN,
97
+  X2_MAX,
98
+  Y2_MIN,
99
+  Y2_MAX,
96 100
   Z2_MIN,
97 101
   Z2_MAX
98 102
 };

Marlin/example_configurations/TAZ4/Configuration.h → Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h 파일 보기

@@ -37,7 +37,7 @@
37 37
  */
38 38
 #ifndef CONFIGURATION_H
39 39
 #define CONFIGURATION_H
40
-#define CONFIGURATION_H_VERSION 010100
40
+#define CONFIGURATION_H_VERSION 010107
41 41
 
42 42
 //===========================================================================
43 43
 //============================= Getting Started =============================
@@ -74,7 +74,7 @@
74 74
 // User-specified version info of this build to display in [Pronterface, etc] terminal window during
75 75
 // startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
76 76
 // build by the user have been successfully uploaded into firmware.
77
-#define STRING_CONFIG_H_AUTHOR "(Aleph Objects, Inc, TAZ  config)" // Who made the changes.
77
+#define STRING_CONFIG_H_AUTHOR "(Aleph Objects Inc, TAZ)" // Who made the changes.
78 78
 #define SHOW_BOOTSCREEN
79 79
 #define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
80 80
 #define STRING_SPLASH_LINE2 WEBSITE_URL         // will be shown during bootup in line 2
@@ -107,8 +107,9 @@
107 107
  *
108 108
  * 250000 works in most cases, but you might try a lower speed if
109 109
  * you commonly experience drop-outs during host printing.
110
+ * You may try up to 1000000 to speed up SD file transfer.
110 111
  *
111
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
112
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
112 113
  */
113 114
 #define BAUDRATE 250000
114 115
 
@@ -135,6 +136,9 @@
135 136
 // :[1, 2, 3, 4, 5]
136 137
 #define EXTRUDERS 1
137 138
 
139
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
140
+#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
141
+
138 142
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
139 143
 //#define SINGLENOZZLE
140 144
 
@@ -161,7 +165,10 @@
161 165
 //#define SWITCHING_EXTRUDER
162 166
 #if ENABLED(SWITCHING_EXTRUDER)
163 167
   #define SWITCHING_EXTRUDER_SERVO_NR 0
164
-  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1
168
+  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3]
169
+  #if EXTRUDERS > 3
170
+    #define SWITCHING_EXTRUDER_E23_SERVO_NR 1
171
+  #endif
165 172
 #endif
166 173
 
167 174
 // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles
@@ -173,6 +180,21 @@
173 180
 #endif
174 181
 
175 182
 /**
183
+ * Two separate X-carriages with extruders that connect to a moving part
184
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
185
+ */
186
+//#define PARKING_EXTRUDER
187
+#if ENABLED(PARKING_EXTRUDER)
188
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
189
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
190
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
191
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
192
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
193
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
194
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
195
+#endif
196
+
197
+/**
176 198
  * "Mixing Extruder"
177 199
  *   - Adds a new code, M165, to set the current mix factors.
178 200
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -307,6 +329,7 @@
307 329
 #define HEATER_1_MAXTEMP 250
308 330
 #define HEATER_2_MAXTEMP 250
309 331
 #define HEATER_3_MAXTEMP 250
332
+#define HEATER_4_MAXTEMP 250
310 333
 #define BED_MAXTEMP 150
311 334
 
312 335
 //===========================================================================
@@ -316,8 +339,9 @@
316 339
 
317 340
 // Comment the following line to disable PID and enable bang-bang.
318 341
 #define PIDTEMP
319
-#define BANG_MAX 70 // limits current to nozzle while in bang-bang mode; 255=full current
320
-#define PID_MAX 74 // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
342
+#define BANG_MAX 70      // Limits current to nozzle while in bang-bang mode; 255=full current
343
+#define PID_MAX  74      // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
344
+#define PID_K1 0.95      // Smoothing factor within the PID
321 345
 #if ENABLED(PIDTEMP)
322 346
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
323 347
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -327,7 +351,6 @@
327 351
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
328 352
   #define PID_FUNCTIONAL_RANGE 16 // If the temperature difference between the target temperature and the actual temperature
329 353
                                   // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
330
-  #define K1 0.95 //smoothing factor within the PID
331 354
 
332 355
   // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
333 356
   // Buda 2.0 on 24V
@@ -428,12 +451,13 @@
428 451
 //===========================================================================
429 452
 
430 453
 /**
431
- * Thermal Protection protects your printer from damage and fire if a
432
- * thermistor falls out or temperature sensors fail in any way.
454
+ * Thermal Protection provides additional protection to your printer from damage
455
+ * and fire. Marlin always includes safe min and max temperature ranges which
456
+ * protect against a broken or disconnected thermistor wire.
433 457
  *
434
- * The issue: If a thermistor falls out or a temperature sensor fails,
435
- * Marlin can no longer sense the actual temperature. Since a disconnected
436
- * thermistor reads as a low temperature, the firmware will keep the heater on.
458
+ * The issue: If a thermistor falls out, it will report the much lower
459
+ * temperature of the air in the room, and the the firmware will keep
460
+ * the heater on.
437 461
  *
438 462
  * If you get "Thermal Runaway" or "Heating failed" errors the
439 463
  * details can be tuned in Configuration_adv.h
@@ -478,13 +502,13 @@
478 502
 
479 503
 #if DISABLED(ENDSTOPPULLUPS)
480 504
   // fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined
481
-  #define ENDSTOPPULLUP_XMAX
482
-  #define ENDSTOPPULLUP_YMAX
483
-  #define ENDSTOPPULLUP_ZMAX
484
-  #define ENDSTOPPULLUP_XMIN
485
-  #define ENDSTOPPULLUP_YMIN
486
-  #define ENDSTOPPULLUP_ZMIN
487
-  #define ENDSTOPPULLUP_ZMIN_PROBE
505
+  //#define ENDSTOPPULLUP_XMAX
506
+  //#define ENDSTOPPULLUP_YMAX
507
+  //#define ENDSTOPPULLUP_ZMAX
508
+  //#define ENDSTOPPULLUP_XMIN
509
+  //#define ENDSTOPPULLUP_YMIN
510
+  //#define ENDSTOPPULLUP_ZMIN
511
+  //#define ENDSTOPPULLUP_ZMIN_PROBE
488 512
 #endif
489 513
 
490 514
 // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
@@ -573,7 +597,7 @@
573 597
 // @section probes
574 598
 
575 599
 //
576
-// See http://marlinfw.org/configuration/probes.html
600
+// See http://marlinfw.org/docs/configuration/probes.html
577 601
 //
578 602
 
579 603
 /**
@@ -639,14 +663,15 @@
639 663
 #endif
640 664
 
641 665
 /**
642
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
643
- * options selected below - will be disabled during probing so as to minimize
644
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
645
- * in current flowing through the wires).  This is likely most useful to users of the
646
- * BLTouch probe, but may also help those with inductive or other probe types.
666
+ * Enable one or more of the following if probing seems unreliable.
667
+ * Heaters and/or fans can be disabled during probing to minimize electrical
668
+ * noise. A delay can also be added to allow noise and vibration to settle.
669
+ * These options are most useful for the BLTouch probe, but may also improve
670
+ * readings with inductive probes and piezo sensors.
647 671
  */
648 672
 //#define PROBING_HEATERS_OFF       // Turn heaters off when probing
649 673
 //#define PROBING_FANS_OFF          // Turn fans off when probing
674
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
650 675
 
651 676
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
652 677
 //#define SOLENOID_PROBE
@@ -685,14 +710,16 @@
685 710
 // X and Y axis travel speed (mm/m) between probes
686 711
 #define XY_PROBE_SPEED 8000
687 712
 
688
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
713
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
689 714
 #define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
690 715
 
691 716
 // Speed for the "accurate" probe of each point
692 717
 #define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
693 718
 
694
-// Use double touch for probing
695
-//#define PROBE_DOUBLE_TOUCH
719
+// The number of probes to perform at each point.
720
+//   Set to 2 for a fast/slow probe, using the second probe result.
721
+//   Set to 3 or more for slow probes, averaging the results.
722
+//#define MULTIPLE_PROBING 2
696 723
 
697 724
 /**
698 725
  * Z probes require clearance when deploying, stowing, and moving between
@@ -759,6 +786,8 @@
759 786
 
760 787
 // @section homing
761 788
 
789
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
790
+
762 791
 //#define Z_HOMING_HEIGHT 4  // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
763 792
                              // Be sure you have this distance over your Z_MAX_POS in case.
764 793
 
@@ -770,18 +799,42 @@
770 799
 
771 800
 // @section machine
772 801
 
773
-// Travel limits after homing (units are in mm)
802
+// The size of the print bed
803
+#define X_BED_SIZE 298
804
+#define Y_BED_SIZE 275
805
+
806
+// Travel limits (mm) after homing, corresponding to endstop positions.
774 807
 #define X_MIN_POS 0
775 808
 #define Y_MIN_POS 0
776 809
 #define Z_MIN_POS 0
777
-#define X_MAX_POS 298
778
-#define Y_MAX_POS 275
810
+#define X_MAX_POS X_BED_SIZE
811
+#define Y_MAX_POS Y_BED_SIZE
779 812
 #define Z_MAX_POS 250
780 813
 
781
-// If enabled, axes won't move below MIN_POS in response to movement commands.
814
+/**
815
+ * Software Endstops
816
+ *
817
+ * - Prevent moves outside the set machine bounds.
818
+ * - Individual axes can be disabled, if desired.
819
+ * - X and Y only apply to Cartesian robots.
820
+ * - Use 'M211' to set software endstops on/off or report current state
821
+ */
822
+
823
+// Min software endstops curtail movement below minimum coordinate bounds
782 824
 #define MIN_SOFTWARE_ENDSTOPS
783
-// If enabled, axes won't move above MAX_POS in response to movement commands.
825
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
826
+  #define MIN_SOFTWARE_ENDSTOP_X
827
+  #define MIN_SOFTWARE_ENDSTOP_Y
828
+  #define MIN_SOFTWARE_ENDSTOP_Z
829
+#endif
830
+
831
+// Max software endstops curtail movement above maximum coordinate bounds
784 832
 #define MAX_SOFTWARE_ENDSTOPS
833
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
834
+  #define MAX_SOFTWARE_ENDSTOP_X
835
+  #define MAX_SOFTWARE_ENDSTOP_Y
836
+  #define MAX_SOFTWARE_ENDSTOP_Z
837
+#endif
785 838
 
786 839
 /**
787 840
  * Filament Runout Sensor
@@ -801,7 +854,7 @@
801 854
 //===========================================================================
802 855
 //=============================== Bed Leveling ==============================
803 856
 //===========================================================================
804
-// @section bedlevel
857
+// @section calibrate
805 858
 
806 859
 /**
807 860
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -827,12 +880,7 @@
827 880
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
828 881
  *   A comprehensive bed leveling system combining the features and benefits
829 882
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
830
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
831
- *   for Cartesian Printers. That said, it was primarily designed to correct
832
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
833
- *   please post an issue if something doesn't work correctly. Initially,
834
- *   you will need to set a reduced bed size so you have a rectangular area
835
- *   to test on.
883
+ *   Validation and Mesh Editing systems.
836 884
  *
837 885
  * - MESH_BED_LEVELING
838 886
  *   Probe a grid manually
@@ -859,6 +907,24 @@
859 907
   // at which point movement will be level to the machine's XY plane.
860 908
   // The height can be set with M420 Z<height>
861 909
   #define ENABLE_LEVELING_FADE_HEIGHT
910
+
911
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
912
+  // split up moves into short segments like a Delta. This follows the
913
+  // contours of the bed more closely than edge-to-edge straight moves.
914
+  #define SEGMENT_LEVELED_MOVES
915
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
916
+
917
+  /**
918
+   * Enable the G26 Mesh Validation Pattern tool.
919
+   */
920
+  //#define G26_MESH_VALIDATION   // Enable G26 mesh validation
921
+  #if ENABLED(G26_MESH_VALIDATION)
922
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
923
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
924
+    #define MESH_TEST_HOTEND_TEMP   205.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
925
+    #define MESH_TEST_BED_TEMP       60.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
926
+  #endif
927
+
862 928
 #endif
863 929
 
864 930
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -914,7 +980,9 @@
914 980
   //========================= Unified Bed Leveling ============================
915 981
   //===========================================================================
916 982
 
917
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
983
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
984
+
985
+  #define MESH_INSET 1              // Mesh inset margin on print area
918 986
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
919 987
   #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
920 988
 
@@ -925,8 +993,8 @@
925 993
   #define UBL_PROBE_PT_3_X 180
926 994
   #define UBL_PROBE_PT_3_Y 20
927 995
 
928
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
929 996
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
997
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
930 998
 
931 999
 #elif ENABLED(MESH_BED_LEVELING)
932 1000
 
@@ -953,6 +1021,9 @@
953 1021
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
954 1022
 #endif
955 1023
 
1024
+// Add a menu item to move between bed corners for manual bed adjustment
1025
+//#define LEVEL_BED_CORNERS
1026
+
956 1027
 /**
957 1028
  * Commands to execute at the end of G29 probing.
958 1029
  * Useful to retract or move the Z probe out of the way.
@@ -983,14 +1054,71 @@
983 1054
 //#define Z_SAFE_HOMING
984 1055
 
985 1056
 #if ENABLED(Z_SAFE_HOMING)
986
-  #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
987
-  #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
1057
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1058
+  #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2)    // Y point for Z homing when homing all axes (G28).
988 1059
 #endif
989 1060
 
990 1061
 // Homing speeds (mm/m)
991 1062
 #define HOMING_FEEDRATE_XY (50*60)
992 1063
 #define HOMING_FEEDRATE_Z  (8*60)
993 1064
 
1065
+// @section calibrate
1066
+
1067
+/**
1068
+ * Bed Skew Compensation
1069
+ *
1070
+ * This feature corrects for misalignment in the XYZ axes.
1071
+ *
1072
+ * Take the following steps to get the bed skew in the XY plane:
1073
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1074
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1075
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1076
+ *  4. For XY_SIDE_AD measure the edge A to D
1077
+ *
1078
+ * Marlin automatically computes skew factors from these measurements.
1079
+ * Skew factors may also be computed and set manually:
1080
+ *
1081
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1082
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1083
+ *
1084
+ * If desired, follow the same procedure for XZ and YZ.
1085
+ * Use these diagrams for reference:
1086
+ *
1087
+ *    Y                     Z                     Z
1088
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1089
+ *    |    /       /        |    /       /        |    /       /
1090
+ *    |   /       /         |   /       /         |   /       /
1091
+ *    |  A-------D          |  A-------D          |  A-------D
1092
+ *    +-------------->X     +-------------->X     +-------------->Y
1093
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1094
+ */
1095
+//#define SKEW_CORRECTION
1096
+
1097
+#if ENABLED(SKEW_CORRECTION)
1098
+  // Input all length measurements here:
1099
+  #define XY_DIAG_AC 282.8427124746
1100
+  #define XY_DIAG_BD 282.8427124746
1101
+  #define XY_SIDE_AD 200
1102
+
1103
+  // Or, set the default skew factors directly here
1104
+  // to override the above measurements:
1105
+  #define XY_SKEW_FACTOR 0.0
1106
+
1107
+  //#define SKEW_CORRECTION_FOR_Z
1108
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1109
+    #define XZ_DIAG_AC 282.8427124746
1110
+    #define XZ_DIAG_BD 282.8427124746
1111
+    #define YZ_DIAG_AC 282.8427124746
1112
+    #define YZ_DIAG_BD 282.8427124746
1113
+    #define YZ_SIDE_AD 200
1114
+    #define XZ_SKEW_FACTOR 0.0
1115
+    #define YZ_SKEW_FACTOR 0.0
1116
+  #endif
1117
+
1118
+  // Enable this option for M852 to set skew at runtime
1119
+  //#define SKEW_CORRECTION_GCODE
1120
+#endif
1121
+
994 1122
 //=============================================================================
995 1123
 //============================= Additional Features ===========================
996 1124
 //=============================================================================
@@ -1017,11 +1145,12 @@
1017 1145
 //
1018 1146
 #define HOST_KEEPALIVE_FEATURE        // Disable this if your host doesn't like keepalive messages
1019 1147
 #define DEFAULT_KEEPALIVE_INTERVAL 2  // Number of seconds between "busy" messages. Set with M113.
1148
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
1020 1149
 
1021 1150
 //
1022 1151
 // M100 Free Memory Watcher
1023 1152
 //
1024
-//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1153
+//#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
1025 1154
 
1026 1155
 //
1027 1156
 // G20/G21 Inch mode support
@@ -1166,11 +1295,11 @@
1166 1295
  *
1167 1296
  * Select the language to display on the LCD. These languages are available:
1168 1297
  *
1169
- *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
1170
- *    it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
1171
- *    zh_CN, zh_TW, test
1298
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1299
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1300
+ *    tr, uk, zh_CN, zh_TW, test
1172 1301
  *
1173
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1302
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1174 1303
  */
1175 1304
 #define LCD_LANGUAGE en
1176 1305
 
@@ -1192,7 +1321,7 @@
1192 1321
  *  - Click the controller to view the LCD menu
1193 1322
  *  - The LCD will display Japanese, Western, or Cyrillic text
1194 1323
  *
1195
- * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1324
+ * See http://marlinfw.org/docs/development/lcd_language.html
1196 1325
  *
1197 1326
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1198 1327
  */
@@ -1298,8 +1427,8 @@
1298 1427
 // Note: Test audio output with the G-Code:
1299 1428
 //  M300 S<frequency Hz> P<duration ms>
1300 1429
 //
1301
-//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
1302
-//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
1430
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
1431
+//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
1303 1432
 
1304 1433
 //
1305 1434
 // CONTROLLER TYPE: Standard
@@ -1407,11 +1536,13 @@
1407 1536
 //#define CARTESIO_UI
1408 1537
 
1409 1538
 //
1410
-// ANET_10 Controller supported displays.
1539
+// ANET and Tronxy Controller supported displays.
1411 1540
 //
1412
-//#define ANET_KEYPAD_LCD         // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1541
+//#define ZONESTAR_LCD            // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1413 1542
                                   // This LCD is known to be susceptible to electrical interference
1414 1543
                                   // which scrambles the display.  Pressing any button clears it up.
1544
+                                  // This is a LCD2004 display with 5 analog buttons.
1545
+
1415 1546
 //#define ANET_FULL_GRAPHICS_LCD  // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1416 1547
                                   // A clone of the RepRapDiscount full graphics display but with
1417 1548
                                   // different pins/wiring (see pins_ANET_10.h).
@@ -1471,11 +1602,6 @@
1471 1602
 //#define U8GLIB_SSD1306
1472 1603
 
1473 1604
 //
1474
-// TinyBoy2 128x64 OLED / Encoder Panel
1475
-//
1476
-//#define OLED_PANEL_TINYBOY2
1477
-
1478
-//
1479 1605
 // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules
1480 1606
 //
1481 1607
 //#define SAV_3DGLCD
@@ -1492,6 +1618,45 @@
1492 1618
 //
1493 1619
 //#define SAV_3DLCD
1494 1620
 
1621
+//
1622
+// TinyBoy2 128x64 OLED / Encoder Panel
1623
+//
1624
+//#define OLED_PANEL_TINYBOY2
1625
+
1626
+//
1627
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1628
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1629
+//
1630
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1631
+
1632
+//
1633
+// MKS MINI12864 with graphic controller and SD support
1634
+// http://reprap.org/wiki/MKS_MINI_12864
1635
+//
1636
+//#define MKS_MINI_12864
1637
+
1638
+//
1639
+// Factory display for Creality CR-10
1640
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1641
+//
1642
+// This is RAMPS-compatible using a single 10-pin connector.
1643
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1644
+//
1645
+//#define CR10_STOCKDISPLAY
1646
+
1647
+//
1648
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1649
+// http://reprap.org/wiki/MKS_12864OLED
1650
+//
1651
+// Tiny, but very sharp OLED display
1652
+//
1653
+//#define MKS_12864OLED
1654
+
1655
+// Silvergate GLCD controller
1656
+// http://github.com/android444/Silvergate
1657
+//
1658
+//#define SILVER_GATE_GLCD_CONTROLLER
1659
+
1495 1660
 //=============================================================================
1496 1661
 //=============================== Extra Features ==============================
1497 1662
 //=============================================================================
@@ -1548,16 +1713,22 @@
1548 1713
  * Adds the M150 command to set the LED (or LED strip) color.
1549 1714
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1550 1715
  * luminance values can be set from 0 to 255.
1716
+ * For Neopixel LED an overall brightness parameter is also available.
1551 1717
  *
1552 1718
  * *** CAUTION ***
1553 1719
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1554 1720
  *  as the Arduino cannot handle the current the LEDs will require.
1555 1721
  *  Failure to follow this precaution can destroy your Arduino!
1722
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1723
+ *  more current than the Arduino 5V linear regulator can produce.
1556 1724
  * *** CAUTION ***
1557 1725
  *
1726
+ * LED Type. Enable only one of the following two options.
1727
+ *
1558 1728
  */
1559 1729
 //#define RGB_LED
1560 1730
 //#define RGBW_LED
1731
+
1561 1732
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1562 1733
   #define RGB_LED_R_PIN 34
1563 1734
   #define RGB_LED_G_PIN 43
@@ -1565,6 +1736,17 @@
1565 1736
   #define RGB_LED_W_PIN -1
1566 1737
 #endif
1567 1738
 
1739
+// Support for Adafruit Neopixel LED driver
1740
+//#define NEOPIXEL_LED
1741
+#if ENABLED(NEOPIXEL_LED)
1742
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1743
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1744
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1745
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1746
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1747
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1748
+#endif
1749
+
1568 1750
 /**
1569 1751
  * Printer Event LEDs
1570 1752
  *
@@ -1576,68 +1758,32 @@
1576 1758
  *  - Change to green once print has finished
1577 1759
  *  - Turn off after the print has finished and the user has pushed a button
1578 1760
  */
1579
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)
1761
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1580 1762
   #define PRINTER_EVENT_LEDS
1581 1763
 #endif
1582 1764
 
1583
-/*********************************************************************\
1584
-* R/C SERVO support
1585
-* Sponsored by TrinityLabs, Reworked by codexmas
1586
-**********************************************************************/
1765
+/**
1766
+ * R/C SERVO support
1767
+ * Sponsored by TrinityLabs, Reworked by codexmas
1768
+ */
1587 1769
 
1588
-// Number of servos
1589
-//
1590
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1591
-// set it manually if you have more servos than extruders and wish to manually control some
1592
-// leaving it undefined or defining as 0 will disable the servo subsystem
1593
-// If unsure, leave commented / disabled
1594
-//
1770
+/**
1771
+ * Number of servos
1772
+ *
1773
+ * For some servo-related options NUM_SERVOS will be set automatically.
1774
+ * Set this manually if there are extra servos needing manual control.
1775
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1776
+ */
1595 1777
 //#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
1596 1778
 
1597 1779
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1598 1780
 // 300ms is a good value but you can try less delay.
1599 1781
 // If the servo can't reach the requested position, increase it.
1600
-#define SERVO_DELAY 300
1782
+#define SERVO_DELAY { 300 }
1601 1783
 
1602 1784
 // Servo deactivation
1603 1785
 //
1604 1786
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1605 1787
 //#define DEACTIVATE_SERVOS_AFTER_MOVE
1606 1788
 
1607
-/**
1608
- * Filament Width Sensor
1609
- *
1610
- * Measures the filament width in real-time and adjusts
1611
- * flow rate to compensate for any irregularities.
1612
- *
1613
- * Also allows the measured filament diameter to set the
1614
- * extrusion rate, so the slicer only has to specify the
1615
- * volume.
1616
- *
1617
- * Only a single extruder is supported at this time.
1618
- *
1619
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1620
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1621
- * 301 RAMBO       : Analog input 3
1622
- *
1623
- * Note: May require analog pins to be defined for other boards.
1624
- */
1625
-//#define FILAMENT_WIDTH_SENSOR
1626
-
1627
-#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00   // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
1628
-
1629
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1630
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1631
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1632
-
1633
-  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1634
-  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1635
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1636
-
1637
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1638
-
1639
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1640
-  //#define FILAMENT_LCD_DISPLAY
1641
-#endif
1642
-
1643 1789
 #endif // CONFIGURATION_H

Marlin/example_configurations/TAZ4/Configuration_adv.h → Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h 파일 보기

@@ -32,7 +32,7 @@
32 32
  */
33 33
 #ifndef CONFIGURATION_ADV_H
34 34
 #define CONFIGURATION_ADV_H
35
-#define CONFIGURATION_ADV_H_VERSION 010100
35
+#define CONFIGURATION_ADV_H_VERSION 010107
36 36
 
37 37
 // @section temperature
38 38
 
@@ -48,31 +48,36 @@
48 48
 #endif
49 49
 
50 50
 /**
51
- * Thermal Protection protects your printer from damage and fire if a
52
- * thermistor falls out or temperature sensors fail in any way.
51
+ * Thermal Protection provides additional protection to your printer from damage
52
+ * and fire. Marlin always includes safe min and max temperature ranges which
53
+ * protect against a broken or disconnected thermistor wire.
53 54
  *
54
- * The issue: If a thermistor falls out or a temperature sensor fails,
55
- * Marlin can no longer sense the actual temperature. Since a disconnected
56
- * thermistor reads as a low temperature, the firmware will keep the heater on.
55
+ * The issue: If a thermistor falls out, it will report the much lower
56
+ * temperature of the air in the room, and the the firmware will keep
57
+ * the heater on.
57 58
  *
58 59
  * The solution: Once the temperature reaches the target, start observing.
59
- * If the temperature stays too far below the target (hysteresis) for too long (period),
60
- * the firmware will halt the machine as a safety precaution.
60
+ * If the temperature stays too far below the target (hysteresis) for too
61
+ * long (period), the firmware will halt the machine as a safety precaution.
61 62
  *
62
- * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63
+ * If you get false positives for "Thermal Runaway", increase
64
+ * THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63 65
  */
64 66
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
65 67
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
66 68
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
67 69
 
68 70
   /**
69
-   * Whenever an M104 or M109 increases the target temperature the firmware will wait for the
70
-   * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
71
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
72
-   * but only if the current temperature is far enough below the target for a reliable test.
71
+   * Whenever an M104, M109, or M303 increases the target temperature, the
72
+   * firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
73
+   * hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
74
+   * requires a hard reset. This test restarts with any M104/M109/M303, but only
75
+   * if the current temperature is far enough below the target for a reliable
76
+   * test.
73 77
    *
74
-   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
75
-   * WATCH_TEMP_INCREASE should not be below 2.
78
+   * If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
79
+   * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
80
+   * below 2.
76 81
    */
77 82
   #define WATCH_TEMP_PERIOD 20                // Seconds
78 83
   #define WATCH_TEMP_INCREASE 2               // Degrees Celsius
@@ -86,13 +91,7 @@
86 91
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
87 92
 
88 93
   /**
89
-   * Whenever an M140 or M190 increases the target temperature the firmware will wait for the
90
-   * WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
91
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
92
-   * but only if the current temperature is far enough below the target for a reliable test.
93
-   *
94
-   * If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
95
-   * WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
94
+   * As described above, except for the bed (M140/M190/M303).
96 95
    */
97 96
   #define WATCH_BED_TEMP_PERIOD 60                // Seconds
98 97
   #define WATCH_BED_TEMP_INCREASE 2               // Degrees Celsius
@@ -123,6 +122,9 @@
123 122
   #define AUTOTEMP_OLDWEIGHT 0.98
124 123
 #endif
125 124
 
125
+// Show extra position information in M114
126
+//#define M114_DETAIL
127
+
126 128
 // Show Temperature ADC value
127 129
 // Enable for M105 to include ADC values read from temperature sensors.
128 130
 //#define SHOW_TEMP_ADC_VALUES
@@ -221,6 +223,17 @@
221 223
 #define EXTRUDER_AUTO_FAN_SPEED   255  // == full speed
222 224
 
223 225
 /**
226
+ * Part-Cooling Fan Multiplexer
227
+ *
228
+ * This feature allows you to digitally multiplex the fan output.
229
+ * The multiplexer is automatically switched at tool-change.
230
+ * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans.
231
+ */
232
+#define FANMUX0_PIN -1
233
+#define FANMUX1_PIN -1
234
+#define FANMUX2_PIN -1
235
+
236
+/**
224 237
  * M355 Case Light on-off / brightness
225 238
  */
226 239
 //#define CASE_LIGHT_ENABLE
@@ -246,48 +259,49 @@
246 259
 
247 260
 //#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
248 261
 
249
-// Dual X Steppers
250
-// Uncomment this option to drive two X axis motors.
251
-// The next unused E driver will be assigned to the second X stepper.
262
+/**
263
+ * Dual Steppers / Dual Endstops
264
+ *
265
+ * This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
266
+ *
267
+ * For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
268
+ * spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
269
+ * set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
270
+ * that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
271
+ *
272
+ * Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
273
+ * this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
274
+ * in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
275
+ */
276
+
252 277
 //#define X_DUAL_STEPPER_DRIVERS
253 278
 #if ENABLED(X_DUAL_STEPPER_DRIVERS)
254
-  // Set true if the two X motors need to rotate in opposite directions
255
-  #define INVERT_X2_VS_X_DIR true
279
+  #define INVERT_X2_VS_X_DIR true   // Set 'true' if X motors should rotate in opposite directions
280
+  //#define X_DUAL_ENDSTOPS
281
+  #if ENABLED(X_DUAL_ENDSTOPS)
282
+    #define X2_USE_ENDSTOP _XMAX_
283
+    #define X_DUAL_ENDSTOPS_ADJUSTMENT  0
284
+  #endif
256 285
 #endif
257 286
 
258
-// Dual Y Steppers
259
-// Uncomment this option to drive two Y axis motors.
260
-// The next unused E driver will be assigned to the second Y stepper.
261 287
 //#define Y_DUAL_STEPPER_DRIVERS
262 288
 #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
263
-  // Set true if the two Y motors need to rotate in opposite directions
264
-  #define INVERT_Y2_VS_Y_DIR true
289
+  #define INVERT_Y2_VS_Y_DIR true   // Set 'true' if Y motors should rotate in opposite directions
290
+  //#define Y_DUAL_ENDSTOPS
291
+  #if ENABLED(Y_DUAL_ENDSTOPS)
292
+    #define Y2_USE_ENDSTOP _YMAX_
293
+    #define Y_DUAL_ENDSTOPS_ADJUSTMENT  0
294
+  #endif
265 295
 #endif
266 296
 
267
-// A single Z stepper driver is usually used to drive 2 stepper motors.
268
-// Uncomment this option to use a separate stepper driver for each Z axis motor.
269
-// The next unused E driver will be assigned to the second Z stepper.
270 297
 //#define Z_DUAL_STEPPER_DRIVERS
271
-
272 298
 #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
273
-
274
-  // Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper.
275
-  // That way the machine is capable to align the bed during home, since both Z steppers are homed.
276
-  // There is also an implementation of M666 (software endstops adjustment) to this feature.
277
-  // After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
278
-  // One just need to home the Z axis and measure the distance difference between both Z axis and apply the math: Z adjust = Z - Z2.
279
-  // If the Z stepper axis is closer to the bed, the measure Z > Z2 (yes, it is.. think about it) and the Z adjust would be positive.
280
-  // Play a little bit with small adjustments (0.5mm) and check the behaviour.
281
-  // The M119 (endstops report) will start reporting the Z2 Endstop as well.
282
-
283 299
   //#define Z_DUAL_ENDSTOPS
284
-
285 300
   #if ENABLED(Z_DUAL_ENDSTOPS)
286 301
     #define Z2_USE_ENDSTOP _XMAX_
287
-    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0  // use M666 command to determine this value
302
+    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0
288 303
   #endif
289
-
290
-#endif // Z_DUAL_STEPPER_DRIVERS
304
+#endif
291 305
 
292 306
 // Enable this for dual x-carriage printers.
293 307
 // A dual x-carriage design has the advantage that the inactive extruder can be parked which
@@ -334,12 +348,12 @@
334 348
 
335 349
 // @section homing
336 350
 
337
-//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
351
+// Homing hits each endstop, retracts by these distances, then does a slower bump.
338 352
 #define X_HOME_BUMP_MM 5
339 353
 #define Y_HOME_BUMP_MM 5
340 354
 #define Z_HOME_BUMP_MM 4
341
-#define HOMING_BUMP_DIVISOR {2, 2, 4}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
342
-#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
355
+#define HOMING_BUMP_DIVISOR { 2, 2, 4 }  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
356
+#define QUICK_HOME                       // If homing includes X and Y, do a diagonal move initially
343 357
 
344 358
 // When G28 is called, this option will make Y home before X
345 359
 //#define HOME_Y_BEFORE_X
@@ -394,7 +408,7 @@
394 408
 // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
395 409
 // of the buffer and all stops. This should not be much greater than zero and should only be changed
396 410
 // if unwanted behavior is observed on a user's machine when running at very slow speeds.
397
-#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
411
+#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
398 412
 
399 413
 // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
400 414
 #define MICROSTEP_MODES {16,16,4,16,16} // [1,2,4,8,16]
@@ -423,8 +437,21 @@
423 437
 //#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 }   // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
424 438
 //#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 }    // Default drive percent - X, Y, Z, E axis
425 439
 
426
-// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
440
+// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
427 441
 //#define DIGIPOT_I2C
442
+#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
443
+  /**
444
+   * Common slave addresses:
445
+   *
446
+   *                    A   (A shifted)   B   (B shifted)  IC
447
+   * Smoothie          0x2C (0x58)       0x2D (0x5A)       MCP4451
448
+   * AZTEEG_X3_PRO     0x2C (0x58)       0x2E (0x5C)       MCP4451
449
+   * MIGHTYBOARD_REVE  0x2F (0x5E)                         MCP4018
450
+   */
451
+  #define DIGIPOT_I2C_ADDRESS_A 0x2C  // unshifted slave address for first DIGIPOT
452
+  #define DIGIPOT_I2C_ADDRESS_B 0x2D  // unshifted slave address for second DIGIPOT
453
+#endif
454
+
428 455
 //#define DIGIPOT_MCP4018          // Requires library from https://github.com/stawel/SlowSoftI2CMaster
429 456
 #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4     AZTEEG_X3_PRO: 8
430 457
 // Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
@@ -452,6 +479,26 @@
452 479
 // On the Info Screen, display XY with one decimal place when possible
453 480
 //#define LCD_DECIMAL_SMALL_XY
454 481
 
482
+// The timeout (in ms) to return to the status screen from sub-menus
483
+//#define LCD_TIMEOUT_TO_STATUS 15000
484
+
485
+/**
486
+ * LED Control Menu
487
+ * Enable this feature to add LED Control to the LCD menu
488
+ */
489
+//#define LED_CONTROL_MENU
490
+#if ENABLED(LED_CONTROL_MENU)
491
+  #define LED_COLOR_PRESETS                 // Enable the Preset Color menu option
492
+  #if ENABLED(LED_COLOR_PRESETS)
493
+    #define LED_USER_PRESET_RED        255  // User defined RED value
494
+    #define LED_USER_PRESET_GREEN      128  // User defined GREEN value
495
+    #define LED_USER_PRESET_BLUE         0  // User defined BLUE value
496
+    #define LED_USER_PRESET_WHITE      255  // User defined WHITE value
497
+    #define LED_USER_PRESET_BRIGHTNESS 255  // User defined intensity
498
+    //#define LED_USER_PRESET_STARTUP       // Have the printer display the user preset color on startup
499
+  #endif
500
+#endif // LED_CONTROL_MENU
501
+
455 502
 #if ENABLED(SDSUPPORT)
456 503
 
457 504
   // Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -461,12 +508,14 @@
461 508
   // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
462 509
   #define SD_DETECT_INVERTED
463 510
 
464
-  #define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
511
+  #define SD_FINISHED_STEPPERRELEASE true          // Disable steppers when SD Print is finished
465 512
   #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
466 513
 
467
-  #define SDCARD_RATHERRECENTFIRST  //reverse file order of sd card menu display. Its sorted practically after the file system block order.
468
-  // if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that.
469
-  // using:
514
+  // Reverse SD sort to show "more recent" files first, according to the card's FAT.
515
+  // Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
516
+  #define SDCARD_RATHERRECENTFIRST
517
+
518
+  // Add an option in the menu to run all auto#.g files
470 519
   //#define MENU_ADDAUTOSTART
471 520
 
472 521
   /**
@@ -496,13 +545,15 @@
496 545
 
497 546
   // SD Card Sorting options
498 547
   #if ENABLED(SDCARD_SORT_ALPHA)
499
-    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256).
548
+    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256). Costs 27 bytes each.
500 549
     #define FOLDER_SORTING     -1     // -1=above  0=none  1=below
501 550
     #define SDSORT_GCODE       false  // Allow turning sorting on/off with LCD and M34 g-code.
502 551
     #define SDSORT_USES_RAM    false  // Pre-allocate a static array for faster pre-sorting.
503 552
     #define SDSORT_USES_STACK  false  // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
504 553
     #define SDSORT_CACHE_NAMES false  // Keep sorted items in RAM longer for speedy performance. Most expensive option.
505 554
     #define SDSORT_DYNAMIC_RAM false  // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
555
+    #define SDSORT_CACHE_VFATS 2      // Maximum number of 13-byte VFAT entries to use for sorting.
556
+                                      // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
506 557
   #endif
507 558
 
508 559
   // Show a progress bar on HD44780 LCDs for SD printing
@@ -521,14 +572,29 @@
521 572
     //#define LCD_PROGRESS_BAR_TEST
522 573
   #endif
523 574
 
575
+  // Add an 'M73' G-code to set the current percentage
576
+  //#define LCD_SET_PROGRESS_MANUALLY
577
+
524 578
   // This allows hosts to request long names for files and folders with M33
525 579
   //#define LONG_FILENAME_HOST_SUPPORT
526 580
 
527
-  // This option allows you to abort SD printing when any endstop is triggered.
528
-  // This feature must be enabled with "M540 S1" or from the LCD menu.
529
-  // To have any effect, endstops must be enabled during SD printing.
581
+  // Enable this option to scroll long filenames in the SD card menu
582
+  //#define SCROLL_LONG_FILENAMES
583
+
584
+  /**
585
+   * This option allows you to abort SD printing when any endstop is triggered.
586
+   * This feature must be enabled with "M540 S1" or from the LCD menu.
587
+   * To have any effect, endstops must be enabled during SD printing.
588
+   */
530 589
   //#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
531 590
 
591
+  /**
592
+   * This option makes it easier to print the same SD Card file again.
593
+   * On print completion the LCD Menu will open with the file selected.
594
+   * You can just click to start the print, or navigate elsewhere.
595
+   */
596
+  //#define SD_REPRINT_LAST_SELECTED_FILE
597
+
532 598
 #endif // SDSUPPORT
533 599
 
534 600
 /**
@@ -561,6 +627,10 @@
561 627
   // Enable this option and reduce the value to optimize screen updates.
562 628
   // The normal delay is 10µs. Use the lowest value that still gives a reliable display.
563 629
   //#define DOGM_SPI_DELAY_US 5
630
+
631
+  // Swap the CW/CCW indicators in the graphics overlay
632
+  //#define OVERLAY_GFX_REVERSE
633
+
564 634
 #endif // DOGLCD
565 635
 
566 636
 // @section safety
@@ -587,31 +657,18 @@
587 657
  */
588 658
 //#define BABYSTEPPING
589 659
 #if ENABLED(BABYSTEPPING)
590
-  #define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
591
-  #define BABYSTEP_INVERT_Z false  // Change if Z babysteps should go the other way
592
-  #define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
593
-  //#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
660
+  //#define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
661
+  #define BABYSTEP_INVERT_Z false    // Change if Z babysteps should go the other way
662
+  #define BABYSTEP_MULTIPLICATOR 1   // Babysteps are very small. Increase for faster motion.
663
+  //#define BABYSTEP_ZPROBE_OFFSET   // Enable to combine M851 and Babystepping
594 664
   //#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
595 665
   #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
596 666
                                         // Note: Extra time may be added to mitigate controller latency.
667
+  //#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
597 668
 #endif
598 669
 
599 670
 // @section extruder
600 671
 
601
-// extruder advance constant (s2/mm3)
602
-//
603
-// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
604
-//
605
-// Hooke's law says:    force = k * distance
606
-// Bernoulli's principle says:  v ^ 2 / 2 + g . h + pressure / density = constant
607
-// so: v ^ 2 is proportional to number of steps we advance the extruder
608
-//#define ADVANCE
609
-
610
-#if ENABLED(ADVANCE)
611
-  #define EXTRUDER_ADVANCE_K .0
612
-  #define D_FILAMENT 2.85
613
-#endif
614
-
615 672
 /**
616 673
  * Implementation of linear pressure control
617 674
  *
@@ -645,7 +702,7 @@
645 702
    *
646 703
    * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
647 704
    *
648
-   * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode.
705
+   * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
649 706
    * Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
650 707
    */
651 708
   #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
@@ -654,19 +711,18 @@
654 711
 
655 712
 // @section leveling
656 713
 
657
-// Default mesh area is an area with an inset margin on the print area.
658
-// Below are the macros that are used to define the borders for the mesh area,
659
-// made available here for specialized needs, ie dual extruder setup.
660
-#if ENABLED(MESH_BED_LEVELING)
661
-  #define MESH_MIN_X (X_MIN_POS + MESH_INSET)
662
-  #define MESH_MAX_X (X_MAX_POS - (MESH_INSET))
663
-  #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET)
664
-  #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET))
665
-#elif ENABLED(AUTO_BED_LEVELING_UBL)
666
-  #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET)
667
-  #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET))
668
-  #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET)
669
-  #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET))
714
+#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
715
+  #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
716
+#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
717
+  #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
718
+#endif
719
+
720
+#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
721
+  // Override the mesh area if the automatic (max) area is too large
722
+  //#define MESH_MIN_X MESH_INSET
723
+  //#define MESH_MIN_Y MESH_INSET
724
+  //#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
725
+  //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
670 726
 #endif
671 727
 
672 728
 // @section extras
@@ -686,7 +742,7 @@
686 742
 //#define BEZIER_CURVE_SUPPORT
687 743
 
688 744
 // G38.2 and G38.3 Probe Target
689
-// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
745
+// Set MULTIPLE_PROBING if you want G38 to double touch
690 746
 //#define G38_PROBE_TARGET
691 747
 #if ENABLED(G38_PROBE_TARGET)
692 748
   #define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
@@ -711,7 +767,7 @@
711 767
 // @section hidden
712 768
 
713 769
 // The number of linear motions that can be in the plan at any give time.
714
-// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
770
+// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
715 771
 #if ENABLED(SDSUPPORT)
716 772
   #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
717 773
 #else
@@ -724,7 +780,7 @@
724 780
 #define MAX_CMD_SIZE 96
725 781
 #define BUFSIZE 4
726 782
 
727
-// Transfer Buffer Size
783
+// Transmission to Host Buffer Size
728 784
 // To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0.
729 785
 // To buffer a simple "ok" you need 4 bytes.
730 786
 // For ADVANCED_OK (M105) you need 32 bytes.
@@ -733,6 +789,28 @@
733 789
 // :[0, 2, 4, 8, 16, 32, 64, 128, 256]
734 790
 #define TX_BUFFER_SIZE 0
735 791
 
792
+// Host Receive Buffer Size
793
+// Without XON/XOFF flow control (see SERIAL_XON_XOFF below) 32 bytes should be enough.
794
+// To use flow control, set this buffer size to at least 1024 bytes.
795
+// :[0, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048]
796
+//#define RX_BUFFER_SIZE 1024
797
+
798
+#if RX_BUFFER_SIZE >= 1024
799
+  // Enable to have the controller send XON/XOFF control characters to
800
+  // the host to signal the RX buffer is becoming full.
801
+  //#define SERIAL_XON_XOFF
802
+#endif
803
+
804
+#if ENABLED(SDSUPPORT)
805
+  // Enable this option to collect and display the maximum
806
+  // RX queue usage after transferring a file to SD.
807
+  //#define SERIAL_STATS_MAX_RX_QUEUED
808
+
809
+  // Enable this option to collect and display the number
810
+  // of dropped bytes after a file transfer to SD.
811
+  //#define SERIAL_STATS_DROPPED_RX
812
+#endif
813
+
736 814
 // Enable an emergency-command parser to intercept certain commands as they
737 815
 // enter the serial receive buffer, so they cannot be blocked.
738 816
 // Currently handles M108, M112, M410
@@ -748,27 +826,47 @@
748 826
 // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary.
749 827
 //#define ADVANCED_OK
750 828
 
751
-// @section fwretract
752
-
753
-// Firmware based and LCD controlled retract
754
-// M207 and M208 can be used to define parameters for the retraction.
755
-// The retraction can be called by the slicer using G10 and G11
756
-// until then, intended retractions can be detected by moves that only extrude and the direction.
757
-// the moves are than replaced by the firmware controlled ones.
829
+// @section extras
758 830
 
759
-//#define FWRETRACT  //ONLY PARTIALLY TESTED
831
+/**
832
+ * Firmware-based and LCD-controlled retract
833
+ *
834
+ * Add G10 / G11 commands for automatic firmware-based retract / recover.
835
+ * Use M207 and M208 to define parameters for retract / recover.
836
+ *
837
+ * Use M209 to enable or disable auto-retract.
838
+ * With auto-retract enabled, all G1 E moves within the set range
839
+ * will be converted to firmware-based retract/recover moves.
840
+ *
841
+ * Be sure to turn off auto-retract during filament change.
842
+ *
843
+ * Note that M207 / M208 / M209 settings are saved to EEPROM.
844
+ *
845
+ */
846
+//#define FWRETRACT  // ONLY PARTIALLY TESTED
760 847
 #if ENABLED(FWRETRACT)
761
-  #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
762
-  #define RETRACT_LENGTH 3               //default retract length (positive mm)
763
-  #define RETRACT_LENGTH_SWAP 13         //default swap retract length (positive mm), for extruder change
764
-  #define RETRACT_FEEDRATE 45            //default feedrate for retracting (mm/s)
765
-  #define RETRACT_ZLIFT 0                //default retract Z-lift
766
-  #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
767
-  #define RETRACT_RECOVER_LENGTH_SWAP 0  //default additional swap recover length (mm, added to retract length when recovering from extruder change)
768
-  #define RETRACT_RECOVER_FEEDRATE 8     //default feedrate for recovering from retraction (mm/s)
848
+  #define MIN_AUTORETRACT 0.1             // When auto-retract is on, convert E moves of this length and over
849
+  #define MAX_AUTORETRACT 10.0            // Upper limit for auto-retract conversion
850
+  #define RETRACT_LENGTH 3                // Default retract length (positive mm)
851
+  #define RETRACT_LENGTH_SWAP 13          // Default swap retract length (positive mm), for extruder change
852
+  #define RETRACT_FEEDRATE 45             // Default feedrate for retracting (mm/s)
853
+  #define RETRACT_ZLIFT 0                 // Default retract Z-lift
854
+  #define RETRACT_RECOVER_LENGTH 0        // Default additional recover length (mm, added to retract length when recovering)
855
+  #define RETRACT_RECOVER_LENGTH_SWAP 0   // Default additional swap recover length (mm, added to retract length when recovering from extruder change)
856
+  #define RETRACT_RECOVER_FEEDRATE 8      // Default feedrate for recovering from retraction (mm/s)
857
+  #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
769 858
 #endif
770 859
 
771 860
 /**
861
+ * Extra Fan Speed
862
+ * Adds a secondary fan speed for each print-cooling fan.
863
+ *   'M106 P<fan> T3-255' : Set a secondary speed for <fan>
864
+ *   'M106 P<fan> T2'     : Use the set secondary speed
865
+ *   'M106 P<fan> T1'     : Restore the previous fan speed
866
+ */
867
+//#define EXTRA_FAN_SPEED
868
+
869
+/**
772 870
  * Advanced Pause
773 871
  * Experimental feature for filament change support and for parking the nozzle when paused.
774 872
  * Adds the GCode M600 for initiating filament change.
@@ -878,7 +976,7 @@
878 976
 
879 977
 #endif
880 978
 
881
-// @section TMC2130
979
+// @section TMC2130, TMC2208
882 980
 
883 981
 /**
884 982
  * Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
@@ -892,7 +990,19 @@
892 990
  */
893 991
 //#define HAVE_TMC2130
894 992
 
895
-#if ENABLED(HAVE_TMC2130)
993
+/**
994
+ * Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
995
+ * Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
996
+ * To use the reading capabilities, also connect #_SERIAL_RX_PIN
997
+ * to #_SERIAL_TX_PIN with a 1K resistor.
998
+ * The drivers can also be used with hardware serial.
999
+ *
1000
+ * You'll also need the TMC2208Stepper Arduino library
1001
+ * (https://github.com/teemuatlut/TMC2208Stepper).
1002
+ */
1003
+//#define HAVE_TMC2208
1004
+
1005
+#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
896 1006
 
897 1007
   // CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
898 1008
   //#define X_IS_TMC2130
@@ -907,46 +1017,58 @@
907 1017
   //#define E3_IS_TMC2130
908 1018
   //#define E4_IS_TMC2130
909 1019
 
1020
+  //#define X_IS_TMC2208
1021
+  //#define X2_IS_TMC2208
1022
+  //#define Y_IS_TMC2208
1023
+  //#define Y2_IS_TMC2208
1024
+  //#define Z_IS_TMC2208
1025
+  //#define Z2_IS_TMC2208
1026
+  //#define E0_IS_TMC2208
1027
+  //#define E1_IS_TMC2208
1028
+  //#define E2_IS_TMC2208
1029
+  //#define E3_IS_TMC2208
1030
+  //#define E4_IS_TMC2208
1031
+
910 1032
   /**
911 1033
    * Stepper driver settings
912 1034
    */
913 1035
 
914 1036
   #define R_SENSE           0.11  // R_sense resistor for SilentStepStick2130
915 1037
   #define HOLD_MULTIPLIER    0.5  // Scales down the holding current from run current
916
-  #define INTERPOLATE          1  // Interpolate X/Y/Z_MICROSTEPS to 256
1038
+  #define INTERPOLATE       true  // Interpolate X/Y/Z_MICROSTEPS to 256
917 1039
 
918
-  #define X_CURRENT         1000  // rms current in mA. Multiply by 1.41 for peak current.
1040
+  #define X_CURRENT          800  // rms current in mA. Multiply by 1.41 for peak current.
919 1041
   #define X_MICROSTEPS        16  // 0..256
920 1042
 
921
-  #define Y_CURRENT         1000
1043
+  #define Y_CURRENT          800
922 1044
   #define Y_MICROSTEPS        16
923 1045
 
924
-  #define Z_CURRENT         1000
1046
+  #define Z_CURRENT          800
925 1047
   #define Z_MICROSTEPS        16
926 1048
 
927
-  //#define X2_CURRENT      1000
928
-  //#define X2_MICROSTEPS     16
1049
+  #define X2_CURRENT         800
1050
+  #define X2_MICROSTEPS       16
929 1051
 
930
-  //#define Y2_CURRENT      1000
931
-  //#define Y2_MICROSTEPS     16
1052
+  #define Y2_CURRENT         800
1053
+  #define Y2_MICROSTEPS       16
932 1054
 
933
-  //#define Z2_CURRENT      1000
934
-  //#define Z2_MICROSTEPS     16
1055
+  #define Z2_CURRENT         800
1056
+  #define Z2_MICROSTEPS       16
935 1057
 
936
-  //#define E0_CURRENT      1000
937
-  //#define E0_MICROSTEPS     16
1058
+  #define E0_CURRENT         800
1059
+  #define E0_MICROSTEPS       16
938 1060
 
939
-  //#define E1_CURRENT      1000
940
-  //#define E1_MICROSTEPS     16
1061
+  #define E1_CURRENT         800
1062
+  #define E1_MICROSTEPS       16
941 1063
 
942
-  //#define E2_CURRENT      1000
943
-  //#define E2_MICROSTEPS     16
1064
+  #define E2_CURRENT         800
1065
+  #define E2_MICROSTEPS       16
944 1066
 
945
-  //#define E3_CURRENT      1000
946
-  //#define E3_MICROSTEPS     16
1067
+  #define E3_CURRENT         800
1068
+  #define E3_MICROSTEPS       16
947 1069
 
948
-  //#define E4_CURRENT      1000
949
-  //#define E4_MICROSTEPS     16
1070
+  #define E4_CURRENT         800
1071
+  #define E4_MICROSTEPS       16
950 1072
 
951 1073
   /**
952 1074
    * Use Trinamic's ultra quiet stepping mode.
@@ -955,24 +1077,22 @@
955 1077
   #define STEALTHCHOP
956 1078
 
957 1079
   /**
958
-   * Let Marlin automatically control stepper current.
959
-   * This is still an experimental feature.
960
-   * Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
961
-   * then decrease current by CURRENT_STEP until temperature prewarn is cleared.
962
-   * Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
1080
+   * Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
1081
+   * like overtemperature and short to ground. TMC2208 requires hardware serial.
1082
+   * In the case of overtemperature Marlin can decrease the driver current until error condition clears.
1083
+   * Other detected conditions can be used to stop the current print.
963 1084
    * Relevant g-codes:
964 1085
    * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
965
-   * M906 S1 - Start adjusting current
966
-   * M906 S0 - Stop adjusting current
967 1086
    * M911 - Report stepper driver overtemperature pre-warn condition.
968 1087
    * M912 - Clear stepper driver overtemperature pre-warn condition flag.
1088
+   * M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
969 1089
    */
970
-  //#define AUTOMATIC_CURRENT_CONTROL
1090
+  //#define MONITOR_DRIVER_STATUS
971 1091
 
972
-  #if ENABLED(AUTOMATIC_CURRENT_CONTROL)
973
-    #define CURRENT_STEP          50  // [mA]
974
-    #define AUTO_ADJUST_MAX     1300  // [mA], 1300mA_rms = 1840mA_peak
1092
+  #if ENABLED(MONITOR_DRIVER_STATUS)
1093
+    #define CURRENT_STEP_DOWN     50  // [mA]
975 1094
     #define REPORT_CURRENT_CHANGE
1095
+    #define STOP_ON_ERROR
976 1096
   #endif
977 1097
 
978 1098
   /**
@@ -987,8 +1107,8 @@
987 1107
   #define X2_HYBRID_THRESHOLD    100
988 1108
   #define Y_HYBRID_THRESHOLD     100
989 1109
   #define Y2_HYBRID_THRESHOLD    100
990
-  #define Z_HYBRID_THRESHOLD       4
991
-  #define Z2_HYBRID_THRESHOLD      4
1110
+  #define Z_HYBRID_THRESHOLD       3
1111
+  #define Z2_HYBRID_THRESHOLD      3
992 1112
   #define E0_HYBRID_THRESHOLD     30
993 1113
   #define E1_HYBRID_THRESHOLD     30
994 1114
   #define E2_HYBRID_THRESHOLD     30
@@ -998,7 +1118,7 @@
998 1118
   /**
999 1119
    * Use stallGuard2 to sense an obstacle and trigger an endstop.
1000 1120
    * You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
1001
-   * If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
1121
+   * X and Y homing will always be done in spreadCycle mode.
1002 1122
    *
1003 1123
    * X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
1004 1124
    * Higher values make the system LESS sensitive.
@@ -1007,27 +1127,34 @@
1007 1127
    * It is advised to set X/Y_HOME_BUMP_MM to 0.
1008 1128
    * M914 X/Y to live tune the setting
1009 1129
    */
1010
-  //#define SENSORLESS_HOMING
1130
+  //#define SENSORLESS_HOMING // TMC2130 only
1011 1131
 
1012 1132
   #if ENABLED(SENSORLESS_HOMING)
1013
-    #define X_HOMING_SENSITIVITY  19
1014
-    #define Y_HOMING_SENSITIVITY  19
1133
+    #define X_HOMING_SENSITIVITY  8
1134
+    #define Y_HOMING_SENSITIVITY  8
1015 1135
   #endif
1016 1136
 
1017 1137
   /**
1138
+   * Enable M122 debugging command for TMC stepper drivers.
1139
+   * M122 S0/1 will enable continous reporting.
1140
+   */
1141
+  //#define TMC_DEBUG
1142
+
1143
+  /**
1018 1144
    * You can set your own advanced settings by filling in predefined functions.
1019 1145
    * A list of available functions can be found on the library github page
1020 1146
    * https://github.com/teemuatlut/TMC2130Stepper
1147
+   * https://github.com/teemuatlut/TMC2208Stepper
1021 1148
    *
1022 1149
    * Example:
1023
-   * #define TMC2130_ADV() { \
1150
+   * #define TMC_ADV() { \
1024 1151
    *   stepperX.diag0_temp_prewarn(1); \
1025
-   *   stepperX.interpolate(0); \
1152
+   *   stepperY.interpolate(0); \
1026 1153
    * }
1027 1154
    */
1028
-  #define  TMC2130_ADV() {  }
1155
+  #define  TMC_ADV() {  }
1029 1156
 
1030
-#endif // HAVE_TMC2130
1157
+#endif // TMC2130 || TMC2208
1031 1158
 
1032 1159
 // @section L6470
1033 1160
 
@@ -1192,6 +1319,48 @@
1192 1319
 #endif
1193 1320
 
1194 1321
 /**
1322
+ * Filament Width Sensor
1323
+ *
1324
+ * Measures the filament width in real-time and adjusts
1325
+ * flow rate to compensate for any irregularities.
1326
+ *
1327
+ * Also allows the measured filament diameter to set the
1328
+ * extrusion rate, so the slicer only has to specify the
1329
+ * volume.
1330
+ *
1331
+ * Only a single extruder is supported at this time.
1332
+ *
1333
+ *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1334
+ *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1335
+ * 301 RAMBO       : Analog input 3
1336
+ *
1337
+ * Note: May require analog pins to be defined for other boards.
1338
+ */
1339
+//#define FILAMENT_WIDTH_SENSOR
1340
+
1341
+#if ENABLED(FILAMENT_WIDTH_SENSOR)
1342
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
1343
+  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1344
+
1345
+  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1346
+  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1347
+  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1348
+
1349
+  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1350
+
1351
+  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1352
+  //#define FILAMENT_LCD_DISPLAY
1353
+#endif
1354
+
1355
+/**
1356
+ * CNC Coordinate Systems
1357
+ *
1358
+ * Enables G53 and G54-G59.3 commands to select coordinate systems
1359
+ * and G92.1 to reset the workspace to native machine space.
1360
+ */
1361
+//#define CNC_COORDINATE_SYSTEMS
1362
+
1363
+/**
1195 1364
  * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
1196 1365
  */
1197 1366
 //#define PINS_DEBUGGING
@@ -1244,6 +1413,8 @@
1244 1413
 //#define CUSTOM_USER_MENUS
1245 1414
 #if ENABLED(CUSTOM_USER_MENUS)
1246 1415
   #define USER_SCRIPT_DONE "M117 User Script Done"
1416
+  #define USER_SCRIPT_AUDIBLE_FEEDBACK
1417
+  //#define USER_SCRIPT_RETURN  // Return to status screen after a script
1247 1418
 
1248 1419
   #define USER_DESC_1 "Home & UBL Info"
1249 1420
   #define USER_GCODE_1 "G28\nG29 W"
@@ -1271,6 +1442,7 @@
1271 1442
 //===========================================================================
1272 1443
 //====================== I2C Position Encoder Settings ======================
1273 1444
 //===========================================================================
1445
+
1274 1446
 /**
1275 1447
  *  I2C position encoders for closed loop control.
1276 1448
  *  Developed by Chris Barr at Aus3D.
@@ -1351,4 +1523,45 @@
1351 1523
 
1352 1524
 #endif // I2C_POSITION_ENCODERS
1353 1525
 
1526
+/**
1527
+ * MAX7219 Debug Matrix
1528
+ *
1529
+ * Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
1530
+ * display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
1531
+ *
1532
+ * Fully assembled MAX7219 boards can be found on the internet for under $2(US).
1533
+ * For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
1534
+ */
1535
+//#define MAX7219_DEBUG
1536
+#if ENABLED(MAX7219_DEBUG)
1537
+  #define MAX7219_CLK_PIN   64  // 77 on Re-ARM       // Configuration of the 3 pins to control the display
1538
+  #define MAX7219_DIN_PIN   57  // 78 on Re-ARM
1539
+  #define MAX7219_LOAD_PIN  44  // 79 on Re-ARM
1540
+
1541
+  /**
1542
+   * Sample debug features
1543
+   * If you add more debug displays, be careful to avoid conflicts!
1544
+   */
1545
+  #define MAX7219_DEBUG_PRINTER_ALIVE    // Blink corner LED of 8x8 matrix to show that the firmware is functioning
1546
+  #define MAX7219_DEBUG_STEPPER_HEAD  3  // Show the stepper queue head position on this and the next LED matrix row
1547
+  #define MAX7219_DEBUG_STEPPER_TAIL  5  // Show the stepper queue tail position on this and the next LED matrix row
1548
+
1549
+  #define MAX7219_DEBUG_STEPPER_QUEUE 0  // Show the current stepper queue depth on this and the next LED matrix row
1550
+                                         // If you experience stuttering, reboots, etc. this option can reveal how
1551
+                                         // tweaks made to the configuration are affecting the printer in real-time.
1552
+#endif
1553
+
1554
+/**
1555
+ * NanoDLP Sync support
1556
+ *
1557
+ * Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
1558
+ * string to enable synchronization with DLP projector exposure. This change will allow to use
1559
+ * [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
1560
+ */
1561
+//#define NANODLP_Z_SYNC
1562
+#if ENABLED(NANODLP_Z_SYNC)
1563
+  //#define NANODLP_ALL_AXIS  // Enables "Z_move_comp" output on any axis move.
1564
+                              // Default behaviour is limited to Z axis only.
1565
+#endif
1566
+
1354 1567
 #endif // CONFIGURATION_ADV_H

Marlin/example_configurations/CL-260/Configuration.h → Marlin/example_configurations/AliExpress/CL-260/Configuration.h 파일 보기

@@ -37,7 +37,7 @@
37 37
  */
38 38
 #ifndef CONFIGURATION_H
39 39
 #define CONFIGURATION_H
40
-#define CONFIGURATION_H_VERSION 010100
40
+#define CONFIGURATION_H_VERSION 010107
41 41
 
42 42
 //===========================================================================
43 43
 //============================= Getting Started =============================
@@ -74,7 +74,7 @@
74 74
 // User-specified version info of this build to display in [Pronterface, etc] terminal window during
75 75
 // startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
76 76
 // build by the user have been successfully uploaded into firmware.
77
-#define STRING_CONFIG_H_AUTHOR "(none, example CL-260 config)" // Who made the changes.
77
+#define STRING_CONFIG_H_AUTHOR "(none, CL-260)" // Who made the changes.
78 78
 #define SHOW_BOOTSCREEN
79 79
 #define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
80 80
 #define STRING_SPLASH_LINE2 WEBSITE_URL         // will be shown during bootup in line 2
@@ -107,8 +107,9 @@
107 107
  *
108 108
  * 250000 works in most cases, but you might try a lower speed if
109 109
  * you commonly experience drop-outs during host printing.
110
+ * You may try up to 1000000 to speed up SD file transfer.
110 111
  *
111
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
112
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
112 113
  */
113 114
 #define BAUDRATE 250000
114 115
 
@@ -135,6 +136,9 @@
135 136
 // :[1, 2, 3, 4, 5]
136 137
 #define EXTRUDERS 1
137 138
 
139
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
140
+#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
141
+
138 142
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
139 143
 //#define SINGLENOZZLE
140 144
 
@@ -161,7 +165,10 @@
161 165
 //#define SWITCHING_EXTRUDER
162 166
 #if ENABLED(SWITCHING_EXTRUDER)
163 167
   #define SWITCHING_EXTRUDER_SERVO_NR 0
164
-  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1
168
+  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3]
169
+  #if EXTRUDERS > 3
170
+    #define SWITCHING_EXTRUDER_E23_SERVO_NR 1
171
+  #endif
165 172
 #endif
166 173
 
167 174
 // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles
@@ -173,6 +180,21 @@
173 180
 #endif
174 181
 
175 182
 /**
183
+ * Two separate X-carriages with extruders that connect to a moving part
184
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
185
+ */
186
+//#define PARKING_EXTRUDER
187
+#if ENABLED(PARKING_EXTRUDER)
188
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
189
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
190
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
191
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
192
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
193
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
194
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
195
+#endif
196
+
197
+/**
176 198
  * "Mixing Extruder"
177 199
  *   - Adds a new code, M165, to set the current mix factors.
178 200
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -317,8 +339,9 @@
317 339
 
318 340
 // Comment the following line to disable PID and enable bang-bang.
319 341
 #define PIDTEMP
320
-#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
321
-#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
342
+#define BANG_MAX 255     // Limits current to nozzle while in bang-bang mode; 255=full current
343
+#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
344
+#define PID_K1 0.95      // Smoothing factor within the PID
322 345
 #if ENABLED(PIDTEMP)
323 346
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
324 347
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -328,7 +351,6 @@
328 351
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
329 352
   #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
330 353
                                   // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
331
-  #define K1 0.95 //smoothing factor within the PID
332 354
 
333 355
   // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
334 356
 
@@ -409,12 +431,13 @@
409 431
 //===========================================================================
410 432
 
411 433
 /**
412
- * Thermal Protection protects your printer from damage and fire if a
413
- * thermistor falls out or temperature sensors fail in any way.
434
+ * Thermal Protection provides additional protection to your printer from damage
435
+ * and fire. Marlin always includes safe min and max temperature ranges which
436
+ * protect against a broken or disconnected thermistor wire.
414 437
  *
415
- * The issue: If a thermistor falls out or a temperature sensor fails,
416
- * Marlin can no longer sense the actual temperature. Since a disconnected
417
- * thermistor reads as a low temperature, the firmware will keep the heater on.
438
+ * The issue: If a thermistor falls out, it will report the much lower
439
+ * temperature of the air in the room, and the the firmware will keep
440
+ * the heater on.
418 441
  *
419 442
  * If you get "Thermal Runaway" or "Heating failed" errors the
420 443
  * details can be tuned in Configuration_adv.h
@@ -548,14 +571,13 @@
548 571
 #define DEFAULT_ZJERK                  0.4
549 572
 #define DEFAULT_EJERK                  5.0
550 573
 
551
-
552 574
 //===========================================================================
553 575
 //============================= Z Probe Options =============================
554 576
 //===========================================================================
555 577
 // @section probes
556 578
 
557 579
 //
558
-// See http://marlinfw.org/configuration/probes.html
580
+// See http://marlinfw.org/docs/configuration/probes.html
559 581
 //
560 582
 
561 583
 /**
@@ -621,14 +643,15 @@
621 643
 #endif
622 644
 
623 645
 /**
624
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
625
- * options selected below - will be disabled during probing so as to minimize
626
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
627
- * in current flowing through the wires).  This is likely most useful to users of the
628
- * BLTouch probe, but may also help those with inductive or other probe types.
646
+ * Enable one or more of the following if probing seems unreliable.
647
+ * Heaters and/or fans can be disabled during probing to minimize electrical
648
+ * noise. A delay can also be added to allow noise and vibration to settle.
649
+ * These options are most useful for the BLTouch probe, but may also improve
650
+ * readings with inductive probes and piezo sensors.
629 651
  */
630 652
 //#define PROBING_HEATERS_OFF       // Turn heaters off when probing
631 653
 //#define PROBING_FANS_OFF          // Turn fans off when probing
654
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
632 655
 
633 656
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
634 657
 //#define SOLENOID_PROBE
@@ -667,14 +690,16 @@
667 690
 // X and Y axis travel speed (mm/m) between probes
668 691
 #define XY_PROBE_SPEED 8000
669 692
 
670
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
693
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
671 694
 #define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
672 695
 
673 696
 // Speed for the "accurate" probe of each point
674 697
 #define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
675 698
 
676
-// Use double touch for probing
677
-//#define PROBE_DOUBLE_TOUCH
699
+// The number of probes to perform at each point.
700
+//   Set to 2 for a fast/slow probe, using the second probe result.
701
+//   Set to 3 or more for slow probes, averaging the results.
702
+//#define MULTIPLE_PROBING 2
678 703
 
679 704
 /**
680 705
  * Z probes require clearance when deploying, stowing, and moving between
@@ -741,6 +766,8 @@
741 766
 
742 767
 // @section homing
743 768
 
769
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
770
+
744 771
 //#define Z_HOMING_HEIGHT 4  // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
745 772
                              // Be sure you have this distance over your Z_MAX_POS in case.
746 773
 
@@ -752,18 +779,42 @@
752 779
 
753 780
 // @section machine
754 781
 
755
-// Travel limits after homing (units are in mm)
782
+// The size of the print bed
783
+#define X_BED_SIZE 220
784
+#define Y_BED_SIZE 220
785
+
786
+// Travel limits (mm) after homing, corresponding to endstop positions.
756 787
 #define X_MIN_POS 0
757 788
 #define Y_MIN_POS 0
758 789
 #define Z_MIN_POS 0
759
-#define X_MAX_POS 220
760
-#define Y_MAX_POS 220
790
+#define X_MAX_POS X_BED_SIZE
791
+#define Y_MAX_POS Y_BED_SIZE
761 792
 #define Z_MAX_POS 260
762 793
 
763
-// If enabled, axes won't move below MIN_POS in response to movement commands.
794
+/**
795
+ * Software Endstops
796
+ *
797
+ * - Prevent moves outside the set machine bounds.
798
+ * - Individual axes can be disabled, if desired.
799
+ * - X and Y only apply to Cartesian robots.
800
+ * - Use 'M211' to set software endstops on/off or report current state
801
+ */
802
+
803
+// Min software endstops curtail movement below minimum coordinate bounds
764 804
 #define MIN_SOFTWARE_ENDSTOPS
765
-// If enabled, axes won't move above MAX_POS in response to movement commands.
805
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
806
+  #define MIN_SOFTWARE_ENDSTOP_X
807
+  #define MIN_SOFTWARE_ENDSTOP_Y
808
+  #define MIN_SOFTWARE_ENDSTOP_Z
809
+#endif
810
+
811
+// Max software endstops curtail movement above maximum coordinate bounds
766 812
 #define MAX_SOFTWARE_ENDSTOPS
813
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
814
+  #define MAX_SOFTWARE_ENDSTOP_X
815
+  #define MAX_SOFTWARE_ENDSTOP_Y
816
+  #define MAX_SOFTWARE_ENDSTOP_Z
817
+#endif
767 818
 
768 819
 /**
769 820
  * Filament Runout Sensor
@@ -783,7 +834,7 @@
783 834
 //===========================================================================
784 835
 //=============================== Bed Leveling ==============================
785 836
 //===========================================================================
786
-// @section bedlevel
837
+// @section calibrate
787 838
 
788 839
 /**
789 840
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -809,12 +860,7 @@
809 860
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
810 861
  *   A comprehensive bed leveling system combining the features and benefits
811 862
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
812
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
813
- *   for Cartesian Printers. That said, it was primarily designed to correct
814
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
815
- *   please post an issue if something doesn't work correctly. Initially,
816
- *   you will need to set a reduced bed size so you have a rectangular area
817
- *   to test on.
863
+ *   Validation and Mesh Editing systems.
818 864
  *
819 865
  * - MESH_BED_LEVELING
820 866
  *   Probe a grid manually
@@ -841,6 +887,24 @@
841 887
   // at which point movement will be level to the machine's XY plane.
842 888
   // The height can be set with M420 Z<height>
843 889
   #define ENABLE_LEVELING_FADE_HEIGHT
890
+
891
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
892
+  // split up moves into short segments like a Delta. This follows the
893
+  // contours of the bed more closely than edge-to-edge straight moves.
894
+  #define SEGMENT_LEVELED_MOVES
895
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
896
+
897
+  /**
898
+   * Enable the G26 Mesh Validation Pattern tool.
899
+   */
900
+  //#define G26_MESH_VALIDATION   // Enable G26 mesh validation
901
+  #if ENABLED(G26_MESH_VALIDATION)
902
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
903
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
904
+    #define MESH_TEST_HOTEND_TEMP   205.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
905
+    #define MESH_TEST_BED_TEMP       60.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
906
+  #endif
907
+
844 908
 #endif
845 909
 
846 910
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -896,7 +960,9 @@
896 960
   //========================= Unified Bed Leveling ============================
897 961
   //===========================================================================
898 962
 
899
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
963
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
964
+
965
+  #define MESH_INSET 1              // Mesh inset margin on print area
900 966
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
901 967
   #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
902 968
 
@@ -907,8 +973,8 @@
907 973
   #define UBL_PROBE_PT_3_X 180
908 974
   #define UBL_PROBE_PT_3_Y 20
909 975
 
910
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
911 976
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
977
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
912 978
 
913 979
 #elif ENABLED(MESH_BED_LEVELING)
914 980
 
@@ -935,6 +1001,9 @@
935 1001
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
936 1002
 #endif
937 1003
 
1004
+// Add a menu item to move between bed corners for manual bed adjustment
1005
+//#define LEVEL_BED_CORNERS
1006
+
938 1007
 /**
939 1008
  * Commands to execute at the end of G29 probing.
940 1009
  * Useful to retract or move the Z probe out of the way.
@@ -965,14 +1034,71 @@
965 1034
 //#define Z_SAFE_HOMING
966 1035
 
967 1036
 #if ENABLED(Z_SAFE_HOMING)
968
-  #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
969
-  #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
1037
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1038
+  #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2)    // Y point for Z homing when homing all axes (G28).
970 1039
 #endif
971 1040
 
972 1041
 // Homing speeds (mm/m)
973 1042
 #define HOMING_FEEDRATE_XY (50*60)
974 1043
 #define HOMING_FEEDRATE_Z  (4*60)
975 1044
 
1045
+// @section calibrate
1046
+
1047
+/**
1048
+ * Bed Skew Compensation
1049
+ *
1050
+ * This feature corrects for misalignment in the XYZ axes.
1051
+ *
1052
+ * Take the following steps to get the bed skew in the XY plane:
1053
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1054
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1055
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1056
+ *  4. For XY_SIDE_AD measure the edge A to D
1057
+ *
1058
+ * Marlin automatically computes skew factors from these measurements.
1059
+ * Skew factors may also be computed and set manually:
1060
+ *
1061
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1062
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1063
+ *
1064
+ * If desired, follow the same procedure for XZ and YZ.
1065
+ * Use these diagrams for reference:
1066
+ *
1067
+ *    Y                     Z                     Z
1068
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1069
+ *    |    /       /        |    /       /        |    /       /
1070
+ *    |   /       /         |   /       /         |   /       /
1071
+ *    |  A-------D          |  A-------D          |  A-------D
1072
+ *    +-------------->X     +-------------->X     +-------------->Y
1073
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1074
+ */
1075
+//#define SKEW_CORRECTION
1076
+
1077
+#if ENABLED(SKEW_CORRECTION)
1078
+  // Input all length measurements here:
1079
+  #define XY_DIAG_AC 282.8427124746
1080
+  #define XY_DIAG_BD 282.8427124746
1081
+  #define XY_SIDE_AD 200
1082
+
1083
+  // Or, set the default skew factors directly here
1084
+  // to override the above measurements:
1085
+  #define XY_SKEW_FACTOR 0.0
1086
+
1087
+  //#define SKEW_CORRECTION_FOR_Z
1088
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1089
+    #define XZ_DIAG_AC 282.8427124746
1090
+    #define XZ_DIAG_BD 282.8427124746
1091
+    #define YZ_DIAG_AC 282.8427124746
1092
+    #define YZ_DIAG_BD 282.8427124746
1093
+    #define YZ_SIDE_AD 200
1094
+    #define XZ_SKEW_FACTOR 0.0
1095
+    #define YZ_SKEW_FACTOR 0.0
1096
+  #endif
1097
+
1098
+  // Enable this option for M852 to set skew at runtime
1099
+  //#define SKEW_CORRECTION_GCODE
1100
+#endif
1101
+
976 1102
 //=============================================================================
977 1103
 //============================= Additional Features ===========================
978 1104
 //=============================================================================
@@ -999,11 +1125,12 @@
999 1125
 //
1000 1126
 #define HOST_KEEPALIVE_FEATURE        // Disable this if your host doesn't like keepalive messages
1001 1127
 #define DEFAULT_KEEPALIVE_INTERVAL 2  // Number of seconds between "busy" messages. Set with M113.
1128
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
1002 1129
 
1003 1130
 //
1004 1131
 // M100 Free Memory Watcher
1005 1132
 //
1006
-//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1133
+//#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
1007 1134
 
1008 1135
 //
1009 1136
 // G20/G21 Inch mode support
@@ -1148,11 +1275,11 @@
1148 1275
  *
1149 1276
  * Select the language to display on the LCD. These languages are available:
1150 1277
  *
1151
- *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
1152
- *    it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
1153
- *    zh_CN, zh_TW, test
1278
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1279
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1280
+ *    tr, uk, zh_CN, zh_TW, test
1154 1281
  *
1155
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1282
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1156 1283
  */
1157 1284
 #define LCD_LANGUAGE en
1158 1285
 
@@ -1174,7 +1301,7 @@
1174 1301
  *  - Click the controller to view the LCD menu
1175 1302
  *  - The LCD will display Japanese, Western, or Cyrillic text
1176 1303
  *
1177
- * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1304
+ * See http://marlinfw.org/docs/development/lcd_language.html
1178 1305
  *
1179 1306
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1180 1307
  */
@@ -1280,8 +1407,8 @@
1280 1407
 // Note: Test audio output with the G-Code:
1281 1408
 //  M300 S<frequency Hz> P<duration ms>
1282 1409
 //
1283
-//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
1284
-//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
1410
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
1411
+//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
1285 1412
 
1286 1413
 //
1287 1414
 // CONTROLLER TYPE: Standard
@@ -1389,11 +1516,13 @@
1389 1516
 //#define CARTESIO_UI
1390 1517
 
1391 1518
 //
1392
-// ANET_10 Controller supported displays.
1519
+// ANET and Tronxy Controller supported displays.
1393 1520
 //
1394
-//#define ANET_KEYPAD_LCD         // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1521
+//#define ZONESTAR_LCD            // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1395 1522
                                   // This LCD is known to be susceptible to electrical interference
1396 1523
                                   // which scrambles the display.  Pressing any button clears it up.
1524
+                                  // This is a LCD2004 display with 5 analog buttons.
1525
+
1397 1526
 //#define ANET_FULL_GRAPHICS_LCD  // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1398 1527
                                   // A clone of the RepRapDiscount full graphics display but with
1399 1528
                                   // different pins/wiring (see pins_ANET_10.h).
@@ -1453,11 +1582,6 @@
1453 1582
 //#define U8GLIB_SSD1306
1454 1583
 
1455 1584
 //
1456
-// TinyBoy2 128x64 OLED / Encoder Panel
1457
-//
1458
-//#define OLED_PANEL_TINYBOY2
1459
-
1460
-//
1461 1585
 // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules
1462 1586
 //
1463 1587
 //#define SAV_3DGLCD
@@ -1474,6 +1598,45 @@
1474 1598
 //
1475 1599
 //#define SAV_3DLCD
1476 1600
 
1601
+//
1602
+// TinyBoy2 128x64 OLED / Encoder Panel
1603
+//
1604
+//#define OLED_PANEL_TINYBOY2
1605
+
1606
+//
1607
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1608
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1609
+//
1610
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1611
+
1612
+//
1613
+// MKS MINI12864 with graphic controller and SD support
1614
+// http://reprap.org/wiki/MKS_MINI_12864
1615
+//
1616
+//#define MKS_MINI_12864
1617
+
1618
+//
1619
+// Factory display for Creality CR-10
1620
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1621
+//
1622
+// This is RAMPS-compatible using a single 10-pin connector.
1623
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1624
+//
1625
+//#define CR10_STOCKDISPLAY
1626
+
1627
+//
1628
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1629
+// http://reprap.org/wiki/MKS_12864OLED
1630
+//
1631
+// Tiny, but very sharp OLED display
1632
+//
1633
+//#define MKS_12864OLED
1634
+
1635
+// Silvergate GLCD controller
1636
+// http://github.com/android444/Silvergate
1637
+//
1638
+//#define SILVER_GATE_GLCD_CONTROLLER
1639
+
1477 1640
 //=============================================================================
1478 1641
 //=============================== Extra Features ==============================
1479 1642
 //=============================================================================
@@ -1530,16 +1693,22 @@
1530 1693
  * Adds the M150 command to set the LED (or LED strip) color.
1531 1694
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1532 1695
  * luminance values can be set from 0 to 255.
1696
+ * For Neopixel LED an overall brightness parameter is also available.
1533 1697
  *
1534 1698
  * *** CAUTION ***
1535 1699
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1536 1700
  *  as the Arduino cannot handle the current the LEDs will require.
1537 1701
  *  Failure to follow this precaution can destroy your Arduino!
1702
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1703
+ *  more current than the Arduino 5V linear regulator can produce.
1538 1704
  * *** CAUTION ***
1539 1705
  *
1706
+ * LED Type. Enable only one of the following two options.
1707
+ *
1540 1708
  */
1541 1709
 //#define RGB_LED
1542 1710
 //#define RGBW_LED
1711
+
1543 1712
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1544 1713
   #define RGB_LED_R_PIN 34
1545 1714
   #define RGB_LED_G_PIN 43
@@ -1547,6 +1716,17 @@
1547 1716
   #define RGB_LED_W_PIN -1
1548 1717
 #endif
1549 1718
 
1719
+// Support for Adafruit Neopixel LED driver
1720
+//#define NEOPIXEL_LED
1721
+#if ENABLED(NEOPIXEL_LED)
1722
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1723
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1724
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1725
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1726
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1727
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1728
+#endif
1729
+
1550 1730
 /**
1551 1731
  * Printer Event LEDs
1552 1732
  *
@@ -1558,68 +1738,32 @@
1558 1738
  *  - Change to green once print has finished
1559 1739
  *  - Turn off after the print has finished and the user has pushed a button
1560 1740
  */
1561
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)
1741
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1562 1742
   #define PRINTER_EVENT_LEDS
1563 1743
 #endif
1564 1744
 
1565
-/*********************************************************************\
1566
-* R/C SERVO support
1567
-* Sponsored by TrinityLabs, Reworked by codexmas
1568
-**********************************************************************/
1745
+/**
1746
+ * R/C SERVO support
1747
+ * Sponsored by TrinityLabs, Reworked by codexmas
1748
+ */
1569 1749
 
1570
-// Number of servos
1571
-//
1572
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1573
-// set it manually if you have more servos than extruders and wish to manually control some
1574
-// leaving it undefined or defining as 0 will disable the servo subsystem
1575
-// If unsure, leave commented / disabled
1576
-//
1750
+/**
1751
+ * Number of servos
1752
+ *
1753
+ * For some servo-related options NUM_SERVOS will be set automatically.
1754
+ * Set this manually if there are extra servos needing manual control.
1755
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1756
+ */
1577 1757
 //#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
1578 1758
 
1579 1759
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1580 1760
 // 300ms is a good value but you can try less delay.
1581 1761
 // If the servo can't reach the requested position, increase it.
1582
-#define SERVO_DELAY 300
1762
+#define SERVO_DELAY { 300 }
1583 1763
 
1584 1764
 // Servo deactivation
1585 1765
 //
1586 1766
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1587 1767
 //#define DEACTIVATE_SERVOS_AFTER_MOVE
1588 1768
 
1589
-/**
1590
- * Filament Width Sensor
1591
- *
1592
- * Measures the filament width in real-time and adjusts
1593
- * flow rate to compensate for any irregularities.
1594
- *
1595
- * Also allows the measured filament diameter to set the
1596
- * extrusion rate, so the slicer only has to specify the
1597
- * volume.
1598
- *
1599
- * Only a single extruder is supported at this time.
1600
- *
1601
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1602
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1603
- * 301 RAMBO       : Analog input 3
1604
- *
1605
- * Note: May require analog pins to be defined for other boards.
1606
- */
1607
-//#define FILAMENT_WIDTH_SENSOR
1608
-
1609
-#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00   // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
1610
-
1611
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1612
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1613
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1614
-
1615
-  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1616
-  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1617
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1618
-
1619
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1620
-
1621
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1622
-  //#define FILAMENT_LCD_DISPLAY
1623
-#endif
1624
-
1625 1769
 #endif // CONFIGURATION_H

Marlin/example_configurations/CL-260/README.txt → Marlin/example_configurations/AliExpress/CL-260/README.txt 파일 보기

@@ -1,4 +1,4 @@
1
-This is an example configuration for the CL-260.
1
+This is an example configuration for the CL-260 Ultimaker 2 clone.
2 2
 Change Z_MAX_POS to 300 for the CL-260MAX.
3 3
 
4 4
 (The printer is available on AliExpress; be aware that this is not a beginner's

+ 272
- 130
Marlin/example_configurations/Anet/A6/Configuration.h 파일 보기

@@ -37,7 +37,7 @@
37 37
  */
38 38
 #ifndef CONFIGURATION_H
39 39
 #define CONFIGURATION_H
40
-#define CONFIGURATION_H_VERSION 010100
40
+#define CONFIGURATION_H_VERSION 010107
41 41
 
42 42
 //===========================================================================
43 43
 //============================= Getting Started =============================
@@ -107,8 +107,9 @@
107 107
  *
108 108
  * 250000 works in most cases, but you might try a lower speed if
109 109
  * you commonly experience drop-outs during host printing.
110
+ * You may try up to 1000000 to speed up SD file transfer.
110 111
  *
111
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
112
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
112 113
  */
113 114
 #define BAUDRATE 115200
114 115
 
@@ -135,6 +136,9 @@
135 136
 // :[1, 2, 3, 4, 5]
136 137
 #define EXTRUDERS 1
137 138
 
139
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
140
+#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
141
+
138 142
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
139 143
 //#define SINGLENOZZLE
140 144
 
@@ -176,6 +180,21 @@
176 180
 #endif
177 181
 
178 182
 /**
183
+ * Two separate X-carriages with extruders that connect to a moving part
184
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
185
+ */
186
+//#define PARKING_EXTRUDER
187
+#if ENABLED(PARKING_EXTRUDER)
188
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
189
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
190
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
191
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
192
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
193
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
194
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
195
+#endif
196
+
197
+/**
179 198
  * "Mixing Extruder"
180 199
  *   - Adds a new code, M165, to set the current mix factors.
181 200
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -320,8 +339,9 @@
320 339
 
321 340
 // Comment the following line to disable PID and enable bang-bang.
322 341
 #define PIDTEMP
323
-#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
324
-#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
342
+#define BANG_MAX 255     // Limits current to nozzle while in bang-bang mode; 255=full current
343
+#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
344
+#define PID_K1 0.95      // Smoothing factor within the PID
325 345
 #if ENABLED(PIDTEMP)
326 346
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
327 347
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -331,7 +351,6 @@
331 351
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
332 352
   #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
333 353
                                   // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
334
-  #define K1 0.95 //smoothing factor within the PID
335 354
 
336 355
   // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
337 356
 
@@ -432,12 +451,13 @@
432 451
 //===========================================================================
433 452
 
434 453
 /**
435
- * Thermal Protection protects your printer from damage and fire if a
436
- * thermistor falls out or temperature sensors fail in any way.
454
+ * Thermal Protection provides additional protection to your printer from damage
455
+ * and fire. Marlin always includes safe min and max temperature ranges which
456
+ * protect against a broken or disconnected thermistor wire.
437 457
  *
438
- * The issue: If a thermistor falls out or a temperature sensor fails,
439
- * Marlin can no longer sense the actual temperature. Since a disconnected
440
- * thermistor reads as a low temperature, the firmware will keep the heater on.
458
+ * The issue: If a thermistor falls out, it will report the much lower
459
+ * temperature of the air in the room, and the the firmware will keep
460
+ * the heater on.
441 461
  *
442 462
  * If you get "Thermal Runaway" or "Heating failed" errors the
443 463
  * details can be tuned in Configuration_adv.h
@@ -608,14 +628,13 @@
608 628
 //#define DEFAULT_ZJERK                  0.3
609 629
 //#define DEFAULT_EJERK                  5.0
610 630
 
611
-
612 631
 //===========================================================================
613 632
 //============================= Z Probe Options =============================
614 633
 //===========================================================================
615 634
 // @section probes
616 635
 
617 636
 //
618
-// See http://marlinfw.org/configuration/probes.html
637
+// See http://marlinfw.org/docs/configuration/probes.html
619 638
 //
620 639
 
621 640
 /**
@@ -650,7 +669,7 @@
650 669
  * Probe Type
651 670
  *
652 671
  * Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
653
- * You must activate one of these to use Auto Bed Leveling below.
672
+ * Activate one of these to use Auto Bed Leveling below.
654 673
  */
655 674
 
656 675
 /**
@@ -681,14 +700,15 @@
681 700
 #endif
682 701
 
683 702
 /**
684
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
685
- * options selected below - will be disabled during probing so as to minimize
686
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
687
- * in current flowing through the wires).  This is likely most useful to users of the
688
- * BLTouch probe, but may also help those with inductive or other probe types.
703
+ * Enable one or more of the following if probing seems unreliable.
704
+ * Heaters and/or fans can be disabled during probing to minimize electrical
705
+ * noise. A delay can also be added to allow noise and vibration to settle.
706
+ * These options are most useful for the BLTouch probe, but may also improve
707
+ * readings with inductive probes and piezo sensors.
689 708
  */
690 709
 #define PROBING_HEATERS_OFF       // Turn heaters off when probing
691 710
 #define PROBING_FANS_OFF          // Turn fans off when probing
711
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
692 712
 
693 713
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
694 714
 //#define SOLENOID_PROBE
@@ -749,14 +769,16 @@
749 769
 #define XY_PROBE_SPEED 8000
750 770
 //#define XY_PROBE_SPEED 6000
751 771
 
752
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
772
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
753 773
 #define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
754 774
 
755 775
 // Speed for the "accurate" probe of each point
756 776
 #define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 3)
757 777
 
758
-// Use double touch for probing
759
-#define PROBE_DOUBLE_TOUCH
778
+// The number of probes to perform at each point.
779
+//   Set to 2 for a fast/slow probe, using the second probe result.
780
+//   Set to 3 or more for slow probes, averaging the results.
781
+#define MULTIPLE_PROBING 2
760 782
 
761 783
 /**
762 784
  * Z probes require clearance when deploying, stowing, and moving between
@@ -828,6 +850,8 @@
828 850
 
829 851
 // @section homing
830 852
 
853
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
854
+
831 855
 //#define Z_HOMING_HEIGHT 4  // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
832 856
                              // Be sure you have this distance over your Z_MAX_POS in case.
833 857
 
@@ -839,52 +863,77 @@
839 863
 
840 864
 // @section machine
841 865
 
842
-// Travel limits after homing (units are in mm)
866
+// The size of the print bed
867
+//#define X_BED_SIZE 200
868
+//#define Y_BED_SIZE 200
869
+
870
+// Travel limits (mm) after homing, corresponding to endstop positions.
843 871
 //#define X_MIN_POS 0
844 872
 //#define Y_MIN_POS 0
873
+//#define X_MAX_POS X_BED_SIZE
874
+//#define Y_MAX_POS Y_BED_SIZE
845 875
 //#define Z_MIN_POS 0
846
-//#define X_MAX_POS 200
847
-//#define Y_MAX_POS 200
848 876
 //#define Z_MAX_POS 200
849 877
 
850 878
 // ANET A6 Firmware V2.0 defaults:
851
-//#define X_MIN_POS     0
852
-//#define Y_MIN_POS     0
853
-//#define Z_MIN_POS     0
854
-//#define X_MAX_POS     220
855
-//#define Y_MAX_POS     220
856
-//#define Z_MAX_POS     250
879
+//#define X_BED_SIZE 220
880
+//#define Y_BED_SIZE 220
881
+//#define X_MIN_POS 0
882
+//#define Y_MIN_POS 0
883
+//#define Z_MIN_POS 0
884
+//#define Z_MAX_POS 250
857 885
 
858 886
 // ANET A6, X0/Y0 0 front left bed edge :
859
-#define X_MIN_POS     -3
860
-#define Y_MIN_POS     -5
861
-#define Z_MIN_POS     0
862
-#define X_MAX_POS     222
863
-#define Y_MAX_POS     222
864
-#define Z_MAX_POS     230
887
+#define X_BED_SIZE 222
888
+#define Y_BED_SIZE 222
889
+#define X_MIN_POS -3
890
+#define Y_MIN_POS -5
891
+#define Z_MIN_POS 0
892
+#define Z_MAX_POS 230
865 893
 
866 894
 // ANET A6 with new X-Axis / modded Y-Axis:
867
-//#define X_MIN_POS     0
868
-//#define Y_MIN_POS     0
869
-//#define Z_MIN_POS     0
870
-//#define X_MAX_POS     235
871
-//#define Y_MAX_POS     230
872
-//#define Z_MAX_POS     230
895
+//#define X_BED_SIZE 235
896
+//#define Y_BED_SIZE 230
897
+//#define X_MIN_POS 0
898
+//#define Y_MIN_POS 0
899
+//#define Z_MIN_POS 0
900
+//#define Z_MAX_POS 230
873 901
 
874 902
 // ANET A6 with new X-Axis / modded Y-Axis, X0/Y0 0 front left bed edge :
875
-//#define X_MIN_POS     -8
876
-//#define Y_MIN_POS     -6
877
-//#define Z_MIN_POS     0
878
-//#define X_MAX_POS     227
879
-//#define Y_MAX_POS     224
880
-//#define Z_MAX_POS     230
903
+//#define X_BED_SIZE 227
904
+//#define Y_BED_SIZE 224
905
+//#define X_MIN_POS -8
906
+//#define Y_MIN_POS -6
907
+//#define Z_MIN_POS 0
908
+//#define Z_MAX_POS 230
881 909
 
910
+#define X_MAX_POS X_BED_SIZE
911
+#define Y_MAX_POS Y_BED_SIZE
882 912
 
913
+/**
914
+ * Software Endstops
915
+ *
916
+ * - Prevent moves outside the set machine bounds.
917
+ * - Individual axes can be disabled, if desired.
918
+ * - X and Y only apply to Cartesian robots.
919
+ * - Use 'M211' to set software endstops on/off or report current state
920
+ */
883 921
 
884
-// If enabled, axes won't move below MIN_POS in response to movement commands.
922
+// Min software endstops curtail movement below minimum coordinate bounds
885 923
 #define MIN_SOFTWARE_ENDSTOPS
886
-// If enabled, axes won't move above MAX_POS in response to movement commands.
924
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
925
+  #define MIN_SOFTWARE_ENDSTOP_X
926
+  #define MIN_SOFTWARE_ENDSTOP_Y
927
+  #define MIN_SOFTWARE_ENDSTOP_Z
928
+#endif
929
+
930
+// Max software endstops curtail movement above maximum coordinate bounds
887 931
 #define MAX_SOFTWARE_ENDSTOPS
932
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
933
+  #define MAX_SOFTWARE_ENDSTOP_X
934
+  #define MAX_SOFTWARE_ENDSTOP_Y
935
+  #define MAX_SOFTWARE_ENDSTOP_Z
936
+#endif
888 937
 
889 938
 /**
890 939
  * Filament Runout Sensor
@@ -904,7 +953,7 @@
904 953
 //===========================================================================
905 954
 //=============================== Bed Leveling ==============================
906 955
 //===========================================================================
907
-// @section bedlevel
956
+// @section calibrate
908 957
 
909 958
 /**
910 959
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -930,12 +979,7 @@
930 979
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
931 980
  *   A comprehensive bed leveling system combining the features and benefits
932 981
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
933
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
934
- *   for Cartesian Printers. That said, it was primarily designed to correct
935
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
936
- *   please post an issue if something doesn't work correctly. Initially,
937
- *   you will need to set a reduced bed size so you have a rectangular area
938
- *   to test on.
982
+ *   Validation and Mesh Editing systems.
939 983
  *
940 984
  * - MESH_BED_LEVELING
941 985
  *   Probe a grid manually
@@ -962,6 +1006,24 @@
962 1006
   // at which point movement will be level to the machine's XY plane.
963 1007
   // The height can be set with M420 Z<height>
964 1008
   #define ENABLE_LEVELING_FADE_HEIGHT
1009
+
1010
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
1011
+  // split up moves into short segments like a Delta. This follows the
1012
+  // contours of the bed more closely than edge-to-edge straight moves.
1013
+  #define SEGMENT_LEVELED_MOVES
1014
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
1015
+
1016
+  /**
1017
+   * Enable the G26 Mesh Validation Pattern tool.
1018
+   */
1019
+  //#define G26_MESH_VALIDATION   // Enable G26 mesh validation
1020
+  #if ENABLED(G26_MESH_VALIDATION)
1021
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
1022
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
1023
+    #define MESH_TEST_HOTEND_TEMP   205.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
1024
+    #define MESH_TEST_BED_TEMP       60.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
1025
+  #endif
1026
+
965 1027
 #endif
966 1028
 
967 1029
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -1041,7 +1103,9 @@
1041 1103
   //========================= Unified Bed Leveling ============================
1042 1104
   //===========================================================================
1043 1105
 
1044
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
1106
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
1107
+
1108
+  #define MESH_INSET 1              // Mesh inset margin on print area
1045 1109
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
1046 1110
   #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
1047 1111
 
@@ -1052,8 +1116,8 @@
1052 1116
   #define UBL_PROBE_PT_3_X 180
1053 1117
   #define UBL_PROBE_PT_3_Y 20
1054 1118
 
1055
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
1056 1119
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
1120
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
1057 1121
 
1058 1122
 #elif ENABLED(MESH_BED_LEVELING)
1059 1123
 
@@ -1080,6 +1144,9 @@
1080 1144
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
1081 1145
 #endif
1082 1146
 
1147
+// Add a menu item to move between bed corners for manual bed adjustment
1148
+//#define LEVEL_BED_CORNERS
1149
+
1083 1150
 /**
1084 1151
  * Commands to execute at the end of G29 probing.
1085 1152
  * Useful to retract or move the Z probe out of the way.
@@ -1115,16 +1182,16 @@
1115 1182
 #define Z_SAFE_HOMING
1116 1183
 
1117 1184
 #if ENABLED(Z_SAFE_HOMING)
1118
-  #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
1119
-  #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
1185
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1186
+  #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2)    // Y point for Z homing when homing all axes (G28).
1120 1187
 
1121 1188
   //Anet A6 with new X-Axis
1122
-  //#define Z_SAFE_HOMING_X_POINT 113    // X point for Z homing when homing all axis (G28).
1123
-  //#define Z_SAFE_HOMING_Y_POINT 112    // Y point for Z homing when homing all axis (G28).
1189
+  //#define Z_SAFE_HOMING_X_POINT 113    // X point for Z homing when homing all axes (G28).
1190
+  //#define Z_SAFE_HOMING_Y_POINT 112    // Y point for Z homing when homing all axes (G28).
1124 1191
 
1125 1192
   //Anet A6 with new X-Axis and defined X_HOME_POS -7, Y_HOME_POS -6
1126
-  //#define Z_SAFE_HOMING_X_POINT 107    // X point for Z homing when homing all axis (G28).
1127
-  //#define Z_SAFE_HOMING_Y_POINT 107    // Y point for Z homing when homing all axis (G28).
1193
+  //#define Z_SAFE_HOMING_X_POINT 107    // X point for Z homing when homing all axes (G28).
1194
+  //#define Z_SAFE_HOMING_Y_POINT 107    // Y point for Z homing when homing all axes (G28).
1128 1195
 
1129 1196
 #endif
1130 1197
 
@@ -1132,6 +1199,63 @@
1132 1199
 #define HOMING_FEEDRATE_XY (50*60)
1133 1200
 #define HOMING_FEEDRATE_Z  (4*60)
1134 1201
 
1202
+// @section calibrate
1203
+
1204
+/**
1205
+ * Bed Skew Compensation
1206
+ *
1207
+ * This feature corrects for misalignment in the XYZ axes.
1208
+ *
1209
+ * Take the following steps to get the bed skew in the XY plane:
1210
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1211
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1212
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1213
+ *  4. For XY_SIDE_AD measure the edge A to D
1214
+ *
1215
+ * Marlin automatically computes skew factors from these measurements.
1216
+ * Skew factors may also be computed and set manually:
1217
+ *
1218
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1219
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1220
+ *
1221
+ * If desired, follow the same procedure for XZ and YZ.
1222
+ * Use these diagrams for reference:
1223
+ *
1224
+ *    Y                     Z                     Z
1225
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1226
+ *    |    /       /        |    /       /        |    /       /
1227
+ *    |   /       /         |   /       /         |   /       /
1228
+ *    |  A-------D          |  A-------D          |  A-------D
1229
+ *    +-------------->X     +-------------->X     +-------------->Y
1230
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1231
+ */
1232
+//#define SKEW_CORRECTION
1233
+
1234
+#if ENABLED(SKEW_CORRECTION)
1235
+  // Input all length measurements here:
1236
+  #define XY_DIAG_AC 282.8427124746
1237
+  #define XY_DIAG_BD 282.8427124746
1238
+  #define XY_SIDE_AD 200
1239
+
1240
+  // Or, set the default skew factors directly here
1241
+  // to override the above measurements:
1242
+  #define XY_SKEW_FACTOR 0.0
1243
+
1244
+  //#define SKEW_CORRECTION_FOR_Z
1245
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1246
+    #define XZ_DIAG_AC 282.8427124746
1247
+    #define XZ_DIAG_BD 282.8427124746
1248
+    #define YZ_DIAG_AC 282.8427124746
1249
+    #define YZ_DIAG_BD 282.8427124746
1250
+    #define YZ_SIDE_AD 200
1251
+    #define XZ_SKEW_FACTOR 0.0
1252
+    #define YZ_SKEW_FACTOR 0.0
1253
+  #endif
1254
+
1255
+  // Enable this option for M852 to set skew at runtime
1256
+  //#define SKEW_CORRECTION_GCODE
1257
+#endif
1258
+
1135 1259
 //=============================================================================
1136 1260
 //============================= Additional Features ===========================
1137 1261
 //=============================================================================
@@ -1158,11 +1282,12 @@
1158 1282
 //
1159 1283
 #define HOST_KEEPALIVE_FEATURE        // Disable this if your host doesn't like keepalive messages
1160 1284
 #define DEFAULT_KEEPALIVE_INTERVAL 2  // Number of seconds between "busy" messages. Set with M113.
1285
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
1161 1286
 
1162 1287
 //
1163 1288
 // M100 Free Memory Watcher
1164 1289
 //
1165
-//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1290
+//#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
1166 1291
 
1167 1292
 //
1168 1293
 // G20/G21 Inch mode support
@@ -1307,11 +1432,11 @@
1307 1432
  *
1308 1433
  * Select the language to display on the LCD. These languages are available:
1309 1434
  *
1310
- *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
1311
- *    it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
1312
- *    zh_CN, zh_TW, test
1435
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1436
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1437
+ *    tr, uk, zh_CN, zh_TW, test
1313 1438
  *
1314
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1439
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1315 1440
  */
1316 1441
 #define LCD_LANGUAGE en
1317 1442
 
@@ -1333,7 +1458,7 @@
1333 1458
  *  - Click the controller to view the LCD menu
1334 1459
  *  - The LCD will display Japanese, Western, or Cyrillic text
1335 1460
  *
1336
- * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1461
+ * See http://marlinfw.org/docs/development/lcd_language.html
1337 1462
  *
1338 1463
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1339 1464
  */
@@ -1439,8 +1564,8 @@
1439 1564
 // Note: Test audio output with the G-Code:
1440 1565
 //  M300 S<frequency Hz> P<duration ms>
1441 1566
 //
1442
-//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
1443
-//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
1567
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
1568
+//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
1444 1569
 
1445 1570
 //
1446 1571
 // CONTROLLER TYPE: Standard
@@ -1460,12 +1585,6 @@
1460 1585
 //#define ULTIPANEL
1461 1586
 
1462 1587
 //
1463
-// Cartesio UI
1464
-// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
1465
-//
1466
-//#define CARTESIO_UI
1467
-
1468
-//
1469 1588
 // PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
1470 1589
 // http://reprap.org/wiki/PanelOne
1471 1590
 //
@@ -1550,11 +1669,19 @@
1550 1669
 //#define BQ_LCD_SMART_CONTROLLER
1551 1670
 
1552 1671
 //
1553
-// ANET_10 Controller supported displays.
1672
+// Cartesio UI
1673
+// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
1554 1674
 //
1555
-//#define ANET_KEYPAD_LCD         // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1675
+//#define CARTESIO_UI
1676
+
1677
+//
1678
+// ANET and Tronxy Controller supported displays.
1679
+//
1680
+//#define ZONESTAR_LCD            // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1556 1681
                                   // This LCD is known to be susceptible to electrical interference
1557 1682
                                   // which scrambles the display.  Pressing any button clears it up.
1683
+                                  // This is a LCD2004 display with 5 analog buttons.
1684
+
1558 1685
 #define ANET_FULL_GRAPHICS_LCD    // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1559 1686
                                   // A clone of the RepRapDiscount full graphics display but with
1560 1687
                                   // different pins/wiring (see pins_ANET_10.h).
@@ -1635,6 +1762,40 @@
1635 1762
 //
1636 1763
 //#define OLED_PANEL_TINYBOY2
1637 1764
 
1765
+//
1766
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1767
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1768
+//
1769
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1770
+
1771
+//
1772
+// MKS MINI12864 with graphic controller and SD support
1773
+// http://reprap.org/wiki/MKS_MINI_12864
1774
+//
1775
+//#define MKS_MINI_12864
1776
+
1777
+//
1778
+// Factory display for Creality CR-10
1779
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1780
+//
1781
+// This is RAMPS-compatible using a single 10-pin connector.
1782
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1783
+//
1784
+//#define CR10_STOCKDISPLAY
1785
+
1786
+//
1787
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1788
+// http://reprap.org/wiki/MKS_12864OLED
1789
+//
1790
+// Tiny, but very sharp OLED display
1791
+//
1792
+//#define MKS_12864OLED
1793
+
1794
+// Silvergate GLCD controller
1795
+// http://github.com/android444/Silvergate
1796
+//
1797
+//#define SILVER_GATE_GLCD_CONTROLLER
1798
+
1638 1799
 //=============================================================================
1639 1800
 //=============================== Extra Features ==============================
1640 1801
 //=============================================================================
@@ -1691,16 +1852,22 @@
1691 1852
  * Adds the M150 command to set the LED (or LED strip) color.
1692 1853
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1693 1854
  * luminance values can be set from 0 to 255.
1855
+ * For Neopixel LED an overall brightness parameter is also available.
1694 1856
  *
1695 1857
  * *** CAUTION ***
1696 1858
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1697 1859
  *  as the Arduino cannot handle the current the LEDs will require.
1698 1860
  *  Failure to follow this precaution can destroy your Arduino!
1861
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1862
+ *  more current than the Arduino 5V linear regulator can produce.
1699 1863
  * *** CAUTION ***
1700 1864
  *
1865
+ * LED Type. Enable only one of the following two options.
1866
+ *
1701 1867
  */
1702 1868
 //#define RGB_LED
1703 1869
 //#define RGBW_LED
1870
+
1704 1871
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1705 1872
   #define RGB_LED_R_PIN 34
1706 1873
   #define RGB_LED_G_PIN 43
@@ -1708,6 +1875,17 @@
1708 1875
   #define RGB_LED_W_PIN -1
1709 1876
 #endif
1710 1877
 
1878
+// Support for Adafruit Neopixel LED driver
1879
+//#define NEOPIXEL_LED
1880
+#if ENABLED(NEOPIXEL_LED)
1881
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1882
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1883
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1884
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1885
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1886
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1887
+#endif
1888
+
1711 1889
 /**
1712 1890
  * Printer Event LEDs
1713 1891
  *
@@ -1719,68 +1897,32 @@
1719 1897
  *  - Change to green once print has finished
1720 1898
  *  - Turn off after the print has finished and the user has pushed a button
1721 1899
  */
1722
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)
1900
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1723 1901
   #define PRINTER_EVENT_LEDS
1724 1902
 #endif
1725 1903
 
1726
-/*********************************************************************\
1727
-* R/C SERVO support
1728
-* Sponsored by TrinityLabs, Reworked by codexmas
1729
-**********************************************************************/
1904
+/**
1905
+ * R/C SERVO support
1906
+ * Sponsored by TrinityLabs, Reworked by codexmas
1907
+ */
1730 1908
 
1731
-// Number of servos
1732
-//
1733
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1734
-// set it manually if you have more servos than extruders and wish to manually control some
1735
-// leaving it undefined or defining as 0 will disable the servo subsystem
1736
-// If unsure, leave commented / disabled
1737
-//
1909
+/**
1910
+ * Number of servos
1911
+ *
1912
+ * For some servo-related options NUM_SERVOS will be set automatically.
1913
+ * Set this manually if there are extra servos needing manual control.
1914
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1915
+ */
1738 1916
 //#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
1739 1917
 
1740 1918
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1741 1919
 // 300ms is a good value but you can try less delay.
1742 1920
 // If the servo can't reach the requested position, increase it.
1743
-#define SERVO_DELAY 300
1921
+#define SERVO_DELAY { 300 }
1744 1922
 
1745 1923
 // Servo deactivation
1746 1924
 //
1747 1925
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1748 1926
 //#define DEACTIVATE_SERVOS_AFTER_MOVE
1749 1927
 
1750
-/**
1751
- * Filament Width Sensor
1752
- *
1753
- * Measures the filament width in real-time and adjusts
1754
- * flow rate to compensate for any irregularities.
1755
- *
1756
- * Also allows the measured filament diameter to set the
1757
- * extrusion rate, so the slicer only has to specify the
1758
- * volume.
1759
- *
1760
- * Only a single extruder is supported at this time.
1761
- *
1762
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1763
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1764
- * 301 RAMBO       : Analog input 3
1765
- *
1766
- * Note: May require analog pins to be defined for other boards.
1767
- */
1768
-//#define FILAMENT_WIDTH_SENSOR
1769
-
1770
-#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00   // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
1771
-
1772
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1773
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1774
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1775
-
1776
-  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1777
-  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1778
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1779
-
1780
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1781
-
1782
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1783
-  //#define FILAMENT_LCD_DISPLAY
1784
-#endif
1785
-
1786 1928
 #endif // CONFIGURATION_H

+ 367
- 161
Marlin/example_configurations/Anet/A6/Configuration_adv.h 파일 보기

@@ -32,7 +32,7 @@
32 32
  */
33 33
 #ifndef CONFIGURATION_ADV_H
34 34
 #define CONFIGURATION_ADV_H
35
-#define CONFIGURATION_ADV_H_VERSION 010100
35
+#define CONFIGURATION_ADV_H_VERSION 010107
36 36
 
37 37
 // @section temperature
38 38
 
@@ -48,31 +48,36 @@
48 48
 #endif
49 49
 
50 50
 /**
51
- * Thermal Protection protects your printer from damage and fire if a
52
- * thermistor falls out or temperature sensors fail in any way.
51
+ * Thermal Protection provides additional protection to your printer from damage
52
+ * and fire. Marlin always includes safe min and max temperature ranges which
53
+ * protect against a broken or disconnected thermistor wire.
53 54
  *
54
- * The issue: If a thermistor falls out or a temperature sensor fails,
55
- * Marlin can no longer sense the actual temperature. Since a disconnected
56
- * thermistor reads as a low temperature, the firmware will keep the heater on.
55
+ * The issue: If a thermistor falls out, it will report the much lower
56
+ * temperature of the air in the room, and the the firmware will keep
57
+ * the heater on.
57 58
  *
58 59
  * The solution: Once the temperature reaches the target, start observing.
59
- * If the temperature stays too far below the target (hysteresis) for too long (period),
60
- * the firmware will halt the machine as a safety precaution.
60
+ * If the temperature stays too far below the target (hysteresis) for too
61
+ * long (period), the firmware will halt the machine as a safety precaution.
61 62
  *
62
- * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63
+ * If you get false positives for "Thermal Runaway", increase
64
+ * THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63 65
  */
64 66
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
65 67
   #define THERMAL_PROTECTION_PERIOD 60        // Seconds
66 68
   #define THERMAL_PROTECTION_HYSTERESIS 10    // Degrees Celsius
67 69
 
68 70
   /**
69
-   * Whenever an M104 or M109 increases the target temperature the firmware will wait for the
70
-   * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
71
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
72
-   * but only if the current temperature is far enough below the target for a reliable test.
71
+   * Whenever an M104, M109, or M303 increases the target temperature, the
72
+   * firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
73
+   * hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
74
+   * requires a hard reset. This test restarts with any M104/M109/M303, but only
75
+   * if the current temperature is far enough below the target for a reliable
76
+   * test.
73 77
    *
74
-   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
75
-   * WATCH_TEMP_INCREASE should not be below 2.
78
+   * If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
79
+   * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
80
+   * below 2.
76 81
    */
77 82
   #define WATCH_TEMP_PERIOD 60                // Seconds
78 83
   #define WATCH_TEMP_INCREASE 5               // Degrees Celsius
@@ -86,13 +91,7 @@
86 91
   #define THERMAL_PROTECTION_BED_HYSTERESIS 5 // Degrees Celsius
87 92
 
88 93
   /**
89
-   * Whenever an M140 or M190 increases the target temperature the firmware will wait for the
90
-   * WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
91
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
92
-   * but only if the current temperature is far enough below the target for a reliable test.
93
-   *
94
-   * If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
95
-   * WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
94
+   * As described above, except for the bed (M140/M190/M303).
96 95
    */
97 96
   #define WATCH_BED_TEMP_PERIOD 180                // Seconds
98 97
   #define WATCH_BED_TEMP_INCREASE 2               // Degrees Celsius
@@ -123,6 +122,9 @@
123 122
   #define AUTOTEMP_OLDWEIGHT 0.98
124 123
 #endif
125 124
 
125
+// Show extra position information in M114
126
+//#define M114_DETAIL
127
+
126 128
 // Show Temperature ADC value
127 129
 // Enable for M105 to include ADC values read from temperature sensors.
128 130
 //#define SHOW_TEMP_ADC_VALUES
@@ -221,6 +223,17 @@
221 223
 #define EXTRUDER_AUTO_FAN_SPEED   255  // == full speed
222 224
 
223 225
 /**
226
+ * Part-Cooling Fan Multiplexer
227
+ *
228
+ * This feature allows you to digitally multiplex the fan output.
229
+ * The multiplexer is automatically switched at tool-change.
230
+ * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans.
231
+ */
232
+#define FANMUX0_PIN -1
233
+#define FANMUX1_PIN -1
234
+#define FANMUX2_PIN -1
235
+
236
+/**
224 237
  * M355 Case Light on-off / brightness
225 238
  */
226 239
 //#define CASE_LIGHT_ENABLE
@@ -246,48 +259,49 @@
246 259
 
247 260
 //#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
248 261
 
249
-// Dual X Steppers
250
-// Uncomment this option to drive two X axis motors.
251
-// The next unused E driver will be assigned to the second X stepper.
262
+/**
263
+ * Dual Steppers / Dual Endstops
264
+ *
265
+ * This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
266
+ *
267
+ * For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
268
+ * spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
269
+ * set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
270
+ * that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
271
+ *
272
+ * Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
273
+ * this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
274
+ * in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
275
+ */
276
+
252 277
 //#define X_DUAL_STEPPER_DRIVERS
253 278
 #if ENABLED(X_DUAL_STEPPER_DRIVERS)
254
-  // Set true if the two X motors need to rotate in opposite directions
255
-  #define INVERT_X2_VS_X_DIR true
279
+  #define INVERT_X2_VS_X_DIR true   // Set 'true' if X motors should rotate in opposite directions
280
+  //#define X_DUAL_ENDSTOPS
281
+  #if ENABLED(X_DUAL_ENDSTOPS)
282
+    #define X2_USE_ENDSTOP _XMAX_
283
+    #define X_DUAL_ENDSTOPS_ADJUSTMENT  0
284
+  #endif
256 285
 #endif
257 286
 
258
-// Dual Y Steppers
259
-// Uncomment this option to drive two Y axis motors.
260
-// The next unused E driver will be assigned to the second Y stepper.
261 287
 //#define Y_DUAL_STEPPER_DRIVERS
262 288
 #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
263
-  // Set true if the two Y motors need to rotate in opposite directions
264
-  #define INVERT_Y2_VS_Y_DIR true
289
+  #define INVERT_Y2_VS_Y_DIR true   // Set 'true' if Y motors should rotate in opposite directions
290
+  //#define Y_DUAL_ENDSTOPS
291
+  #if ENABLED(Y_DUAL_ENDSTOPS)
292
+    #define Y2_USE_ENDSTOP _YMAX_
293
+    #define Y_DUAL_ENDSTOPS_ADJUSTMENT  0
294
+  #endif
265 295
 #endif
266 296
 
267
-// A single Z stepper driver is usually used to drive 2 stepper motors.
268
-// Uncomment this option to use a separate stepper driver for each Z axis motor.
269
-// The next unused E driver will be assigned to the second Z stepper.
270 297
 //#define Z_DUAL_STEPPER_DRIVERS
271
-
272 298
 #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
273
-
274
-  // Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper.
275
-  // That way the machine is capable to align the bed during home, since both Z steppers are homed.
276
-  // There is also an implementation of M666 (software endstops adjustment) to this feature.
277
-  // After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
278
-  // One just need to home the Z axis and measure the distance difference between both Z axis and apply the math: Z adjust = Z - Z2.
279
-  // If the Z stepper axis is closer to the bed, the measure Z > Z2 (yes, it is.. think about it) and the Z adjust would be positive.
280
-  // Play a little bit with small adjustments (0.5mm) and check the behaviour.
281
-  // The M119 (endstops report) will start reporting the Z2 Endstop as well.
282
-
283 299
   //#define Z_DUAL_ENDSTOPS
284
-
285 300
   #if ENABLED(Z_DUAL_ENDSTOPS)
286 301
     #define Z2_USE_ENDSTOP _XMAX_
287
-    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0  // use M666 command to determine/test this value
302
+    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0
288 303
   #endif
289
-
290
-#endif // Z_DUAL_STEPPER_DRIVERS
304
+#endif
291 305
 
292 306
 // Enable this for dual x-carriage printers.
293 307
 // A dual x-carriage design has the advantage that the inactive extruder can be parked which
@@ -334,12 +348,12 @@
334 348
 
335 349
 // @section homing
336 350
 
337
-//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
351
+// Homing hits each endstop, retracts by these distances, then does a slower bump.
338 352
 #define X_HOME_BUMP_MM 5
339 353
 #define Y_HOME_BUMP_MM 5
340 354
 #define Z_HOME_BUMP_MM 2
341
-#define HOMING_BUMP_DIVISOR {2, 2, 4}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
342
-//#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
355
+#define HOMING_BUMP_DIVISOR { 2, 2, 4 }  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
356
+//#define QUICK_HOME                     // If homing includes X and Y, do a diagonal move initially
343 357
 
344 358
 // When G28 is called, this option will make Y home before X
345 359
 //#define HOME_Y_BEFORE_X
@@ -394,7 +408,7 @@
394 408
 // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
395 409
 // of the buffer and all stops. This should not be much greater than zero and should only be changed
396 410
 // if unwanted behavior is observed on a user's machine when running at very slow speeds.
397
-#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
411
+#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
398 412
 
399 413
 // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
400 414
 #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
@@ -423,8 +437,21 @@
423 437
 //#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 }   // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
424 438
 //#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 }    // Default drive percent - X, Y, Z, E axis
425 439
 
426
-// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
440
+// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
427 441
 //#define DIGIPOT_I2C
442
+#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
443
+  /**
444
+   * Common slave addresses:
445
+   *
446
+   *                    A   (A shifted)   B   (B shifted)  IC
447
+   * Smoothie          0x2C (0x58)       0x2D (0x5A)       MCP4451
448
+   * AZTEEG_X3_PRO     0x2C (0x58)       0x2E (0x5C)       MCP4451
449
+   * MIGHTYBOARD_REVE  0x2F (0x5E)                         MCP4018
450
+   */
451
+  #define DIGIPOT_I2C_ADDRESS_A 0x2C  // unshifted slave address for first DIGIPOT
452
+  #define DIGIPOT_I2C_ADDRESS_B 0x2D  // unshifted slave address for second DIGIPOT
453
+#endif
454
+
428 455
 //#define DIGIPOT_MCP4018          // Requires library from https://github.com/stawel/SlowSoftI2CMaster
429 456
 #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4     AZTEEG_X3_PRO: 8
430 457
 // Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
@@ -455,6 +482,23 @@
455 482
 // The timeout (in ms) to return to the status screen from sub-menus
456 483
 //#define LCD_TIMEOUT_TO_STATUS 15000
457 484
 
485
+/**
486
+ * LED Control Menu
487
+ * Enable this feature to add LED Control to the LCD menu
488
+ */
489
+//#define LED_CONTROL_MENU
490
+#if ENABLED(LED_CONTROL_MENU)
491
+  #define LED_COLOR_PRESETS                 // Enable the Preset Color menu option
492
+  #if ENABLED(LED_COLOR_PRESETS)
493
+    #define LED_USER_PRESET_RED        255  // User defined RED value
494
+    #define LED_USER_PRESET_GREEN      128  // User defined GREEN value
495
+    #define LED_USER_PRESET_BLUE         0  // User defined BLUE value
496
+    #define LED_USER_PRESET_WHITE      255  // User defined WHITE value
497
+    #define LED_USER_PRESET_BRIGHTNESS 255  // User defined intensity
498
+    //#define LED_USER_PRESET_STARTUP       // Have the printer display the user preset color on startup
499
+  #endif
500
+#endif // LED_CONTROL_MENU
501
+
458 502
 #if ENABLED(SDSUPPORT)
459 503
 
460 504
   // Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -464,12 +508,14 @@
464 508
   // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
465 509
   //#define SD_DETECT_INVERTED
466 510
 
467
-  #define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
511
+  #define SD_FINISHED_STEPPERRELEASE true          // Disable steppers when SD Print is finished
468 512
   #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
469 513
 
470
-  #define SDCARD_RATHERRECENTFIRST  //reverse file order of sd card menu display. Its sorted practically after the file system block order.
471
-  // if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that.
472
-  // using:
514
+  // Reverse SD sort to show "more recent" files first, according to the card's FAT.
515
+  // Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
516
+  #define SDCARD_RATHERRECENTFIRST
517
+
518
+  // Add an option in the menu to run all auto#.g files
473 519
   //#define MENU_ADDAUTOSTART
474 520
 
475 521
   /**
@@ -499,13 +545,15 @@
499 545
 
500 546
   // SD Card Sorting options
501 547
   #if ENABLED(SDCARD_SORT_ALPHA)
502
-    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256).
548
+    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256). Costs 27 bytes each.
503 549
     #define FOLDER_SORTING     -1     // -1=above  0=none  1=below
504 550
     #define SDSORT_GCODE       false  // Allow turning sorting on/off with LCD and M34 g-code.
505 551
     #define SDSORT_USES_RAM    false  // Pre-allocate a static array for faster pre-sorting.
506 552
     #define SDSORT_USES_STACK  false  // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
507 553
     #define SDSORT_CACHE_NAMES false  // Keep sorted items in RAM longer for speedy performance. Most expensive option.
508 554
     #define SDSORT_DYNAMIC_RAM false  // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
555
+    #define SDSORT_CACHE_VFATS 2      // Maximum number of 13-byte VFAT entries to use for sorting.
556
+                                      // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
509 557
   #endif
510 558
 
511 559
   // Show a progress bar on HD44780 LCDs for SD printing
@@ -524,14 +572,29 @@
524 572
     //#define LCD_PROGRESS_BAR_TEST
525 573
   #endif
526 574
 
575
+  // Add an 'M73' G-code to set the current percentage
576
+  //#define LCD_SET_PROGRESS_MANUALLY
577
+
527 578
   // This allows hosts to request long names for files and folders with M33
528 579
   //#define LONG_FILENAME_HOST_SUPPORT
529 580
 
530
-  // This option allows you to abort SD printing when any endstop is triggered.
531
-  // This feature must be enabled with "M540 S1" or from the LCD menu.
532
-  // To have any effect, endstops must be enabled during SD printing.
581
+  // Enable this option to scroll long filenames in the SD card menu
582
+  //#define SCROLL_LONG_FILENAMES
583
+
584
+  /**
585
+   * This option allows you to abort SD printing when any endstop is triggered.
586
+   * This feature must be enabled with "M540 S1" or from the LCD menu.
587
+   * To have any effect, endstops must be enabled during SD printing.
588
+   */
533 589
   //#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
534 590
 
591
+  /**
592
+   * This option makes it easier to print the same SD Card file again.
593
+   * On print completion the LCD Menu will open with the file selected.
594
+   * You can just click to start the print, or navigate elsewhere.
595
+   */
596
+  //#define SD_REPRINT_LAST_SELECTED_FILE
597
+
535 598
 #endif // SDSUPPORT
536 599
 
537 600
 /**
@@ -564,6 +627,10 @@
564 627
   // Enable this option and reduce the value to optimize screen updates.
565 628
   // The normal delay is 10µs. Use the lowest value that still gives a reliable display.
566 629
   //#define DOGM_SPI_DELAY_US 5
630
+
631
+  // Swap the CW/CCW indicators in the graphics overlay
632
+  //#define OVERLAY_GFX_REVERSE
633
+
567 634
 #endif // DOGLCD
568 635
 
569 636
 // @section safety
@@ -590,31 +657,18 @@
590 657
  */
591 658
 //#define BABYSTEPPING
592 659
 #if ENABLED(BABYSTEPPING)
593
-  #define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
594
-  #define BABYSTEP_INVERT_Z false  // Change if Z babysteps should go the other way
595
-  #define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
596
-  //#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
660
+  //#define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
661
+  #define BABYSTEP_INVERT_Z false    // Change if Z babysteps should go the other way
662
+  #define BABYSTEP_MULTIPLICATOR 1   // Babysteps are very small. Increase for faster motion.
663
+  //#define BABYSTEP_ZPROBE_OFFSET   // Enable to combine M851 and Babystepping
597 664
   //#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
598 665
   #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
599 666
                                         // Note: Extra time may be added to mitigate controller latency.
667
+  //#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
600 668
 #endif
601 669
 
602 670
 // @section extruder
603 671
 
604
-// extruder advance constant (s2/mm3)
605
-//
606
-// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
607
-//
608
-// Hooke's law says:    force = k * distance
609
-// Bernoulli's principle says:  v ^ 2 / 2 + g . h + pressure / density = constant
610
-// so: v ^ 2 is proportional to number of steps we advance the extruder
611
-//#define ADVANCE
612
-
613
-#if ENABLED(ADVANCE)
614
-  #define EXTRUDER_ADVANCE_K .0
615
-  #define D_FILAMENT 2.85
616
-#endif
617
-
618 672
 /**
619 673
  * Implementation of linear pressure control
620 674
  *
@@ -648,7 +702,7 @@
648 702
    *
649 703
    * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
650 704
    *
651
-   * Slic3r (including Prusa Slic3r) produces Gcode compatible with the automatic mode.
705
+   * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
652 706
    * Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
653 707
    */
654 708
   #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
@@ -657,23 +711,18 @@
657 711
 
658 712
 // @section leveling
659 713
 
660
-// Default mesh area is an area with an inset margin on the print area.
661
-// Below are the macros that are used to define the borders for the mesh area,
662
-// made available here for specialized needs, ie dual extruder setup.
663
-#if ENABLED(MESH_BED_LEVELING)
664
-  #define MESH_MIN_X (X_MIN_POS + MESH_INSET)
665
-  #define MESH_MAX_X (X_MAX_POS - (MESH_INSET))
666
-  #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET)
667
-  #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET))
668
-#elif ENABLED(AUTO_BED_LEVELING_UBL)
669
-  #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET)
670
-  #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET))
671
-  #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET)
672
-  #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET))
673
-
674
-  // If this is defined, the currently active mesh will be saved in the
675
-  // current slot on M500.
676
-  #define UBL_SAVE_ACTIVE_ON_M500
714
+#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
715
+  #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
716
+#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
717
+  #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
718
+#endif
719
+
720
+#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
721
+  // Override the mesh area if the automatic (max) area is too large
722
+  //#define MESH_MIN_X MESH_INSET
723
+  //#define MESH_MIN_Y MESH_INSET
724
+  //#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
725
+  //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
677 726
 #endif
678 727
 
679 728
 // @section extras
@@ -693,7 +742,7 @@
693 742
 //#define BEZIER_CURVE_SUPPORT
694 743
 
695 744
 // G38.2 and G38.3 Probe Target
696
-// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
745
+// Set MULTIPLE_PROBING if you want G38 to double touch
697 746
 //#define G38_PROBE_TARGET
698 747
 #if ENABLED(G38_PROBE_TARGET)
699 748
   #define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
@@ -718,7 +767,7 @@
718 767
 // @section hidden
719 768
 
720 769
 // The number of linear motions that can be in the plan at any give time.
721
-// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
770
+// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
722 771
 #if ENABLED(SDSUPPORT)
723 772
   #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
724 773
 #else
@@ -731,7 +780,7 @@
731 780
 #define MAX_CMD_SIZE 96
732 781
 #define BUFSIZE 4
733 782
 
734
-// Transfer Buffer Size
783
+// Transmission to Host Buffer Size
735 784
 // To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0.
736 785
 // To buffer a simple "ok" you need 4 bytes.
737 786
 // For ADVANCED_OK (M105) you need 32 bytes.
@@ -740,6 +789,28 @@
740 789
 // :[0, 2, 4, 8, 16, 32, 64, 128, 256]
741 790
 #define TX_BUFFER_SIZE 0
742 791
 
792
+// Host Receive Buffer Size
793
+// Without XON/XOFF flow control (see SERIAL_XON_XOFF below) 32 bytes should be enough.
794
+// To use flow control, set this buffer size to at least 1024 bytes.
795
+// :[0, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048]
796
+//#define RX_BUFFER_SIZE 1024
797
+
798
+#if RX_BUFFER_SIZE >= 1024
799
+  // Enable to have the controller send XON/XOFF control characters to
800
+  // the host to signal the RX buffer is becoming full.
801
+  //#define SERIAL_XON_XOFF
802
+#endif
803
+
804
+#if ENABLED(SDSUPPORT)
805
+  // Enable this option to collect and display the maximum
806
+  // RX queue usage after transferring a file to SD.
807
+  //#define SERIAL_STATS_MAX_RX_QUEUED
808
+
809
+  // Enable this option to collect and display the number
810
+  // of dropped bytes after a file transfer to SD.
811
+  //#define SERIAL_STATS_DROPPED_RX
812
+#endif
813
+
743 814
 // Enable an emergency-command parser to intercept certain commands as they
744 815
 // enter the serial receive buffer, so they cannot be blocked.
745 816
 // Currently handles M108, M112, M410
@@ -755,27 +826,47 @@
755 826
 // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary.
756 827
 //#define ADVANCED_OK
757 828
 
758
-// @section fwretract
759
-
760
-// Firmware based and LCD controlled retract
761
-// M207 and M208 can be used to define parameters for the retraction.
762
-// The retraction can be called by the slicer using G10 and G11
763
-// until then, intended retractions can be detected by moves that only extrude and the direction.
764
-// the moves are than replaced by the firmware controlled ones.
829
+// @section extras
765 830
 
766
-//#define FWRETRACT  //ONLY PARTIALLY TESTED
831
+/**
832
+ * Firmware-based and LCD-controlled retract
833
+ *
834
+ * Add G10 / G11 commands for automatic firmware-based retract / recover.
835
+ * Use M207 and M208 to define parameters for retract / recover.
836
+ *
837
+ * Use M209 to enable or disable auto-retract.
838
+ * With auto-retract enabled, all G1 E moves within the set range
839
+ * will be converted to firmware-based retract/recover moves.
840
+ *
841
+ * Be sure to turn off auto-retract during filament change.
842
+ *
843
+ * Note that M207 / M208 / M209 settings are saved to EEPROM.
844
+ *
845
+ */
846
+//#define FWRETRACT  // ONLY PARTIALLY TESTED
767 847
 #if ENABLED(FWRETRACT)
768
-  #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
769
-  #define RETRACT_LENGTH 3               //default retract length (positive mm)
770
-  #define RETRACT_LENGTH_SWAP 13         //default swap retract length (positive mm), for extruder change
771
-  #define RETRACT_FEEDRATE 45            //default feedrate for retracting (mm/s)
772
-  #define RETRACT_ZLIFT 0                //default retract Z-lift
773
-  #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
774
-  #define RETRACT_RECOVER_LENGTH_SWAP 0  //default additional swap recover length (mm, added to retract length when recovering from extruder change)
775
-  #define RETRACT_RECOVER_FEEDRATE 8     //default feedrate for recovering from retraction (mm/s)
848
+  #define MIN_AUTORETRACT 0.1             // When auto-retract is on, convert E moves of this length and over
849
+  #define MAX_AUTORETRACT 10.0            // Upper limit for auto-retract conversion
850
+  #define RETRACT_LENGTH 3                // Default retract length (positive mm)
851
+  #define RETRACT_LENGTH_SWAP 13          // Default swap retract length (positive mm), for extruder change
852
+  #define RETRACT_FEEDRATE 45             // Default feedrate for retracting (mm/s)
853
+  #define RETRACT_ZLIFT 0                 // Default retract Z-lift
854
+  #define RETRACT_RECOVER_LENGTH 0        // Default additional recover length (mm, added to retract length when recovering)
855
+  #define RETRACT_RECOVER_LENGTH_SWAP 0   // Default additional swap recover length (mm, added to retract length when recovering from extruder change)
856
+  #define RETRACT_RECOVER_FEEDRATE 8      // Default feedrate for recovering from retraction (mm/s)
857
+  #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
776 858
 #endif
777 859
 
778 860
 /**
861
+ * Extra Fan Speed
862
+ * Adds a secondary fan speed for each print-cooling fan.
863
+ *   'M106 P<fan> T3-255' : Set a secondary speed for <fan>
864
+ *   'M106 P<fan> T2'     : Use the set secondary speed
865
+ *   'M106 P<fan> T1'     : Restore the previous fan speed
866
+ */
867
+//#define EXTRA_FAN_SPEED
868
+
869
+/**
779 870
  * Advanced Pause
780 871
  * Experimental feature for filament change support and for parking the nozzle when paused.
781 872
  * Adds the GCode M600 for initiating filament change.
@@ -885,7 +976,7 @@
885 976
 
886 977
 #endif
887 978
 
888
-// @section TMC2130
979
+// @section TMC2130, TMC2208
889 980
 
890 981
 /**
891 982
  * Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
@@ -899,7 +990,19 @@
899 990
  */
900 991
 //#define HAVE_TMC2130
901 992
 
902
-#if ENABLED(HAVE_TMC2130)
993
+/**
994
+ * Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
995
+ * Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
996
+ * To use the reading capabilities, also connect #_SERIAL_RX_PIN
997
+ * to #_SERIAL_TX_PIN with a 1K resistor.
998
+ * The drivers can also be used with hardware serial.
999
+ *
1000
+ * You'll also need the TMC2208Stepper Arduino library
1001
+ * (https://github.com/teemuatlut/TMC2208Stepper).
1002
+ */
1003
+//#define HAVE_TMC2208
1004
+
1005
+#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
903 1006
 
904 1007
   // CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
905 1008
   //#define X_IS_TMC2130
@@ -914,46 +1017,58 @@
914 1017
   //#define E3_IS_TMC2130
915 1018
   //#define E4_IS_TMC2130
916 1019
 
1020
+  //#define X_IS_TMC2208
1021
+  //#define X2_IS_TMC2208
1022
+  //#define Y_IS_TMC2208
1023
+  //#define Y2_IS_TMC2208
1024
+  //#define Z_IS_TMC2208
1025
+  //#define Z2_IS_TMC2208
1026
+  //#define E0_IS_TMC2208
1027
+  //#define E1_IS_TMC2208
1028
+  //#define E2_IS_TMC2208
1029
+  //#define E3_IS_TMC2208
1030
+  //#define E4_IS_TMC2208
1031
+
917 1032
   /**
918 1033
    * Stepper driver settings
919 1034
    */
920 1035
 
921 1036
   #define R_SENSE           0.11  // R_sense resistor for SilentStepStick2130
922 1037
   #define HOLD_MULTIPLIER    0.5  // Scales down the holding current from run current
923
-  #define INTERPOLATE          1  // Interpolate X/Y/Z_MICROSTEPS to 256
1038
+  #define INTERPOLATE       true  // Interpolate X/Y/Z_MICROSTEPS to 256
924 1039
 
925
-  #define X_CURRENT         1000  // rms current in mA. Multiply by 1.41 for peak current.
1040
+  #define X_CURRENT          800  // rms current in mA. Multiply by 1.41 for peak current.
926 1041
   #define X_MICROSTEPS        16  // 0..256
927 1042
 
928
-  #define Y_CURRENT         1000
1043
+  #define Y_CURRENT          800
929 1044
   #define Y_MICROSTEPS        16
930 1045
 
931
-  #define Z_CURRENT         1000
1046
+  #define Z_CURRENT          800
932 1047
   #define Z_MICROSTEPS        16
933 1048
 
934
-  //#define X2_CURRENT      1000
935
-  //#define X2_MICROSTEPS     16
1049
+  #define X2_CURRENT         800
1050
+  #define X2_MICROSTEPS       16
936 1051
 
937
-  //#define Y2_CURRENT      1000
938
-  //#define Y2_MICROSTEPS     16
1052
+  #define Y2_CURRENT         800
1053
+  #define Y2_MICROSTEPS       16
939 1054
 
940
-  //#define Z2_CURRENT      1000
941
-  //#define Z2_MICROSTEPS     16
1055
+  #define Z2_CURRENT         800
1056
+  #define Z2_MICROSTEPS       16
942 1057
 
943
-  //#define E0_CURRENT      1000
944
-  //#define E0_MICROSTEPS     16
1058
+  #define E0_CURRENT         800
1059
+  #define E0_MICROSTEPS       16
945 1060
 
946
-  //#define E1_CURRENT      1000
947
-  //#define E1_MICROSTEPS     16
1061
+  #define E1_CURRENT         800
1062
+  #define E1_MICROSTEPS       16
948 1063
 
949
-  //#define E2_CURRENT      1000
950
-  //#define E2_MICROSTEPS     16
1064
+  #define E2_CURRENT         800
1065
+  #define E2_MICROSTEPS       16
951 1066
 
952
-  //#define E3_CURRENT      1000
953
-  //#define E3_MICROSTEPS     16
1067
+  #define E3_CURRENT         800
1068
+  #define E3_MICROSTEPS       16
954 1069
 
955
-  //#define E4_CURRENT      1000
956
-  //#define E4_MICROSTEPS     16
1070
+  #define E4_CURRENT         800
1071
+  #define E4_MICROSTEPS       16
957 1072
 
958 1073
   /**
959 1074
    * Use Trinamic's ultra quiet stepping mode.
@@ -962,24 +1077,22 @@
962 1077
   #define STEALTHCHOP
963 1078
 
964 1079
   /**
965
-   * Let Marlin automatically control stepper current.
966
-   * This is still an experimental feature.
967
-   * Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
968
-   * then decrease current by CURRENT_STEP until temperature prewarn is cleared.
969
-   * Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
1080
+   * Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
1081
+   * like overtemperature and short to ground. TMC2208 requires hardware serial.
1082
+   * In the case of overtemperature Marlin can decrease the driver current until error condition clears.
1083
+   * Other detected conditions can be used to stop the current print.
970 1084
    * Relevant g-codes:
971 1085
    * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
972
-   * M906 S1 - Start adjusting current
973
-   * M906 S0 - Stop adjusting current
974 1086
    * M911 - Report stepper driver overtemperature pre-warn condition.
975 1087
    * M912 - Clear stepper driver overtemperature pre-warn condition flag.
1088
+   * M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
976 1089
    */
977
-  //#define AUTOMATIC_CURRENT_CONTROL
1090
+  //#define MONITOR_DRIVER_STATUS
978 1091
 
979
-  #if ENABLED(AUTOMATIC_CURRENT_CONTROL)
980
-    #define CURRENT_STEP          50  // [mA]
981
-    #define AUTO_ADJUST_MAX     1300  // [mA], 1300mA_rms = 1840mA_peak
1092
+  #if ENABLED(MONITOR_DRIVER_STATUS)
1093
+    #define CURRENT_STEP_DOWN     50  // [mA]
982 1094
     #define REPORT_CURRENT_CHANGE
1095
+    #define STOP_ON_ERROR
983 1096
   #endif
984 1097
 
985 1098
   /**
@@ -994,8 +1107,8 @@
994 1107
   #define X2_HYBRID_THRESHOLD    100
995 1108
   #define Y_HYBRID_THRESHOLD     100
996 1109
   #define Y2_HYBRID_THRESHOLD    100
997
-  #define Z_HYBRID_THRESHOLD       4
998
-  #define Z2_HYBRID_THRESHOLD      4
1110
+  #define Z_HYBRID_THRESHOLD       3
1111
+  #define Z2_HYBRID_THRESHOLD      3
999 1112
   #define E0_HYBRID_THRESHOLD     30
1000 1113
   #define E1_HYBRID_THRESHOLD     30
1001 1114
   #define E2_HYBRID_THRESHOLD     30
@@ -1005,7 +1118,7 @@
1005 1118
   /**
1006 1119
    * Use stallGuard2 to sense an obstacle and trigger an endstop.
1007 1120
    * You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
1008
-   * If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
1121
+   * X and Y homing will always be done in spreadCycle mode.
1009 1122
    *
1010 1123
    * X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
1011 1124
    * Higher values make the system LESS sensitive.
@@ -1014,27 +1127,34 @@
1014 1127
    * It is advised to set X/Y_HOME_BUMP_MM to 0.
1015 1128
    * M914 X/Y to live tune the setting
1016 1129
    */
1017
-  //#define SENSORLESS_HOMING
1130
+  //#define SENSORLESS_HOMING // TMC2130 only
1018 1131
 
1019 1132
   #if ENABLED(SENSORLESS_HOMING)
1020
-    #define X_HOMING_SENSITIVITY  19
1021
-    #define Y_HOMING_SENSITIVITY  19
1133
+    #define X_HOMING_SENSITIVITY  8
1134
+    #define Y_HOMING_SENSITIVITY  8
1022 1135
   #endif
1023 1136
 
1024 1137
   /**
1138
+   * Enable M122 debugging command for TMC stepper drivers.
1139
+   * M122 S0/1 will enable continous reporting.
1140
+   */
1141
+  //#define TMC_DEBUG
1142
+
1143
+  /**
1025 1144
    * You can set your own advanced settings by filling in predefined functions.
1026 1145
    * A list of available functions can be found on the library github page
1027 1146
    * https://github.com/teemuatlut/TMC2130Stepper
1147
+   * https://github.com/teemuatlut/TMC2208Stepper
1028 1148
    *
1029 1149
    * Example:
1030
-   * #define TMC2130_ADV() { \
1150
+   * #define TMC_ADV() { \
1031 1151
    *   stepperX.diag0_temp_prewarn(1); \
1032
-   *   stepperX.interpolate(0); \
1152
+   *   stepperY.interpolate(0); \
1033 1153
    * }
1034 1154
    */
1035
-  #define  TMC2130_ADV() {  }
1155
+  #define  TMC_ADV() {  }
1036 1156
 
1037
-#endif // HAVE_TMC2130
1157
+#endif // TMC2130 || TMC2208
1038 1158
 
1039 1159
 // @section L6470
1040 1160
 
@@ -1199,6 +1319,48 @@
1199 1319
 #endif
1200 1320
 
1201 1321
 /**
1322
+ * Filament Width Sensor
1323
+ *
1324
+ * Measures the filament width in real-time and adjusts
1325
+ * flow rate to compensate for any irregularities.
1326
+ *
1327
+ * Also allows the measured filament diameter to set the
1328
+ * extrusion rate, so the slicer only has to specify the
1329
+ * volume.
1330
+ *
1331
+ * Only a single extruder is supported at this time.
1332
+ *
1333
+ *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1334
+ *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1335
+ * 301 RAMBO       : Analog input 3
1336
+ *
1337
+ * Note: May require analog pins to be defined for other boards.
1338
+ */
1339
+//#define FILAMENT_WIDTH_SENSOR
1340
+
1341
+#if ENABLED(FILAMENT_WIDTH_SENSOR)
1342
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
1343
+  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1344
+
1345
+  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1346
+  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1347
+  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1348
+
1349
+  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1350
+
1351
+  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1352
+  //#define FILAMENT_LCD_DISPLAY
1353
+#endif
1354
+
1355
+/**
1356
+ * CNC Coordinate Systems
1357
+ *
1358
+ * Enables G53 and G54-G59.3 commands to select coordinate systems
1359
+ * and G92.1 to reset the workspace to native machine space.
1360
+ */
1361
+//#define CNC_COORDINATE_SYSTEMS
1362
+
1363
+/**
1202 1364
  * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
1203 1365
  */
1204 1366
 //#define PINS_DEBUGGING
@@ -1251,6 +1413,8 @@
1251 1413
 //#define CUSTOM_USER_MENUS
1252 1414
 #if ENABLED(CUSTOM_USER_MENUS)
1253 1415
   #define USER_SCRIPT_DONE "M117 User Script Done"
1416
+  #define USER_SCRIPT_AUDIBLE_FEEDBACK
1417
+  //#define USER_SCRIPT_RETURN  // Return to status screen after a script
1254 1418
 
1255 1419
   #define USER_DESC_1 "Home & UBL Info"
1256 1420
   #define USER_GCODE_1 "G28\nG29 W"
@@ -1278,6 +1442,7 @@
1278 1442
 //===========================================================================
1279 1443
 //====================== I2C Position Encoder Settings ======================
1280 1444
 //===========================================================================
1445
+
1281 1446
 /**
1282 1447
  *  I2C position encoders for closed loop control.
1283 1448
  *  Developed by Chris Barr at Aus3D.
@@ -1358,4 +1523,45 @@
1358 1523
 
1359 1524
 #endif // I2C_POSITION_ENCODERS
1360 1525
 
1526
+/**
1527
+ * MAX7219 Debug Matrix
1528
+ *
1529
+ * Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
1530
+ * display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
1531
+ *
1532
+ * Fully assembled MAX7219 boards can be found on the internet for under $2(US).
1533
+ * For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
1534
+ */
1535
+//#define MAX7219_DEBUG
1536
+#if ENABLED(MAX7219_DEBUG)
1537
+  #define MAX7219_CLK_PIN   64  // 77 on Re-ARM       // Configuration of the 3 pins to control the display
1538
+  #define MAX7219_DIN_PIN   57  // 78 on Re-ARM
1539
+  #define MAX7219_LOAD_PIN  44  // 79 on Re-ARM
1540
+
1541
+  /**
1542
+   * Sample debug features
1543
+   * If you add more debug displays, be careful to avoid conflicts!
1544
+   */
1545
+  #define MAX7219_DEBUG_PRINTER_ALIVE    // Blink corner LED of 8x8 matrix to show that the firmware is functioning
1546
+  #define MAX7219_DEBUG_STEPPER_HEAD  3  // Show the stepper queue head position on this and the next LED matrix row
1547
+  #define MAX7219_DEBUG_STEPPER_TAIL  5  // Show the stepper queue tail position on this and the next LED matrix row
1548
+
1549
+  #define MAX7219_DEBUG_STEPPER_QUEUE 0  // Show the current stepper queue depth on this and the next LED matrix row
1550
+                                         // If you experience stuttering, reboots, etc. this option can reveal how
1551
+                                         // tweaks made to the configuration are affecting the printer in real-time.
1552
+#endif
1553
+
1554
+/**
1555
+ * NanoDLP Sync support
1556
+ *
1557
+ * Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
1558
+ * string to enable synchronization with DLP projector exposure. This change will allow to use
1559
+ * [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
1560
+ */
1561
+//#define NANODLP_Z_SYNC
1562
+#if ENABLED(NANODLP_Z_SYNC)
1563
+  //#define NANODLP_ALL_AXIS  // Enables "Z_move_comp" output on any axis move.
1564
+                              // Default behaviour is limited to Z axis only.
1565
+#endif
1566
+
1361 1567
 #endif // CONFIGURATION_ADV_H

+ 247
- 105
Marlin/example_configurations/Anet/A8/Configuration.h 파일 보기

@@ -37,7 +37,7 @@
37 37
  */
38 38
 #ifndef CONFIGURATION_H
39 39
 #define CONFIGURATION_H
40
-#define CONFIGURATION_H_VERSION 010100
40
+#define CONFIGURATION_H_VERSION 010107
41 41
 
42 42
 //===========================================================================
43 43
 //============================= Getting Started =============================
@@ -107,8 +107,9 @@
107 107
  *
108 108
  * 250000 works in most cases, but you might try a lower speed if
109 109
  * you commonly experience drop-outs during host printing.
110
+ * You may try up to 1000000 to speed up SD file transfer.
110 111
  *
111
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
112
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
112 113
  */
113 114
 #define BAUDRATE 115200
114 115
 
@@ -135,6 +136,10 @@
135 136
 // :[1, 2, 3, 4, 5]
136 137
 #define EXTRUDERS 1
137 138
 
139
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
140
+// The Anet A8 original extruder is designed for 1.75mm
141
+#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75
142
+
138 143
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
139 144
 //#define SINGLENOZZLE
140 145
 
@@ -176,6 +181,21 @@
176 181
 #endif
177 182
 
178 183
 /**
184
+ * Two separate X-carriages with extruders that connect to a moving part
185
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
186
+ */
187
+//#define PARKING_EXTRUDER
188
+#if ENABLED(PARKING_EXTRUDER)
189
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
190
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
191
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
192
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
193
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
194
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
195
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
196
+#endif
197
+
198
+/**
179 199
  * "Mixing Extruder"
180 200
  *   - Adds a new code, M165, to set the current mix factors.
181 201
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -320,8 +340,9 @@
320 340
 
321 341
 // Comment the following line to disable PID and enable bang-bang.
322 342
 #define PIDTEMP
323
-#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
324
-#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
343
+#define BANG_MAX 255     // Limits current to nozzle while in bang-bang mode; 255=full current
344
+#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
345
+#define PID_K1 0.95      // Smoothing factor within the PID
325 346
 #if ENABLED(PIDTEMP)
326 347
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
327 348
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -331,7 +352,6 @@
331 352
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
332 353
   #define PID_FUNCTIONAL_RANGE 15 // If the temperature difference between the target temperature and the actual temperature
333 354
                                   // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
334
-  #define K1 0.95 //smoothing factor within the PID
335 355
 
336 356
   // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
337 357
 
@@ -406,7 +426,7 @@
406 426
 // or to allow moving the extruder regardless of the hotend temperature.
407 427
 // *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
408 428
 #define PREVENT_COLD_EXTRUSION
409
-#define EXTRUDE_MINTEMP 170
429
+#define EXTRUDE_MINTEMP 160  // 160 guards against false tripping when the extruder fan kicks on.
410 430
 
411 431
 // This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
412 432
 // Note that for Bowden Extruders a too-small value here may prevent loading.
@@ -418,12 +438,13 @@
418 438
 //===========================================================================
419 439
 
420 440
 /**
421
- * Thermal Protection protects your printer from damage and fire if a
422
- * thermistor falls out or temperature sensors fail in any way.
441
+ * Thermal Protection provides additional protection to your printer from damage
442
+ * and fire. Marlin always includes safe min and max temperature ranges which
443
+ * protect against a broken or disconnected thermistor wire.
423 444
  *
424
- * The issue: If a thermistor falls out or a temperature sensor fails,
425
- * Marlin can no longer sense the actual temperature. Since a disconnected
426
- * thermistor reads as a low temperature, the firmware will keep the heater on.
445
+ * The issue: If a thermistor falls out, it will report the much lower
446
+ * temperature of the air in the room, and the the firmware will keep
447
+ * the heater on.
427 448
  *
428 449
  * If you get "Thermal Runaway" or "Heating failed" errors the
429 450
  * details can be tuned in Configuration_adv.h
@@ -515,7 +536,7 @@
515 536
  * Override with M92
516 537
  *                                      X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]]
517 538
  */
518
-#define DEFAULT_AXIS_STEPS_PER_UNIT   { 100, 100, 400, 95 }
539
+#define DEFAULT_AXIS_STEPS_PER_UNIT   { 100, 100, 400, 100 }
519 540
 
520 541
 /**
521 542
  * Default Max Feed Rate (mm/s)
@@ -557,14 +578,13 @@
557 578
 #define DEFAULT_ZJERK                  0.3
558 579
 #define DEFAULT_EJERK                  5.0
559 580
 
560
-
561 581
 //===========================================================================
562 582
 //============================= Z Probe Options =============================
563 583
 //===========================================================================
564 584
 // @section probes
565 585
 
566 586
 //
567
-// See http://marlinfw.org/configuration/probes.html
587
+// See http://marlinfw.org/docs/configuration/probes.html
568 588
 //
569 589
 
570 590
 /**
@@ -599,7 +619,7 @@
599 619
  * Probe Type
600 620
  *
601 621
  * Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
602
- * You must activate one of these to use Auto Bed Leveling below.
622
+ * Activate one of these to use Auto Bed Leveling below.
603 623
  */
604 624
 
605 625
 /**
@@ -630,14 +650,15 @@
630 650
 #endif
631 651
 
632 652
 /**
633
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
634
- * options selected below - will be disabled during probing so as to minimize
635
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
636
- * in current flowing through the wires).  This is likely most useful to users of the
637
- * BLTouch probe, but may also help those with inductive or other probe types.
653
+ * Enable one or more of the following if probing seems unreliable.
654
+ * Heaters and/or fans can be disabled during probing to minimize electrical
655
+ * noise. A delay can also be added to allow noise and vibration to settle.
656
+ * These options are most useful for the BLTouch probe, but may also improve
657
+ * readings with inductive probes and piezo sensors.
638 658
  */
639 659
 //#define PROBING_HEATERS_OFF       // Turn heaters off when probing
640 660
 //#define PROBING_FANS_OFF          // Turn fans off when probing
661
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
641 662
 
642 663
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
643 664
 //#define SOLENOID_PROBE
@@ -676,14 +697,16 @@
676 697
 // X and Y axis travel speed (mm/m) between probes
677 698
 #define XY_PROBE_SPEED 6000
678 699
 
679
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
700
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
680 701
 #define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
681 702
 
682 703
 // Speed for the "accurate" probe of each point
683 704
 #define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
684 705
 
685
-// Use double touch for probing
686
-//#define PROBE_DOUBLE_TOUCH
706
+// The number of probes to perform at each point.
707
+//   Set to 2 for a fast/slow probe, using the second probe result.
708
+//   Set to 3 or more for slow probes, averaging the results.
709
+//#define MULTIPLE_PROBING 2
687 710
 
688 711
 /**
689 712
  * Z probes require clearance when deploying, stowing, and moving between
@@ -750,6 +773,8 @@
750 773
 
751 774
 // @section homing
752 775
 
776
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
777
+
753 778
 //#define Z_HOMING_HEIGHT 4  // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
754 779
                              // Be sure you have this distance over your Z_MAX_POS in case.
755 780
 
@@ -761,18 +786,42 @@
761 786
 
762 787
 // @section machine
763 788
 
764
-// Travel limits after homing (units are in mm)
789
+// The size of the print bed
790
+#define X_BED_SIZE 220
791
+#define Y_BED_SIZE 220
792
+
793
+// Travel limits (mm) after homing, corresponding to endstop positions.
765 794
 #define X_MIN_POS -33
766 795
 #define Y_MIN_POS -10
767 796
 #define Z_MIN_POS 0
768
-#define X_MAX_POS 220
769
-#define Y_MAX_POS 220
797
+#define X_MAX_POS X_BED_SIZE
798
+#define Y_MAX_POS Y_BED_SIZE
770 799
 #define Z_MAX_POS 240
771 800
 
772
-// If enabled, axes won't move below MIN_POS in response to movement commands.
801
+/**
802
+ * Software Endstops
803
+ *
804
+ * - Prevent moves outside the set machine bounds.
805
+ * - Individual axes can be disabled, if desired.
806
+ * - X and Y only apply to Cartesian robots.
807
+ * - Use 'M211' to set software endstops on/off or report current state
808
+ */
809
+
810
+// Min software endstops curtail movement below minimum coordinate bounds
773 811
 #define MIN_SOFTWARE_ENDSTOPS
774
-// If enabled, axes won't move above MAX_POS in response to movement commands.
812
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
813
+  #define MIN_SOFTWARE_ENDSTOP_X
814
+  #define MIN_SOFTWARE_ENDSTOP_Y
815
+  #define MIN_SOFTWARE_ENDSTOP_Z
816
+#endif
817
+
818
+// Max software endstops curtail movement above maximum coordinate bounds
775 819
 #define MAX_SOFTWARE_ENDSTOPS
820
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
821
+  #define MAX_SOFTWARE_ENDSTOP_X
822
+  #define MAX_SOFTWARE_ENDSTOP_Y
823
+  #define MAX_SOFTWARE_ENDSTOP_Z
824
+#endif
776 825
 
777 826
 /**
778 827
  * Filament Runout Sensor
@@ -792,7 +841,7 @@
792 841
 //===========================================================================
793 842
 //=============================== Bed Leveling ==============================
794 843
 //===========================================================================
795
-// @section bedlevel
844
+// @section calibrate
796 845
 
797 846
 /**
798 847
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -818,12 +867,7 @@
818 867
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
819 868
  *   A comprehensive bed leveling system combining the features and benefits
820 869
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
821
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
822
- *   for Cartesian Printers. That said, it was primarily designed to correct
823
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
824
- *   please post an issue if something doesn't work correctly. Initially,
825
- *   you will need to set a reduced bed size so you have a rectangular area
826
- *   to test on.
870
+ *   Validation and Mesh Editing systems.
827 871
  *
828 872
  * - MESH_BED_LEVELING
829 873
  *   Probe a grid manually
@@ -850,6 +894,24 @@
850 894
   // at which point movement will be level to the machine's XY plane.
851 895
   // The height can be set with M420 Z<height>
852 896
   #define ENABLE_LEVELING_FADE_HEIGHT
897
+
898
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
899
+  // split up moves into short segments like a Delta. This follows the
900
+  // contours of the bed more closely than edge-to-edge straight moves.
901
+  #define SEGMENT_LEVELED_MOVES
902
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
903
+
904
+  /**
905
+   * Enable the G26 Mesh Validation Pattern tool.
906
+   */
907
+  //#define G26_MESH_VALIDATION   // Enable G26 mesh validation
908
+  #if ENABLED(G26_MESH_VALIDATION)
909
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
910
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
911
+    #define MESH_TEST_HOTEND_TEMP   205.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
912
+    #define MESH_TEST_BED_TEMP       60.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
913
+  #endif
914
+
853 915
 #endif
854 916
 
855 917
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -905,7 +967,9 @@
905 967
   //========================= Unified Bed Leveling ============================
906 968
   //===========================================================================
907 969
 
908
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
970
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
971
+
972
+  #define MESH_INSET 1              // Mesh inset margin on print area
909 973
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
910 974
   #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
911 975
 
@@ -916,8 +980,8 @@
916 980
   #define UBL_PROBE_PT_3_X 180
917 981
   #define UBL_PROBE_PT_3_Y 20
918 982
 
919
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
920 983
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
984
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
921 985
 
922 986
 #elif ENABLED(MESH_BED_LEVELING)
923 987
 
@@ -944,6 +1008,9 @@
944 1008
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
945 1009
 #endif
946 1010
 
1011
+// Add a menu item to move between bed corners for manual bed adjustment
1012
+//#define LEVEL_BED_CORNERS
1013
+
947 1014
 /**
948 1015
  * Commands to execute at the end of G29 probing.
949 1016
  * Useful to retract or move the Z probe out of the way.
@@ -974,14 +1041,71 @@
974 1041
 //#define Z_SAFE_HOMING
975 1042
 
976 1043
 #if ENABLED(Z_SAFE_HOMING)
977
-  #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
978
-  #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
1044
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1045
+  #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2)    // Y point for Z homing when homing all axes (G28).
979 1046
 #endif
980 1047
 
981 1048
 // Homing speeds (mm/m)
982 1049
 #define HOMING_FEEDRATE_XY (100*60)
983 1050
 #define HOMING_FEEDRATE_Z  (4*60)
984 1051
 
1052
+// @section calibrate
1053
+
1054
+/**
1055
+ * Bed Skew Compensation
1056
+ *
1057
+ * This feature corrects for misalignment in the XYZ axes.
1058
+ *
1059
+ * Take the following steps to get the bed skew in the XY plane:
1060
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1061
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1062
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1063
+ *  4. For XY_SIDE_AD measure the edge A to D
1064
+ *
1065
+ * Marlin automatically computes skew factors from these measurements.
1066
+ * Skew factors may also be computed and set manually:
1067
+ *
1068
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1069
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1070
+ *
1071
+ * If desired, follow the same procedure for XZ and YZ.
1072
+ * Use these diagrams for reference:
1073
+ *
1074
+ *    Y                     Z                     Z
1075
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1076
+ *    |    /       /        |    /       /        |    /       /
1077
+ *    |   /       /         |   /       /         |   /       /
1078
+ *    |  A-------D          |  A-------D          |  A-------D
1079
+ *    +-------------->X     +-------------->X     +-------------->Y
1080
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1081
+ */
1082
+//#define SKEW_CORRECTION
1083
+
1084
+#if ENABLED(SKEW_CORRECTION)
1085
+  // Input all length measurements here:
1086
+  #define XY_DIAG_AC 282.8427124746
1087
+  #define XY_DIAG_BD 282.8427124746
1088
+  #define XY_SIDE_AD 200
1089
+
1090
+  // Or, set the default skew factors directly here
1091
+  // to override the above measurements:
1092
+  #define XY_SKEW_FACTOR 0.0
1093
+
1094
+  //#define SKEW_CORRECTION_FOR_Z
1095
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1096
+    #define XZ_DIAG_AC 282.8427124746
1097
+    #define XZ_DIAG_BD 282.8427124746
1098
+    #define YZ_DIAG_AC 282.8427124746
1099
+    #define YZ_DIAG_BD 282.8427124746
1100
+    #define YZ_SIDE_AD 200
1101
+    #define XZ_SKEW_FACTOR 0.0
1102
+    #define YZ_SKEW_FACTOR 0.0
1103
+  #endif
1104
+
1105
+  // Enable this option for M852 to set skew at runtime
1106
+  //#define SKEW_CORRECTION_GCODE
1107
+#endif
1108
+
985 1109
 //=============================================================================
986 1110
 //============================= Additional Features ===========================
987 1111
 //=============================================================================
@@ -1008,11 +1132,12 @@
1008 1132
 //
1009 1133
 //#define HOST_KEEPALIVE_FEATURE       // Disable this if your host doesn't like keepalive messages
1010 1134
 //#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
1135
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
1011 1136
 
1012 1137
 //
1013 1138
 // M100 Free Memory Watcher
1014 1139
 //
1015
-//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1140
+//#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
1016 1141
 
1017 1142
 //
1018 1143
 // G20/G21 Inch mode support
@@ -1032,7 +1157,7 @@
1032 1157
 #define PREHEAT_1_FAN_SPEED     0 // Value from 0 to 255
1033 1158
 
1034 1159
 #define PREHEAT_2_TEMP_HOTEND 240
1035
-#define PREHEAT_2_TEMP_BED    90
1160
+#define PREHEAT_2_TEMP_BED     90
1036 1161
 #define PREHEAT_2_FAN_SPEED     0 // Value from 0 to 255
1037 1162
 
1038 1163
 /**
@@ -1157,11 +1282,11 @@
1157 1282
  *
1158 1283
  * Select the language to display on the LCD. These languages are available:
1159 1284
  *
1160
- *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
1161
- *    it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
1162
- *    zh_CN, zh_TW, test
1285
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1286
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1287
+ *    tr, uk, zh_CN, zh_TW, test
1163 1288
  *
1164
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1289
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1165 1290
  */
1166 1291
 #define LCD_LANGUAGE en
1167 1292
 
@@ -1183,7 +1308,7 @@
1183 1308
  *  - Click the controller to view the LCD menu
1184 1309
  *  - The LCD will display Japanese, Western, or Cyrillic text
1185 1310
  *
1186
- * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1311
+ * See http://marlinfw.org/docs/development/lcd_language.html
1187 1312
  *
1188 1313
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1189 1314
  */
@@ -1289,8 +1414,8 @@
1289 1414
 // Note: Test audio output with the G-Code:
1290 1415
 //  M300 S<frequency Hz> P<duration ms>
1291 1416
 //
1292
-//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
1293
-//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
1417
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
1418
+//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
1294 1419
 
1295 1420
 //
1296 1421
 // CONTROLLER TYPE: Standard
@@ -1310,12 +1435,6 @@
1310 1435
 //#define ULTIPANEL
1311 1436
 
1312 1437
 //
1313
-// Cartesio UI
1314
-// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
1315
-//
1316
-//#define CARTESIO_UI
1317
-
1318
-//
1319 1438
 // PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
1320 1439
 // http://reprap.org/wiki/PanelOne
1321 1440
 //
@@ -1400,11 +1519,19 @@
1400 1519
 //#define BQ_LCD_SMART_CONTROLLER
1401 1520
 
1402 1521
 //
1403
-// ANET_10 Controller supported displays.
1522
+// Cartesio UI
1523
+// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
1524
+//
1525
+//#define CARTESIO_UI
1526
+
1404 1527
 //
1405
-#define ANET_KEYPAD_LCD           // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1528
+// ANET and Tronxy Controller supported displays.
1529
+//
1530
+#define ZONESTAR_LCD              // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1406 1531
                                   // This LCD is known to be susceptible to electrical interference
1407 1532
                                   // which scrambles the display.  Pressing any button clears it up.
1533
+                                  // This is a LCD2004 display with 5 analog buttons.
1534
+
1408 1535
 //#define ANET_FULL_GRAPHICS_LCD  // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1409 1536
                                   // A clone of the RepRapDiscount full graphics display but with
1410 1537
                                   // different pins/wiring (see pins_ANET_10.h).
@@ -1485,6 +1612,40 @@
1485 1612
 //
1486 1613
 //#define OLED_PANEL_TINYBOY2
1487 1614
 
1615
+//
1616
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1617
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1618
+//
1619
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1620
+
1621
+//
1622
+// MKS MINI12864 with graphic controller and SD support
1623
+// http://reprap.org/wiki/MKS_MINI_12864
1624
+//
1625
+//#define MKS_MINI_12864
1626
+
1627
+//
1628
+// Factory display for Creality CR-10
1629
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1630
+//
1631
+// This is RAMPS-compatible using a single 10-pin connector.
1632
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1633
+//
1634
+//#define CR10_STOCKDISPLAY
1635
+
1636
+//
1637
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1638
+// http://reprap.org/wiki/MKS_12864OLED
1639
+//
1640
+// Tiny, but very sharp OLED display
1641
+//
1642
+//#define MKS_12864OLED
1643
+
1644
+// Silvergate GLCD controller
1645
+// http://github.com/android444/Silvergate
1646
+//
1647
+//#define SILVER_GATE_GLCD_CONTROLLER
1648
+
1488 1649
 //=============================================================================
1489 1650
 //=============================== Extra Features ==============================
1490 1651
 //=============================================================================
@@ -1541,16 +1702,22 @@
1541 1702
  * Adds the M150 command to set the LED (or LED strip) color.
1542 1703
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1543 1704
  * luminance values can be set from 0 to 255.
1705
+ * For Neopixel LED an overall brightness parameter is also available.
1544 1706
  *
1545 1707
  * *** CAUTION ***
1546 1708
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1547 1709
  *  as the Arduino cannot handle the current the LEDs will require.
1548 1710
  *  Failure to follow this precaution can destroy your Arduino!
1711
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1712
+ *  more current than the Arduino 5V linear regulator can produce.
1549 1713
  * *** CAUTION ***
1550 1714
  *
1715
+ * LED Type. Enable only one of the following two options.
1716
+ *
1551 1717
  */
1552 1718
 //#define RGB_LED
1553 1719
 //#define RGBW_LED
1720
+
1554 1721
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1555 1722
   #define RGB_LED_R_PIN 34
1556 1723
   #define RGB_LED_G_PIN 43
@@ -1558,6 +1725,17 @@
1558 1725
   #define RGB_LED_W_PIN -1
1559 1726
 #endif
1560 1727
 
1728
+// Support for Adafruit Neopixel LED driver
1729
+//#define NEOPIXEL_LED
1730
+#if ENABLED(NEOPIXEL_LED)
1731
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1732
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1733
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1734
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1735
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1736
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1737
+#endif
1738
+
1561 1739
 /**
1562 1740
  * Printer Event LEDs
1563 1741
  *
@@ -1569,68 +1747,32 @@
1569 1747
  *  - Change to green once print has finished
1570 1748
  *  - Turn off after the print has finished and the user has pushed a button
1571 1749
  */
1572
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)
1750
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1573 1751
   #define PRINTER_EVENT_LEDS
1574 1752
 #endif
1575 1753
 
1576
-/*********************************************************************\
1577
-* R/C SERVO support
1578
-* Sponsored by TrinityLabs, Reworked by codexmas
1579
-**********************************************************************/
1754
+/**
1755
+ * R/C SERVO support
1756
+ * Sponsored by TrinityLabs, Reworked by codexmas
1757
+ */
1580 1758
 
1581
-// Number of servos
1582
-//
1583
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1584
-// set it manually if you have more servos than extruders and wish to manually control some
1585
-// leaving it undefined or defining as 0 will disable the servo subsystem
1586
-// If unsure, leave commented / disabled
1587
-//
1759
+/**
1760
+ * Number of servos
1761
+ *
1762
+ * For some servo-related options NUM_SERVOS will be set automatically.
1763
+ * Set this manually if there are extra servos needing manual control.
1764
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1765
+ */
1588 1766
 //#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
1589 1767
 
1590 1768
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1591 1769
 // 300ms is a good value but you can try less delay.
1592 1770
 // If the servo can't reach the requested position, increase it.
1593
-#define SERVO_DELAY 300
1771
+#define SERVO_DELAY { 300 }
1594 1772
 
1595 1773
 // Servo deactivation
1596 1774
 //
1597 1775
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1598 1776
 //#define DEACTIVATE_SERVOS_AFTER_MOVE
1599 1777
 
1600
-/**
1601
- * Filament Width Sensor
1602
- *
1603
- * Measures the filament width in real-time and adjusts
1604
- * flow rate to compensate for any irregularities.
1605
- *
1606
- * Also allows the measured filament diameter to set the
1607
- * extrusion rate, so the slicer only has to specify the
1608
- * volume.
1609
- *
1610
- * Only a single extruder is supported at this time.
1611
- *
1612
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1613
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1614
- * 301 RAMBO       : Analog input 3
1615
- *
1616
- * Note: May require analog pins to be defined for other boards.
1617
- */
1618
-//#define FILAMENT_WIDTH_SENSOR
1619
-
1620
-#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00   // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
1621
-
1622
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1623
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1624
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1625
-
1626
-  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1627
-  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1628
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1629
-
1630
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1631
-
1632
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1633
-  //#define FILAMENT_LCD_DISPLAY
1634
-#endif
1635
-
1636 1778
 #endif // CONFIGURATION_H

+ 367
- 161
Marlin/example_configurations/Anet/A8/Configuration_adv.h 파일 보기

@@ -32,7 +32,7 @@
32 32
  */
33 33
 #ifndef CONFIGURATION_ADV_H
34 34
 #define CONFIGURATION_ADV_H
35
-#define CONFIGURATION_ADV_H_VERSION 010100
35
+#define CONFIGURATION_ADV_H_VERSION 010107
36 36
 
37 37
 // @section temperature
38 38
 
@@ -48,31 +48,36 @@
48 48
 #endif
49 49
 
50 50
 /**
51
- * Thermal Protection protects your printer from damage and fire if a
52
- * thermistor falls out or temperature sensors fail in any way.
51
+ * Thermal Protection provides additional protection to your printer from damage
52
+ * and fire. Marlin always includes safe min and max temperature ranges which
53
+ * protect against a broken or disconnected thermistor wire.
53 54
  *
54
- * The issue: If a thermistor falls out or a temperature sensor fails,
55
- * Marlin can no longer sense the actual temperature. Since a disconnected
56
- * thermistor reads as a low temperature, the firmware will keep the heater on.
55
+ * The issue: If a thermistor falls out, it will report the much lower
56
+ * temperature of the air in the room, and the the firmware will keep
57
+ * the heater on.
57 58
  *
58 59
  * The solution: Once the temperature reaches the target, start observing.
59
- * If the temperature stays too far below the target (hysteresis) for too long (period),
60
- * the firmware will halt the machine as a safety precaution.
60
+ * If the temperature stays too far below the target (hysteresis) for too
61
+ * long (period), the firmware will halt the machine as a safety precaution.
61 62
  *
62
- * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63
+ * If you get false positives for "Thermal Runaway", increase
64
+ * THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63 65
  */
64 66
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
65 67
   #define THERMAL_PROTECTION_PERIOD 60        // Seconds
66 68
   #define THERMAL_PROTECTION_HYSTERESIS 10    // Degrees Celsius
67 69
 
68 70
   /**
69
-   * Whenever an M104 or M109 increases the target temperature the firmware will wait for the
70
-   * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
71
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
72
-   * but only if the current temperature is far enough below the target for a reliable test.
71
+   * Whenever an M104, M109, or M303 increases the target temperature, the
72
+   * firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
73
+   * hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
74
+   * requires a hard reset. This test restarts with any M104/M109/M303, but only
75
+   * if the current temperature is far enough below the target for a reliable
76
+   * test.
73 77
    *
74
-   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
75
-   * WATCH_TEMP_INCREASE should not be below 2.
78
+   * If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
79
+   * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
80
+   * below 2.
76 81
    */
77 82
   #define WATCH_TEMP_PERIOD 20                // Seconds
78 83
   #define WATCH_TEMP_INCREASE 2               // Degrees Celsius
@@ -86,13 +91,7 @@
86 91
   #define THERMAL_PROTECTION_BED_HYSTERESIS 5 // Degrees Celsius
87 92
 
88 93
   /**
89
-   * Whenever an M140 or M190 increases the target temperature the firmware will wait for the
90
-   * WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
91
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
92
-   * but only if the current temperature is far enough below the target for a reliable test.
93
-   *
94
-   * If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
95
-   * WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
94
+   * As described above, except for the bed (M140/M190/M303).
96 95
    */
97 96
   #define WATCH_BED_TEMP_PERIOD 180               // Seconds
98 97
   #define WATCH_BED_TEMP_INCREASE 2               // Degrees Celsius
@@ -123,6 +122,9 @@
123 122
   #define AUTOTEMP_OLDWEIGHT 0.98
124 123
 #endif
125 124
 
125
+// Show extra position information in M114
126
+//#define M114_DETAIL
127
+
126 128
 // Show Temperature ADC value
127 129
 // Enable for M105 to include ADC values read from temperature sensors.
128 130
 //#define SHOW_TEMP_ADC_VALUES
@@ -221,6 +223,17 @@
221 223
 #define EXTRUDER_AUTO_FAN_SPEED   255  // == full speed
222 224
 
223 225
 /**
226
+ * Part-Cooling Fan Multiplexer
227
+ *
228
+ * This feature allows you to digitally multiplex the fan output.
229
+ * The multiplexer is automatically switched at tool-change.
230
+ * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans.
231
+ */
232
+#define FANMUX0_PIN -1
233
+#define FANMUX1_PIN -1
234
+#define FANMUX2_PIN -1
235
+
236
+/**
224 237
  * M355 Case Light on-off / brightness
225 238
  */
226 239
 //#define CASE_LIGHT_ENABLE
@@ -246,48 +259,49 @@
246 259
 
247 260
 //#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
248 261
 
249
-// Dual X Steppers
250
-// Uncomment this option to drive two X axis motors.
251
-// The next unused E driver will be assigned to the second X stepper.
262
+/**
263
+ * Dual Steppers / Dual Endstops
264
+ *
265
+ * This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
266
+ *
267
+ * For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
268
+ * spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
269
+ * set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
270
+ * that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
271
+ *
272
+ * Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
273
+ * this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
274
+ * in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
275
+ */
276
+
252 277
 //#define X_DUAL_STEPPER_DRIVERS
253 278
 #if ENABLED(X_DUAL_STEPPER_DRIVERS)
254
-  // Set true if the two X motors need to rotate in opposite directions
255
-  #define INVERT_X2_VS_X_DIR true
279
+  #define INVERT_X2_VS_X_DIR true   // Set 'true' if X motors should rotate in opposite directions
280
+  //#define X_DUAL_ENDSTOPS
281
+  #if ENABLED(X_DUAL_ENDSTOPS)
282
+    #define X2_USE_ENDSTOP _XMAX_
283
+    #define X_DUAL_ENDSTOPS_ADJUSTMENT  0
284
+  #endif
256 285
 #endif
257 286
 
258
-// Dual Y Steppers
259
-// Uncomment this option to drive two Y axis motors.
260
-// The next unused E driver will be assigned to the second Y stepper.
261 287
 //#define Y_DUAL_STEPPER_DRIVERS
262 288
 #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
263
-  // Set true if the two Y motors need to rotate in opposite directions
264
-  #define INVERT_Y2_VS_Y_DIR true
289
+  #define INVERT_Y2_VS_Y_DIR true   // Set 'true' if Y motors should rotate in opposite directions
290
+  //#define Y_DUAL_ENDSTOPS
291
+  #if ENABLED(Y_DUAL_ENDSTOPS)
292
+    #define Y2_USE_ENDSTOP _YMAX_
293
+    #define Y_DUAL_ENDSTOPS_ADJUSTMENT  0
294
+  #endif
265 295
 #endif
266 296
 
267
-// A single Z stepper driver is usually used to drive 2 stepper motors.
268
-// Uncomment this option to use a separate stepper driver for each Z axis motor.
269
-// The next unused E driver will be assigned to the second Z stepper.
270 297
 //#define Z_DUAL_STEPPER_DRIVERS
271
-
272 298
 #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
273
-
274
-  // Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper.
275
-  // That way the machine is capable to align the bed during home, since both Z steppers are homed.
276
-  // There is also an implementation of M666 (software endstops adjustment) to this feature.
277
-  // After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
278
-  // One just need to home the Z axis and measure the distance difference between both Z axis and apply the math: Z adjust = Z - Z2.
279
-  // If the Z stepper axis is closer to the bed, the measure Z > Z2 (yes, it is.. think about it) and the Z adjust would be positive.
280
-  // Play a little bit with small adjustments (0.5mm) and check the behaviour.
281
-  // The M119 (endstops report) will start reporting the Z2 Endstop as well.
282
-
283 299
   //#define Z_DUAL_ENDSTOPS
284
-
285 300
   #if ENABLED(Z_DUAL_ENDSTOPS)
286 301
     #define Z2_USE_ENDSTOP _XMAX_
287
-    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0  // use M666 command to determine/test this value
302
+    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0
288 303
   #endif
289
-
290
-#endif // Z_DUAL_STEPPER_DRIVERS
304
+#endif
291 305
 
292 306
 // Enable this for dual x-carriage printers.
293 307
 // A dual x-carriage design has the advantage that the inactive extruder can be parked which
@@ -334,12 +348,12 @@
334 348
 
335 349
 // @section homing
336 350
 
337
-//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
351
+// Homing hits each endstop, retracts by these distances, then does a slower bump.
338 352
 #define X_HOME_BUMP_MM 5
339 353
 #define Y_HOME_BUMP_MM 5
340 354
 #define Z_HOME_BUMP_MM 2
341
-#define HOMING_BUMP_DIVISOR {2, 2, 4}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
342
-//#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
355
+#define HOMING_BUMP_DIVISOR { 2, 2, 4 }  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
356
+//#define QUICK_HOME                     // If homing includes X and Y, do a diagonal move initially
343 357
 
344 358
 // When G28 is called, this option will make Y home before X
345 359
 //#define HOME_Y_BEFORE_X
@@ -394,7 +408,7 @@
394 408
 // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
395 409
 // of the buffer and all stops. This should not be much greater than zero and should only be changed
396 410
 // if unwanted behavior is observed on a user's machine when running at very slow speeds.
397
-#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
411
+#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
398 412
 
399 413
 // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
400 414
 #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
@@ -423,8 +437,21 @@
423 437
 //#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 }   // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
424 438
 //#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 }    // Default drive percent - X, Y, Z, E axis
425 439
 
426
-// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
440
+// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
427 441
 //#define DIGIPOT_I2C
442
+#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
443
+  /**
444
+   * Common slave addresses:
445
+   *
446
+   *                    A   (A shifted)   B   (B shifted)  IC
447
+   * Smoothie          0x2C (0x58)       0x2D (0x5A)       MCP4451
448
+   * AZTEEG_X3_PRO     0x2C (0x58)       0x2E (0x5C)       MCP4451
449
+   * MIGHTYBOARD_REVE  0x2F (0x5E)                         MCP4018
450
+   */
451
+  #define DIGIPOT_I2C_ADDRESS_A 0x2C  // unshifted slave address for first DIGIPOT
452
+  #define DIGIPOT_I2C_ADDRESS_B 0x2D  // unshifted slave address for second DIGIPOT
453
+#endif
454
+
428 455
 //#define DIGIPOT_MCP4018          // Requires library from https://github.com/stawel/SlowSoftI2CMaster
429 456
 #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4     AZTEEG_X3_PRO: 8
430 457
 // Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
@@ -455,6 +482,23 @@
455 482
 // The timeout (in ms) to return to the status screen from sub-menus
456 483
 //#define LCD_TIMEOUT_TO_STATUS 15000
457 484
 
485
+/**
486
+ * LED Control Menu
487
+ * Enable this feature to add LED Control to the LCD menu
488
+ */
489
+//#define LED_CONTROL_MENU
490
+#if ENABLED(LED_CONTROL_MENU)
491
+  #define LED_COLOR_PRESETS                 // Enable the Preset Color menu option
492
+  #if ENABLED(LED_COLOR_PRESETS)
493
+    #define LED_USER_PRESET_RED        255  // User defined RED value
494
+    #define LED_USER_PRESET_GREEN      128  // User defined GREEN value
495
+    #define LED_USER_PRESET_BLUE         0  // User defined BLUE value
496
+    #define LED_USER_PRESET_WHITE      255  // User defined WHITE value
497
+    #define LED_USER_PRESET_BRIGHTNESS 255  // User defined intensity
498
+    //#define LED_USER_PRESET_STARTUP       // Have the printer display the user preset color on startup
499
+  #endif
500
+#endif // LED_CONTROL_MENU
501
+
458 502
 #if ENABLED(SDSUPPORT)
459 503
 
460 504
   // Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -464,12 +508,14 @@
464 508
   // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
465 509
   //#define SD_DETECT_INVERTED
466 510
 
467
-  #define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
511
+  #define SD_FINISHED_STEPPERRELEASE true          // Disable steppers when SD Print is finished
468 512
   #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
469 513
 
470
-  #define SDCARD_RATHERRECENTFIRST  //reverse file order of sd card menu display. Its sorted practically after the file system block order.
471
-  // if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that.
472
-  // using:
514
+  // Reverse SD sort to show "more recent" files first, according to the card's FAT.
515
+  // Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
516
+  #define SDCARD_RATHERRECENTFIRST
517
+
518
+  // Add an option in the menu to run all auto#.g files
473 519
   //#define MENU_ADDAUTOSTART
474 520
 
475 521
   /**
@@ -499,13 +545,15 @@
499 545
 
500 546
   // SD Card Sorting options
501 547
   #if ENABLED(SDCARD_SORT_ALPHA)
502
-    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256).
548
+    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256). Costs 27 bytes each.
503 549
     #define FOLDER_SORTING     -1     // -1=above  0=none  1=below
504 550
     #define SDSORT_GCODE       false  // Allow turning sorting on/off with LCD and M34 g-code.
505 551
     #define SDSORT_USES_RAM    false  // Pre-allocate a static array for faster pre-sorting.
506 552
     #define SDSORT_USES_STACK  false  // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
507 553
     #define SDSORT_CACHE_NAMES false  // Keep sorted items in RAM longer for speedy performance. Most expensive option.
508 554
     #define SDSORT_DYNAMIC_RAM false  // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
555
+    #define SDSORT_CACHE_VFATS 2      // Maximum number of 13-byte VFAT entries to use for sorting.
556
+                                      // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
509 557
   #endif
510 558
 
511 559
   // Show a progress bar on HD44780 LCDs for SD printing
@@ -524,14 +572,29 @@
524 572
     //#define LCD_PROGRESS_BAR_TEST
525 573
   #endif
526 574
 
575
+  // Add an 'M73' G-code to set the current percentage
576
+  //#define LCD_SET_PROGRESS_MANUALLY
577
+
527 578
   // This allows hosts to request long names for files and folders with M33
528 579
   //#define LONG_FILENAME_HOST_SUPPORT
529 580
 
530
-  // This option allows you to abort SD printing when any endstop is triggered.
531
-  // This feature must be enabled with "M540 S1" or from the LCD menu.
532
-  // To have any effect, endstops must be enabled during SD printing.
581
+  // Enable this option to scroll long filenames in the SD card menu
582
+  //#define SCROLL_LONG_FILENAMES
583
+
584
+  /**
585
+   * This option allows you to abort SD printing when any endstop is triggered.
586
+   * This feature must be enabled with "M540 S1" or from the LCD menu.
587
+   * To have any effect, endstops must be enabled during SD printing.
588
+   */
533 589
   //#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
534 590
 
591
+  /**
592
+   * This option makes it easier to print the same SD Card file again.
593
+   * On print completion the LCD Menu will open with the file selected.
594
+   * You can just click to start the print, or navigate elsewhere.
595
+   */
596
+  //#define SD_REPRINT_LAST_SELECTED_FILE
597
+
535 598
 #endif // SDSUPPORT
536 599
 
537 600
 /**
@@ -564,6 +627,10 @@
564 627
   // Enable this option and reduce the value to optimize screen updates.
565 628
   // The normal delay is 10µs. Use the lowest value that still gives a reliable display.
566 629
   //#define DOGM_SPI_DELAY_US 5
630
+
631
+  // Swap the CW/CCW indicators in the graphics overlay
632
+  //#define OVERLAY_GFX_REVERSE
633
+
567 634
 #endif // DOGLCD
568 635
 
569 636
 // @section safety
@@ -590,31 +657,18 @@
590 657
  */
591 658
 //#define BABYSTEPPING
592 659
 #if ENABLED(BABYSTEPPING)
593
-  #define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
594
-  #define BABYSTEP_INVERT_Z false  // Change if Z babysteps should go the other way
595
-  #define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
596
-  //#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
660
+  //#define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
661
+  #define BABYSTEP_INVERT_Z false    // Change if Z babysteps should go the other way
662
+  #define BABYSTEP_MULTIPLICATOR 1   // Babysteps are very small. Increase for faster motion.
663
+  //#define BABYSTEP_ZPROBE_OFFSET   // Enable to combine M851 and Babystepping
597 664
   //#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
598 665
   #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
599 666
                                         // Note: Extra time may be added to mitigate controller latency.
667
+  //#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
600 668
 #endif
601 669
 
602 670
 // @section extruder
603 671
 
604
-// extruder advance constant (s2/mm3)
605
-//
606
-// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
607
-//
608
-// Hooke's law says:    force = k * distance
609
-// Bernoulli's principle says:  v ^ 2 / 2 + g . h + pressure / density = constant
610
-// so: v ^ 2 is proportional to number of steps we advance the extruder
611
-//#define ADVANCE
612
-
613
-#if ENABLED(ADVANCE)
614
-  #define EXTRUDER_ADVANCE_K .0
615
-  #define D_FILAMENT 2.85
616
-#endif
617
-
618 672
 /**
619 673
  * Implementation of linear pressure control
620 674
  *
@@ -648,7 +702,7 @@
648 702
    *
649 703
    * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
650 704
    *
651
-   * Slic3r (including Prusa Slic3r) produces Gcode compatible with the automatic mode.
705
+   * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
652 706
    * Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
653 707
    */
654 708
   #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
@@ -657,23 +711,18 @@
657 711
 
658 712
 // @section leveling
659 713
 
660
-// Default mesh area is an area with an inset margin on the print area.
661
-// Below are the macros that are used to define the borders for the mesh area,
662
-// made available here for specialized needs, ie dual extruder setup.
663
-#if ENABLED(MESH_BED_LEVELING)
664
-  #define MESH_MIN_X (X_MIN_POS + MESH_INSET)
665
-  #define MESH_MAX_X (X_MAX_POS - (MESH_INSET))
666
-  #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET)
667
-  #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET))
668
-#elif ENABLED(AUTO_BED_LEVELING_UBL)
669
-  #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET)
670
-  #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET))
671
-  #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET)
672
-  #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET))
673
-
674
-  // If this is defined, the currently active mesh will be saved in the
675
-  // current slot on M500.
676
-  #define UBL_SAVE_ACTIVE_ON_M500
714
+#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
715
+  #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
716
+#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
717
+  #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
718
+#endif
719
+
720
+#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
721
+  // Override the mesh area if the automatic (max) area is too large
722
+  //#define MESH_MIN_X MESH_INSET
723
+  //#define MESH_MIN_Y MESH_INSET
724
+  //#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
725
+  //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
677 726
 #endif
678 727
 
679 728
 // @section extras
@@ -693,7 +742,7 @@
693 742
 //#define BEZIER_CURVE_SUPPORT
694 743
 
695 744
 // G38.2 and G38.3 Probe Target
696
-// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
745
+// Set MULTIPLE_PROBING if you want G38 to double touch
697 746
 //#define G38_PROBE_TARGET
698 747
 #if ENABLED(G38_PROBE_TARGET)
699 748
   #define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
@@ -718,7 +767,7 @@
718 767
 // @section hidden
719 768
 
720 769
 // The number of linear motions that can be in the plan at any give time.
721
-// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
770
+// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
722 771
 #if ENABLED(SDSUPPORT)
723 772
   #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
724 773
 #else
@@ -731,7 +780,7 @@
731 780
 #define MAX_CMD_SIZE 96
732 781
 #define BUFSIZE 4
733 782
 
734
-// Transfer Buffer Size
783
+// Transmission to Host Buffer Size
735 784
 // To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0.
736 785
 // To buffer a simple "ok" you need 4 bytes.
737 786
 // For ADVANCED_OK (M105) you need 32 bytes.
@@ -740,6 +789,28 @@
740 789
 // :[0, 2, 4, 8, 16, 32, 64, 128, 256]
741 790
 #define TX_BUFFER_SIZE 0
742 791
 
792
+// Host Receive Buffer Size
793
+// Without XON/XOFF flow control (see SERIAL_XON_XOFF below) 32 bytes should be enough.
794
+// To use flow control, set this buffer size to at least 1024 bytes.
795
+// :[0, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048]
796
+//#define RX_BUFFER_SIZE 1024
797
+
798
+#if RX_BUFFER_SIZE >= 1024
799
+  // Enable to have the controller send XON/XOFF control characters to
800
+  // the host to signal the RX buffer is becoming full.
801
+  //#define SERIAL_XON_XOFF
802
+#endif
803
+
804
+#if ENABLED(SDSUPPORT)
805
+  // Enable this option to collect and display the maximum
806
+  // RX queue usage after transferring a file to SD.
807
+  //#define SERIAL_STATS_MAX_RX_QUEUED
808
+
809
+  // Enable this option to collect and display the number
810
+  // of dropped bytes after a file transfer to SD.
811
+  //#define SERIAL_STATS_DROPPED_RX
812
+#endif
813
+
743 814
 // Enable an emergency-command parser to intercept certain commands as they
744 815
 // enter the serial receive buffer, so they cannot be blocked.
745 816
 // Currently handles M108, M112, M410
@@ -755,27 +826,47 @@
755 826
 // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary.
756 827
 //#define ADVANCED_OK
757 828
 
758
-// @section fwretract
759
-
760
-// Firmware based and LCD controlled retract
761
-// M207 and M208 can be used to define parameters for the retraction.
762
-// The retraction can be called by the slicer using G10 and G11
763
-// until then, intended retractions can be detected by moves that only extrude and the direction.
764
-// the moves are than replaced by the firmware controlled ones.
829
+// @section extras
765 830
 
766
-//#define FWRETRACT  //ONLY PARTIALLY TESTED
831
+/**
832
+ * Firmware-based and LCD-controlled retract
833
+ *
834
+ * Add G10 / G11 commands for automatic firmware-based retract / recover.
835
+ * Use M207 and M208 to define parameters for retract / recover.
836
+ *
837
+ * Use M209 to enable or disable auto-retract.
838
+ * With auto-retract enabled, all G1 E moves within the set range
839
+ * will be converted to firmware-based retract/recover moves.
840
+ *
841
+ * Be sure to turn off auto-retract during filament change.
842
+ *
843
+ * Note that M207 / M208 / M209 settings are saved to EEPROM.
844
+ *
845
+ */
846
+//#define FWRETRACT  // ONLY PARTIALLY TESTED
767 847
 #if ENABLED(FWRETRACT)
768
-  #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
769
-  #define RETRACT_LENGTH 3               //default retract length (positive mm)
770
-  #define RETRACT_LENGTH_SWAP 13         //default swap retract length (positive mm), for extruder change
771
-  #define RETRACT_FEEDRATE 45            //default feedrate for retracting (mm/s)
772
-  #define RETRACT_ZLIFT 0                //default retract Z-lift
773
-  #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
774
-  #define RETRACT_RECOVER_LENGTH_SWAP 0  //default additional swap recover length (mm, added to retract length when recovering from extruder change)
775
-  #define RETRACT_RECOVER_FEEDRATE 8     //default feedrate for recovering from retraction (mm/s)
848
+  #define MIN_AUTORETRACT 0.1             // When auto-retract is on, convert E moves of this length and over
849
+  #define MAX_AUTORETRACT 10.0            // Upper limit for auto-retract conversion
850
+  #define RETRACT_LENGTH 3                // Default retract length (positive mm)
851
+  #define RETRACT_LENGTH_SWAP 13          // Default swap retract length (positive mm), for extruder change
852
+  #define RETRACT_FEEDRATE 45             // Default feedrate for retracting (mm/s)
853
+  #define RETRACT_ZLIFT 0                 // Default retract Z-lift
854
+  #define RETRACT_RECOVER_LENGTH 0        // Default additional recover length (mm, added to retract length when recovering)
855
+  #define RETRACT_RECOVER_LENGTH_SWAP 0   // Default additional swap recover length (mm, added to retract length when recovering from extruder change)
856
+  #define RETRACT_RECOVER_FEEDRATE 8      // Default feedrate for recovering from retraction (mm/s)
857
+  #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
776 858
 #endif
777 859
 
778 860
 /**
861
+ * Extra Fan Speed
862
+ * Adds a secondary fan speed for each print-cooling fan.
863
+ *   'M106 P<fan> T3-255' : Set a secondary speed for <fan>
864
+ *   'M106 P<fan> T2'     : Use the set secondary speed
865
+ *   'M106 P<fan> T1'     : Restore the previous fan speed
866
+ */
867
+//#define EXTRA_FAN_SPEED
868
+
869
+/**
779 870
  * Advanced Pause
780 871
  * Experimental feature for filament change support and for parking the nozzle when paused.
781 872
  * Adds the GCode M600 for initiating filament change.
@@ -885,7 +976,7 @@
885 976
 
886 977
 #endif
887 978
 
888
-// @section TMC2130
979
+// @section TMC2130, TMC2208
889 980
 
890 981
 /**
891 982
  * Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
@@ -899,7 +990,19 @@
899 990
  */
900 991
 //#define HAVE_TMC2130
901 992
 
902
-#if ENABLED(HAVE_TMC2130)
993
+/**
994
+ * Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
995
+ * Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
996
+ * To use the reading capabilities, also connect #_SERIAL_RX_PIN
997
+ * to #_SERIAL_TX_PIN with a 1K resistor.
998
+ * The drivers can also be used with hardware serial.
999
+ *
1000
+ * You'll also need the TMC2208Stepper Arduino library
1001
+ * (https://github.com/teemuatlut/TMC2208Stepper).
1002
+ */
1003
+//#define HAVE_TMC2208
1004
+
1005
+#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
903 1006
 
904 1007
   // CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
905 1008
   //#define X_IS_TMC2130
@@ -914,46 +1017,58 @@
914 1017
   //#define E3_IS_TMC2130
915 1018
   //#define E4_IS_TMC2130
916 1019
 
1020
+  //#define X_IS_TMC2208
1021
+  //#define X2_IS_TMC2208
1022
+  //#define Y_IS_TMC2208
1023
+  //#define Y2_IS_TMC2208
1024
+  //#define Z_IS_TMC2208
1025
+  //#define Z2_IS_TMC2208
1026
+  //#define E0_IS_TMC2208
1027
+  //#define E1_IS_TMC2208
1028
+  //#define E2_IS_TMC2208
1029
+  //#define E3_IS_TMC2208
1030
+  //#define E4_IS_TMC2208
1031
+
917 1032
   /**
918 1033
    * Stepper driver settings
919 1034
    */
920 1035
 
921 1036
   #define R_SENSE           0.11  // R_sense resistor for SilentStepStick2130
922 1037
   #define HOLD_MULTIPLIER    0.5  // Scales down the holding current from run current
923
-  #define INTERPOLATE          1  // Interpolate X/Y/Z_MICROSTEPS to 256
1038
+  #define INTERPOLATE       true  // Interpolate X/Y/Z_MICROSTEPS to 256
924 1039
 
925
-  #define X_CURRENT         1000  // rms current in mA. Multiply by 1.41 for peak current.
1040
+  #define X_CURRENT          800  // rms current in mA. Multiply by 1.41 for peak current.
926 1041
   #define X_MICROSTEPS        16  // 0..256
927 1042
 
928
-  #define Y_CURRENT         1000
1043
+  #define Y_CURRENT          800
929 1044
   #define Y_MICROSTEPS        16
930 1045
 
931
-  #define Z_CURRENT         1000
1046
+  #define Z_CURRENT          800
932 1047
   #define Z_MICROSTEPS        16
933 1048
 
934
-  //#define X2_CURRENT      1000
935
-  //#define X2_MICROSTEPS     16
1049
+  #define X2_CURRENT         800
1050
+  #define X2_MICROSTEPS       16
936 1051
 
937
-  //#define Y2_CURRENT      1000
938
-  //#define Y2_MICROSTEPS     16
1052
+  #define Y2_CURRENT         800
1053
+  #define Y2_MICROSTEPS       16
939 1054
 
940
-  //#define Z2_CURRENT      1000
941
-  //#define Z2_MICROSTEPS     16
1055
+  #define Z2_CURRENT         800
1056
+  #define Z2_MICROSTEPS       16
942 1057
 
943
-  //#define E0_CURRENT      1000
944
-  //#define E0_MICROSTEPS     16
1058
+  #define E0_CURRENT         800
1059
+  #define E0_MICROSTEPS       16
945 1060
 
946
-  //#define E1_CURRENT      1000
947
-  //#define E1_MICROSTEPS     16
1061
+  #define E1_CURRENT         800
1062
+  #define E1_MICROSTEPS       16
948 1063
 
949
-  //#define E2_CURRENT      1000
950
-  //#define E2_MICROSTEPS     16
1064
+  #define E2_CURRENT         800
1065
+  #define E2_MICROSTEPS       16
951 1066
 
952
-  //#define E3_CURRENT      1000
953
-  //#define E3_MICROSTEPS     16
1067
+  #define E3_CURRENT         800
1068
+  #define E3_MICROSTEPS       16
954 1069
 
955
-  //#define E4_CURRENT      1000
956
-  //#define E4_MICROSTEPS     16
1070
+  #define E4_CURRENT         800
1071
+  #define E4_MICROSTEPS       16
957 1072
 
958 1073
   /**
959 1074
    * Use Trinamic's ultra quiet stepping mode.
@@ -962,24 +1077,22 @@
962 1077
   #define STEALTHCHOP
963 1078
 
964 1079
   /**
965
-   * Let Marlin automatically control stepper current.
966
-   * This is still an experimental feature.
967
-   * Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
968
-   * then decrease current by CURRENT_STEP until temperature prewarn is cleared.
969
-   * Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
1080
+   * Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
1081
+   * like overtemperature and short to ground. TMC2208 requires hardware serial.
1082
+   * In the case of overtemperature Marlin can decrease the driver current until error condition clears.
1083
+   * Other detected conditions can be used to stop the current print.
970 1084
    * Relevant g-codes:
971 1085
    * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
972
-   * M906 S1 - Start adjusting current
973
-   * M906 S0 - Stop adjusting current
974 1086
    * M911 - Report stepper driver overtemperature pre-warn condition.
975 1087
    * M912 - Clear stepper driver overtemperature pre-warn condition flag.
1088
+   * M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
976 1089
    */
977
-  //#define AUTOMATIC_CURRENT_CONTROL
1090
+  //#define MONITOR_DRIVER_STATUS
978 1091
 
979
-  #if ENABLED(AUTOMATIC_CURRENT_CONTROL)
980
-    #define CURRENT_STEP          50  // [mA]
981
-    #define AUTO_ADJUST_MAX     1300  // [mA], 1300mA_rms = 1840mA_peak
1092
+  #if ENABLED(MONITOR_DRIVER_STATUS)
1093
+    #define CURRENT_STEP_DOWN     50  // [mA]
982 1094
     #define REPORT_CURRENT_CHANGE
1095
+    #define STOP_ON_ERROR
983 1096
   #endif
984 1097
 
985 1098
   /**
@@ -994,8 +1107,8 @@
994 1107
   #define X2_HYBRID_THRESHOLD    100
995 1108
   #define Y_HYBRID_THRESHOLD     100
996 1109
   #define Y2_HYBRID_THRESHOLD    100
997
-  #define Z_HYBRID_THRESHOLD       4
998
-  #define Z2_HYBRID_THRESHOLD      4
1110
+  #define Z_HYBRID_THRESHOLD       3
1111
+  #define Z2_HYBRID_THRESHOLD      3
999 1112
   #define E0_HYBRID_THRESHOLD     30
1000 1113
   #define E1_HYBRID_THRESHOLD     30
1001 1114
   #define E2_HYBRID_THRESHOLD     30
@@ -1005,7 +1118,7 @@
1005 1118
   /**
1006 1119
    * Use stallGuard2 to sense an obstacle and trigger an endstop.
1007 1120
    * You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
1008
-   * If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
1121
+   * X and Y homing will always be done in spreadCycle mode.
1009 1122
    *
1010 1123
    * X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
1011 1124
    * Higher values make the system LESS sensitive.
@@ -1014,27 +1127,34 @@
1014 1127
    * It is advised to set X/Y_HOME_BUMP_MM to 0.
1015 1128
    * M914 X/Y to live tune the setting
1016 1129
    */
1017
-  //#define SENSORLESS_HOMING
1130
+  //#define SENSORLESS_HOMING // TMC2130 only
1018 1131
 
1019 1132
   #if ENABLED(SENSORLESS_HOMING)
1020
-    #define X_HOMING_SENSITIVITY  19
1021
-    #define Y_HOMING_SENSITIVITY  19
1133
+    #define X_HOMING_SENSITIVITY  8
1134
+    #define Y_HOMING_SENSITIVITY  8
1022 1135
   #endif
1023 1136
 
1024 1137
   /**
1138
+   * Enable M122 debugging command for TMC stepper drivers.
1139
+   * M122 S0/1 will enable continous reporting.
1140
+   */
1141
+  //#define TMC_DEBUG
1142
+
1143
+  /**
1025 1144
    * You can set your own advanced settings by filling in predefined functions.
1026 1145
    * A list of available functions can be found on the library github page
1027 1146
    * https://github.com/teemuatlut/TMC2130Stepper
1147
+   * https://github.com/teemuatlut/TMC2208Stepper
1028 1148
    *
1029 1149
    * Example:
1030
-   * #define TMC2130_ADV() { \
1150
+   * #define TMC_ADV() { \
1031 1151
    *   stepperX.diag0_temp_prewarn(1); \
1032
-   *   stepperX.interpolate(0); \
1152
+   *   stepperY.interpolate(0); \
1033 1153
    * }
1034 1154
    */
1035
-  #define  TMC2130_ADV() {  }
1155
+  #define  TMC_ADV() {  }
1036 1156
 
1037
-#endif // HAVE_TMC2130
1157
+#endif // TMC2130 || TMC2208
1038 1158
 
1039 1159
 // @section L6470
1040 1160
 
@@ -1199,6 +1319,48 @@
1199 1319
 #endif
1200 1320
 
1201 1321
 /**
1322
+ * Filament Width Sensor
1323
+ *
1324
+ * Measures the filament width in real-time and adjusts
1325
+ * flow rate to compensate for any irregularities.
1326
+ *
1327
+ * Also allows the measured filament diameter to set the
1328
+ * extrusion rate, so the slicer only has to specify the
1329
+ * volume.
1330
+ *
1331
+ * Only a single extruder is supported at this time.
1332
+ *
1333
+ *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1334
+ *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1335
+ * 301 RAMBO       : Analog input 3
1336
+ *
1337
+ * Note: May require analog pins to be defined for other boards.
1338
+ */
1339
+//#define FILAMENT_WIDTH_SENSOR
1340
+
1341
+#if ENABLED(FILAMENT_WIDTH_SENSOR)
1342
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
1343
+  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1344
+
1345
+  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1346
+  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1347
+  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1348
+
1349
+  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1350
+
1351
+  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1352
+  //#define FILAMENT_LCD_DISPLAY
1353
+#endif
1354
+
1355
+/**
1356
+ * CNC Coordinate Systems
1357
+ *
1358
+ * Enables G53 and G54-G59.3 commands to select coordinate systems
1359
+ * and G92.1 to reset the workspace to native machine space.
1360
+ */
1361
+//#define CNC_COORDINATE_SYSTEMS
1362
+
1363
+/**
1202 1364
  * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
1203 1365
  */
1204 1366
 //#define PINS_DEBUGGING
@@ -1251,6 +1413,8 @@
1251 1413
 //#define CUSTOM_USER_MENUS
1252 1414
 #if ENABLED(CUSTOM_USER_MENUS)
1253 1415
   #define USER_SCRIPT_DONE "M117 User Script Done"
1416
+  #define USER_SCRIPT_AUDIBLE_FEEDBACK
1417
+  //#define USER_SCRIPT_RETURN  // Return to status screen after a script
1254 1418
 
1255 1419
   #define USER_DESC_1 "Home & UBL Info"
1256 1420
   #define USER_GCODE_1 "G28\nG29 W"
@@ -1278,6 +1442,7 @@
1278 1442
 //===========================================================================
1279 1443
 //====================== I2C Position Encoder Settings ======================
1280 1444
 //===========================================================================
1445
+
1281 1446
 /**
1282 1447
  *  I2C position encoders for closed loop control.
1283 1448
  *  Developed by Chris Barr at Aus3D.
@@ -1358,4 +1523,45 @@
1358 1523
 
1359 1524
 #endif // I2C_POSITION_ENCODERS
1360 1525
 
1526
+/**
1527
+ * MAX7219 Debug Matrix
1528
+ *
1529
+ * Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
1530
+ * display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
1531
+ *
1532
+ * Fully assembled MAX7219 boards can be found on the internet for under $2(US).
1533
+ * For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
1534
+ */
1535
+//#define MAX7219_DEBUG
1536
+#if ENABLED(MAX7219_DEBUG)
1537
+  #define MAX7219_CLK_PIN   64  // 77 on Re-ARM       // Configuration of the 3 pins to control the display
1538
+  #define MAX7219_DIN_PIN   57  // 78 on Re-ARM
1539
+  #define MAX7219_LOAD_PIN  44  // 79 on Re-ARM
1540
+
1541
+  /**
1542
+   * Sample debug features
1543
+   * If you add more debug displays, be careful to avoid conflicts!
1544
+   */
1545
+  #define MAX7219_DEBUG_PRINTER_ALIVE    // Blink corner LED of 8x8 matrix to show that the firmware is functioning
1546
+  #define MAX7219_DEBUG_STEPPER_HEAD  3  // Show the stepper queue head position on this and the next LED matrix row
1547
+  #define MAX7219_DEBUG_STEPPER_TAIL  5  // Show the stepper queue tail position on this and the next LED matrix row
1548
+
1549
+  #define MAX7219_DEBUG_STEPPER_QUEUE 0  // Show the current stepper queue depth on this and the next LED matrix row
1550
+                                         // If you experience stuttering, reboots, etc. this option can reveal how
1551
+                                         // tweaks made to the configuration are affecting the printer in real-time.
1552
+#endif
1553
+
1554
+/**
1555
+ * NanoDLP Sync support
1556
+ *
1557
+ * Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
1558
+ * string to enable synchronization with DLP projector exposure. This change will allow to use
1559
+ * [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
1560
+ */
1561
+//#define NANODLP_Z_SYNC
1562
+#if ENABLED(NANODLP_Z_SYNC)
1563
+  //#define NANODLP_ALL_AXIS  // Enables "Z_move_comp" output on any axis move.
1564
+                              // Default behaviour is limited to Z axis only.
1565
+#endif
1566
+
1361 1567
 #endif // CONFIGURATION_ADV_H

Marlin/example_configurations/Hephestos/Configuration.h → Marlin/example_configurations/BQ/Hephestos/Configuration.h 파일 보기

@@ -37,7 +37,7 @@
37 37
  */
38 38
 #ifndef CONFIGURATION_H
39 39
 #define CONFIGURATION_H
40
-#define CONFIGURATION_H_VERSION 010100
40
+#define CONFIGURATION_H_VERSION 010107
41 41
 
42 42
 //===========================================================================
43 43
 //============================= Getting Started =============================
@@ -107,8 +107,9 @@
107 107
  *
108 108
  * 250000 works in most cases, but you might try a lower speed if
109 109
  * you commonly experience drop-outs during host printing.
110
+ * You may try up to 1000000 to speed up SD file transfer.
110 111
  *
111
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
112
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
112 113
  */
113 114
 #define BAUDRATE 115200
114 115
 
@@ -138,6 +139,9 @@
138 139
 // :[1, 2, 3, 4, 5]
139 140
 #define EXTRUDERS 1
140 141
 
142
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
143
+#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
144
+
141 145
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
142 146
 //#define SINGLENOZZLE
143 147
 
@@ -164,7 +168,10 @@
164 168
 //#define SWITCHING_EXTRUDER
165 169
 #if ENABLED(SWITCHING_EXTRUDER)
166 170
   #define SWITCHING_EXTRUDER_SERVO_NR 0
167
-  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1
171
+  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3]
172
+  #if EXTRUDERS > 3
173
+    #define SWITCHING_EXTRUDER_E23_SERVO_NR 1
174
+  #endif
168 175
 #endif
169 176
 
170 177
 // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles
@@ -176,6 +183,21 @@
176 183
 #endif
177 184
 
178 185
 /**
186
+ * Two separate X-carriages with extruders that connect to a moving part
187
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
188
+ */
189
+//#define PARKING_EXTRUDER
190
+#if ENABLED(PARKING_EXTRUDER)
191
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
192
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
193
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
194
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
195
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
196
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
197
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
198
+#endif
199
+
200
+/**
179 201
  * "Mixing Extruder"
180 202
  *   - Adds a new code, M165, to set the current mix factors.
181 203
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -310,6 +332,7 @@
310 332
 #define HEATER_1_MAXTEMP 260
311 333
 #define HEATER_2_MAXTEMP 260
312 334
 #define HEATER_3_MAXTEMP 260
335
+#define HEATER_4_MAXTEMP 260
313 336
 #define BED_MAXTEMP 150
314 337
 
315 338
 //===========================================================================
@@ -319,8 +342,9 @@
319 342
 
320 343
 // Comment the following line to disable PID and enable bang-bang.
321 344
 #define PIDTEMP
322
-#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
323
-#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
345
+#define BANG_MAX 255     // Limits current to nozzle while in bang-bang mode; 255=full current
346
+#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
347
+#define PID_K1 0.95      // Smoothing factor within the PID
324 348
 #if ENABLED(PIDTEMP)
325 349
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
326 350
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -330,7 +354,6 @@
330 354
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
331 355
   #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
332 356
                                   // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
333
-  #define K1 0.95 //smoothing factor within the PID
334 357
 
335 358
   // Hephestos i3
336 359
   #define  DEFAULT_Kp 23.05
@@ -399,12 +422,13 @@
399 422
 //===========================================================================
400 423
 
401 424
 /**
402
- * Thermal Protection protects your printer from damage and fire if a
403
- * thermistor falls out or temperature sensors fail in any way.
425
+ * Thermal Protection provides additional protection to your printer from damage
426
+ * and fire. Marlin always includes safe min and max temperature ranges which
427
+ * protect against a broken or disconnected thermistor wire.
404 428
  *
405
- * The issue: If a thermistor falls out or a temperature sensor fails,
406
- * Marlin can no longer sense the actual temperature. Since a disconnected
407
- * thermistor reads as a low temperature, the firmware will keep the heater on.
429
+ * The issue: If a thermistor falls out, it will report the much lower
430
+ * temperature of the air in the room, and the the firmware will keep
431
+ * the heater on.
408 432
  *
409 433
  * If you get "Thermal Runaway" or "Heating failed" errors the
410 434
  * details can be tuned in Configuration_adv.h
@@ -521,7 +545,7 @@
521 545
  *   M204 R    Retract Acceleration
522 546
  *   M204 T    Travel Acceleration
523 547
  */
524
-#define DEFAULT_ACCELERATION          650     // X, Y, Z and E acceleration for printing moves
548
+#define DEFAULT_ACCELERATION           650    // X, Y, Z and E acceleration for printing moves
525 549
 #define DEFAULT_RETRACT_ACCELERATION  1000    // E acceleration for retracts
526 550
 #define DEFAULT_TRAVEL_ACCELERATION   1000    // X, Y, Z acceleration for travel (non printing) moves
527 551
 
@@ -544,7 +568,7 @@
544 568
 // @section probes
545 569
 
546 570
 //
547
-// See http://marlinfw.org/configuration/probes.html
571
+// See http://marlinfw.org/docs/configuration/probes.html
548 572
 //
549 573
 
550 574
 /**
@@ -610,14 +634,15 @@
610 634
 #endif
611 635
 
612 636
 /**
613
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
614
- * options selected below - will be disabled during probing so as to minimize
615
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
616
- * in current flowing through the wires).  This is likely most useful to users of the
617
- * BLTouch probe, but may also help those with inductive or other probe types.
637
+ * Enable one or more of the following if probing seems unreliable.
638
+ * Heaters and/or fans can be disabled during probing to minimize electrical
639
+ * noise. A delay can also be added to allow noise and vibration to settle.
640
+ * These options are most useful for the BLTouch probe, but may also improve
641
+ * readings with inductive probes and piezo sensors.
618 642
  */
619 643
 //#define PROBING_HEATERS_OFF       // Turn heaters off when probing
620 644
 //#define PROBING_FANS_OFF          // Turn fans off when probing
645
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
621 646
 
622 647
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
623 648
 //#define SOLENOID_PROBE
@@ -656,14 +681,16 @@
656 681
 // X and Y axis travel speed (mm/m) between probes
657 682
 #define XY_PROBE_SPEED 8000
658 683
 
659
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
684
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
660 685
 #define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
661 686
 
662 687
 // Speed for the "accurate" probe of each point
663 688
 #define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
664 689
 
665
-// Use double touch for probing
666
-//#define PROBE_DOUBLE_TOUCH
690
+// The number of probes to perform at each point.
691
+//   Set to 2 for a fast/slow probe, using the second probe result.
692
+//   Set to 3 or more for slow probes, averaging the results.
693
+//#define MULTIPLE_PROBING 2
667 694
 
668 695
 /**
669 696
  * Z probes require clearance when deploying, stowing, and moving between
@@ -730,6 +757,8 @@
730 757
 
731 758
 // @section homing
732 759
 
760
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
761
+
733 762
 //#define Z_HOMING_HEIGHT 4  // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
734 763
                              // Be sure you have this distance over your Z_MAX_POS in case.
735 764
 
@@ -741,18 +770,42 @@
741 770
 
742 771
 // @section machine
743 772
 
744
-// Travel limits after homing (units are in mm)
773
+// The size of the print bed
774
+#define X_BED_SIZE 215
775
+#define Y_BED_SIZE 210
776
+
777
+// Travel limits (mm) after homing, corresponding to endstop positions.
745 778
 #define X_MIN_POS 0
746 779
 #define Y_MIN_POS 0
747 780
 #define Z_MIN_POS 0
748
-#define X_MAX_POS 215
749
-#define Y_MAX_POS 210
781
+#define X_MAX_POS X_BED_SIZE
782
+#define Y_MAX_POS Y_BED_SIZE
750 783
 #define Z_MAX_POS 180
751 784
 
752
-// If enabled, axes won't move below MIN_POS in response to movement commands.
785
+/**
786
+ * Software Endstops
787
+ *
788
+ * - Prevent moves outside the set machine bounds.
789
+ * - Individual axes can be disabled, if desired.
790
+ * - X and Y only apply to Cartesian robots.
791
+ * - Use 'M211' to set software endstops on/off or report current state
792
+ */
793
+
794
+// Min software endstops curtail movement below minimum coordinate bounds
753 795
 #define MIN_SOFTWARE_ENDSTOPS
754
-// If enabled, axes won't move above MAX_POS in response to movement commands.
796
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
797
+  #define MIN_SOFTWARE_ENDSTOP_X
798
+  #define MIN_SOFTWARE_ENDSTOP_Y
799
+  #define MIN_SOFTWARE_ENDSTOP_Z
800
+#endif
801
+
802
+// Max software endstops curtail movement above maximum coordinate bounds
755 803
 #define MAX_SOFTWARE_ENDSTOPS
804
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
805
+  #define MAX_SOFTWARE_ENDSTOP_X
806
+  #define MAX_SOFTWARE_ENDSTOP_Y
807
+  #define MAX_SOFTWARE_ENDSTOP_Z
808
+#endif
756 809
 
757 810
 /**
758 811
  * Filament Runout Sensor
@@ -772,7 +825,7 @@
772 825
 //===========================================================================
773 826
 //=============================== Bed Leveling ==============================
774 827
 //===========================================================================
775
-// @section bedlevel
828
+// @section calibrate
776 829
 
777 830
 /**
778 831
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -798,12 +851,7 @@
798 851
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
799 852
  *   A comprehensive bed leveling system combining the features and benefits
800 853
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
801
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
802
- *   for Cartesian Printers. That said, it was primarily designed to correct
803
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
804
- *   please post an issue if something doesn't work correctly. Initially,
805
- *   you will need to set a reduced bed size so you have a rectangular area
806
- *   to test on.
854
+ *   Validation and Mesh Editing systems.
807 855
  *
808 856
  * - MESH_BED_LEVELING
809 857
  *   Probe a grid manually
@@ -830,6 +878,24 @@
830 878
   // at which point movement will be level to the machine's XY plane.
831 879
   // The height can be set with M420 Z<height>
832 880
   #define ENABLE_LEVELING_FADE_HEIGHT
881
+
882
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
883
+  // split up moves into short segments like a Delta. This follows the
884
+  // contours of the bed more closely than edge-to-edge straight moves.
885
+  #define SEGMENT_LEVELED_MOVES
886
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
887
+
888
+  /**
889
+   * Enable the G26 Mesh Validation Pattern tool.
890
+   */
891
+  //#define G26_MESH_VALIDATION   // Enable G26 mesh validation
892
+  #if ENABLED(G26_MESH_VALIDATION)
893
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
894
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
895
+    #define MESH_TEST_HOTEND_TEMP   205.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
896
+    #define MESH_TEST_BED_TEMP       60.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
897
+  #endif
898
+
833 899
 #endif
834 900
 
835 901
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -885,7 +951,9 @@
885 951
   //========================= Unified Bed Leveling ============================
886 952
   //===========================================================================
887 953
 
888
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
954
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
955
+
956
+  #define MESH_INSET 1              // Mesh inset margin on print area
889 957
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
890 958
   #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
891 959
 
@@ -896,8 +964,8 @@
896 964
   #define UBL_PROBE_PT_3_X 180
897 965
   #define UBL_PROBE_PT_3_Y 20
898 966
 
899
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
900 967
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
968
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
901 969
 
902 970
 #elif ENABLED(MESH_BED_LEVELING)
903 971
 
@@ -924,6 +992,9 @@
924 992
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
925 993
 #endif
926 994
 
995
+// Add a menu item to move between bed corners for manual bed adjustment
996
+//#define LEVEL_BED_CORNERS
997
+
927 998
 /**
928 999
  * Commands to execute at the end of G29 probing.
929 1000
  * Useful to retract or move the Z probe out of the way.
@@ -954,14 +1025,71 @@
954 1025
 //#define Z_SAFE_HOMING
955 1026
 
956 1027
 #if ENABLED(Z_SAFE_HOMING)
957
-  #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
958
-  #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
1028
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1029
+  #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2)    // Y point for Z homing when homing all axes (G28).
959 1030
 #endif
960 1031
 
961 1032
 // Homing speeds (mm/m)
962 1033
 #define HOMING_FEEDRATE_XY 2000
963 1034
 #define HOMING_FEEDRATE_Z  150
964 1035
 
1036
+// @section calibrate
1037
+
1038
+/**
1039
+ * Bed Skew Compensation
1040
+ *
1041
+ * This feature corrects for misalignment in the XYZ axes.
1042
+ *
1043
+ * Take the following steps to get the bed skew in the XY plane:
1044
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1045
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1046
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1047
+ *  4. For XY_SIDE_AD measure the edge A to D
1048
+ *
1049
+ * Marlin automatically computes skew factors from these measurements.
1050
+ * Skew factors may also be computed and set manually:
1051
+ *
1052
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1053
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1054
+ *
1055
+ * If desired, follow the same procedure for XZ and YZ.
1056
+ * Use these diagrams for reference:
1057
+ *
1058
+ *    Y                     Z                     Z
1059
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1060
+ *    |    /       /        |    /       /        |    /       /
1061
+ *    |   /       /         |   /       /         |   /       /
1062
+ *    |  A-------D          |  A-------D          |  A-------D
1063
+ *    +-------------->X     +-------------->X     +-------------->Y
1064
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1065
+ */
1066
+//#define SKEW_CORRECTION
1067
+
1068
+#if ENABLED(SKEW_CORRECTION)
1069
+  // Input all length measurements here:
1070
+  #define XY_DIAG_AC 282.8427124746
1071
+  #define XY_DIAG_BD 282.8427124746
1072
+  #define XY_SIDE_AD 200
1073
+
1074
+  // Or, set the default skew factors directly here
1075
+  // to override the above measurements:
1076
+  #define XY_SKEW_FACTOR 0.0
1077
+
1078
+  //#define SKEW_CORRECTION_FOR_Z
1079
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1080
+    #define XZ_DIAG_AC 282.8427124746
1081
+    #define XZ_DIAG_BD 282.8427124746
1082
+    #define YZ_DIAG_AC 282.8427124746
1083
+    #define YZ_DIAG_BD 282.8427124746
1084
+    #define YZ_SIDE_AD 200
1085
+    #define XZ_SKEW_FACTOR 0.0
1086
+    #define YZ_SKEW_FACTOR 0.0
1087
+  #endif
1088
+
1089
+  // Enable this option for M852 to set skew at runtime
1090
+  //#define SKEW_CORRECTION_GCODE
1091
+#endif
1092
+
965 1093
 //=============================================================================
966 1094
 //============================= Additional Features ===========================
967 1095
 //=============================================================================
@@ -988,11 +1116,12 @@
988 1116
 //
989 1117
 #define HOST_KEEPALIVE_FEATURE        // Disable this if your host doesn't like keepalive messages
990 1118
 #define DEFAULT_KEEPALIVE_INTERVAL 2  // Number of seconds between "busy" messages. Set with M113.
1119
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
991 1120
 
992 1121
 //
993 1122
 // M100 Free Memory Watcher
994 1123
 //
995
-//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1124
+//#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
996 1125
 
997 1126
 //
998 1127
 // G20/G21 Inch mode support
@@ -1137,13 +1266,13 @@
1137 1266
  *
1138 1267
  * Select the language to display on the LCD. These languages are available:
1139 1268
  *
1140
- *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
1141
- *    it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
1142
- *    zh_CN, zh_TW, test
1269
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1270
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1271
+ *    tr, uk, zh_CN, zh_TW, test
1143 1272
  *
1144
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1273
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1145 1274
  */
1146
-//#define LCD_LANGUAGE en
1275
+#define LCD_LANGUAGE en
1147 1276
 
1148 1277
 /**
1149 1278
  * LCD Character Set
@@ -1163,7 +1292,7 @@
1163 1292
  *  - Click the controller to view the LCD menu
1164 1293
  *  - The LCD will display Japanese, Western, or Cyrillic text
1165 1294
  *
1166
- * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1295
+ * See http://marlinfw.org/docs/development/lcd_language.html
1167 1296
  *
1168 1297
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1169 1298
  */
@@ -1269,8 +1398,8 @@
1269 1398
 // Note: Test audio output with the G-Code:
1270 1399
 //  M300 S<frequency Hz> P<duration ms>
1271 1400
 //
1272
-//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
1273
-//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
1401
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
1402
+//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
1274 1403
 
1275 1404
 //
1276 1405
 // CONTROLLER TYPE: Standard
@@ -1378,11 +1507,13 @@
1378 1507
 //#define CARTESIO_UI
1379 1508
 
1380 1509
 //
1381
-// ANET_10 Controller supported displays.
1510
+// ANET and Tronxy Controller supported displays.
1382 1511
 //
1383
-//#define ANET_KEYPAD_LCD         // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1512
+//#define ZONESTAR_LCD            // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1384 1513
                                   // This LCD is known to be susceptible to electrical interference
1385 1514
                                   // which scrambles the display.  Pressing any button clears it up.
1515
+                                  // This is a LCD2004 display with 5 analog buttons.
1516
+
1386 1517
 //#define ANET_FULL_GRAPHICS_LCD  // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1387 1518
                                   // A clone of the RepRapDiscount full graphics display but with
1388 1519
                                   // different pins/wiring (see pins_ANET_10.h).
@@ -1442,11 +1573,6 @@
1442 1573
 //#define U8GLIB_SSD1306
1443 1574
 
1444 1575
 //
1445
-// TinyBoy2 128x64 OLED / Encoder Panel
1446
-//
1447
-//#define OLED_PANEL_TINYBOY2
1448
-
1449
-//
1450 1576
 // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules
1451 1577
 //
1452 1578
 //#define SAV_3DGLCD
@@ -1463,6 +1589,45 @@
1463 1589
 //
1464 1590
 //#define SAV_3DLCD
1465 1591
 
1592
+//
1593
+// TinyBoy2 128x64 OLED / Encoder Panel
1594
+//
1595
+//#define OLED_PANEL_TINYBOY2
1596
+
1597
+//
1598
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1599
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1600
+//
1601
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1602
+
1603
+//
1604
+// MKS MINI12864 with graphic controller and SD support
1605
+// http://reprap.org/wiki/MKS_MINI_12864
1606
+//
1607
+//#define MKS_MINI_12864
1608
+
1609
+//
1610
+// Factory display for Creality CR-10
1611
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1612
+//
1613
+// This is RAMPS-compatible using a single 10-pin connector.
1614
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1615
+//
1616
+//#define CR10_STOCKDISPLAY
1617
+
1618
+//
1619
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1620
+// http://reprap.org/wiki/MKS_12864OLED
1621
+//
1622
+// Tiny, but very sharp OLED display
1623
+//
1624
+//#define MKS_12864OLED
1625
+
1626
+// Silvergate GLCD controller
1627
+// http://github.com/android444/Silvergate
1628
+//
1629
+//#define SILVER_GATE_GLCD_CONTROLLER
1630
+
1466 1631
 //=============================================================================
1467 1632
 //=============================== Extra Features ==============================
1468 1633
 //=============================================================================
@@ -1519,16 +1684,22 @@
1519 1684
  * Adds the M150 command to set the LED (or LED strip) color.
1520 1685
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1521 1686
  * luminance values can be set from 0 to 255.
1687
+ * For Neopixel LED an overall brightness parameter is also available.
1522 1688
  *
1523 1689
  * *** CAUTION ***
1524 1690
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1525 1691
  *  as the Arduino cannot handle the current the LEDs will require.
1526 1692
  *  Failure to follow this precaution can destroy your Arduino!
1693
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1694
+ *  more current than the Arduino 5V linear regulator can produce.
1527 1695
  * *** CAUTION ***
1528 1696
  *
1697
+ * LED Type. Enable only one of the following two options.
1698
+ *
1529 1699
  */
1530 1700
 //#define RGB_LED
1531 1701
 //#define RGBW_LED
1702
+
1532 1703
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1533 1704
   #define RGB_LED_R_PIN 34
1534 1705
   #define RGB_LED_G_PIN 43
@@ -1536,6 +1707,17 @@
1536 1707
   #define RGB_LED_W_PIN -1
1537 1708
 #endif
1538 1709
 
1710
+// Support for Adafruit Neopixel LED driver
1711
+//#define NEOPIXEL_LED
1712
+#if ENABLED(NEOPIXEL_LED)
1713
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1714
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1715
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1716
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1717
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1718
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1719
+#endif
1720
+
1539 1721
 /**
1540 1722
  * Printer Event LEDs
1541 1723
  *
@@ -1547,68 +1729,32 @@
1547 1729
  *  - Change to green once print has finished
1548 1730
  *  - Turn off after the print has finished and the user has pushed a button
1549 1731
  */
1550
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)
1732
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1551 1733
   #define PRINTER_EVENT_LEDS
1552 1734
 #endif
1553 1735
 
1554
-/*********************************************************************\
1555
-* R/C SERVO support
1556
-* Sponsored by TrinityLabs, Reworked by codexmas
1557
-**********************************************************************/
1736
+/**
1737
+ * R/C SERVO support
1738
+ * Sponsored by TrinityLabs, Reworked by codexmas
1739
+ */
1558 1740
 
1559
-// Number of servos
1560
-//
1561
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1562
-// set it manually if you have more servos than extruders and wish to manually control some
1563
-// leaving it undefined or defining as 0 will disable the servo subsystem
1564
-// If unsure, leave commented / disabled
1565
-//
1741
+/**
1742
+ * Number of servos
1743
+ *
1744
+ * For some servo-related options NUM_SERVOS will be set automatically.
1745
+ * Set this manually if there are extra servos needing manual control.
1746
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1747
+ */
1566 1748
 //#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
1567 1749
 
1568 1750
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1569 1751
 // 300ms is a good value but you can try less delay.
1570 1752
 // If the servo can't reach the requested position, increase it.
1571
-#define SERVO_DELAY 300
1753
+#define SERVO_DELAY { 300 }
1572 1754
 
1573 1755
 // Servo deactivation
1574 1756
 //
1575 1757
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1576 1758
 //#define DEACTIVATE_SERVOS_AFTER_MOVE
1577 1759
 
1578
-/**
1579
- * Filament Width Sensor
1580
- *
1581
- * Measures the filament width in real-time and adjusts
1582
- * flow rate to compensate for any irregularities.
1583
- *
1584
- * Also allows the measured filament diameter to set the
1585
- * extrusion rate, so the slicer only has to specify the
1586
- * volume.
1587
- *
1588
- * Only a single extruder is supported at this time.
1589
- *
1590
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1591
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1592
- * 301 RAMBO       : Analog input 3
1593
- *
1594
- * Note: May require analog pins to be defined for other boards.
1595
- */
1596
-//#define FILAMENT_WIDTH_SENSOR
1597
-
1598
-#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00   // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
1599
-
1600
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1601
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1602
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1603
-
1604
-  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1605
-  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1606
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1607
-
1608
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1609
-
1610
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1611
-  //#define FILAMENT_LCD_DISPLAY
1612
-#endif
1613
-
1614 1760
 #endif // CONFIGURATION_H

Marlin/example_configurations/Hephestos/Configuration_adv.h → Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h 파일 보기

@@ -32,7 +32,7 @@
32 32
  */
33 33
 #ifndef CONFIGURATION_ADV_H
34 34
 #define CONFIGURATION_ADV_H
35
-#define CONFIGURATION_ADV_H_VERSION 010100
35
+#define CONFIGURATION_ADV_H_VERSION 010107
36 36
 
37 37
 // @section temperature
38 38
 
@@ -48,31 +48,36 @@
48 48
 #endif
49 49
 
50 50
 /**
51
- * Thermal Protection protects your printer from damage and fire if a
52
- * thermistor falls out or temperature sensors fail in any way.
51
+ * Thermal Protection provides additional protection to your printer from damage
52
+ * and fire. Marlin always includes safe min and max temperature ranges which
53
+ * protect against a broken or disconnected thermistor wire.
53 54
  *
54
- * The issue: If a thermistor falls out or a temperature sensor fails,
55
- * Marlin can no longer sense the actual temperature. Since a disconnected
56
- * thermistor reads as a low temperature, the firmware will keep the heater on.
55
+ * The issue: If a thermistor falls out, it will report the much lower
56
+ * temperature of the air in the room, and the the firmware will keep
57
+ * the heater on.
57 58
  *
58 59
  * The solution: Once the temperature reaches the target, start observing.
59
- * If the temperature stays too far below the target (hysteresis) for too long (period),
60
- * the firmware will halt the machine as a safety precaution.
60
+ * If the temperature stays too far below the target (hysteresis) for too
61
+ * long (period), the firmware will halt the machine as a safety precaution.
61 62
  *
62
- * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63
+ * If you get false positives for "Thermal Runaway", increase
64
+ * THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63 65
  */
64 66
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
65 67
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
66 68
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
67 69
 
68 70
   /**
69
-   * Whenever an M104 or M109 increases the target temperature the firmware will wait for the
70
-   * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
71
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
72
-   * but only if the current temperature is far enough below the target for a reliable test.
71
+   * Whenever an M104, M109, or M303 increases the target temperature, the
72
+   * firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
73
+   * hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
74
+   * requires a hard reset. This test restarts with any M104/M109/M303, but only
75
+   * if the current temperature is far enough below the target for a reliable
76
+   * test.
73 77
    *
74
-   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
75
-   * WATCH_TEMP_INCREASE should not be below 2.
78
+   * If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
79
+   * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
80
+   * below 2.
76 81
    */
77 82
   #define WATCH_TEMP_PERIOD 20                // Seconds
78 83
   #define WATCH_TEMP_INCREASE 2               // Degrees Celsius
@@ -86,13 +91,7 @@
86 91
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
87 92
 
88 93
   /**
89
-   * Whenever an M140 or M190 increases the target temperature the firmware will wait for the
90
-   * WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
91
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
92
-   * but only if the current temperature is far enough below the target for a reliable test.
93
-   *
94
-   * If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
95
-   * WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
94
+   * As described above, except for the bed (M140/M190/M303).
96 95
    */
97 96
   #define WATCH_BED_TEMP_PERIOD 60                // Seconds
98 97
   #define WATCH_BED_TEMP_INCREASE 2               // Degrees Celsius
@@ -123,6 +122,9 @@
123 122
   #define AUTOTEMP_OLDWEIGHT 0.98
124 123
 #endif
125 124
 
125
+// Show extra position information in M114
126
+//#define M114_DETAIL
127
+
126 128
 // Show Temperature ADC value
127 129
 // Enable for M105 to include ADC values read from temperature sensors.
128 130
 //#define SHOW_TEMP_ADC_VALUES
@@ -221,6 +223,17 @@
221 223
 #define EXTRUDER_AUTO_FAN_SPEED   255  // == full speed
222 224
 
223 225
 /**
226
+ * Part-Cooling Fan Multiplexer
227
+ *
228
+ * This feature allows you to digitally multiplex the fan output.
229
+ * The multiplexer is automatically switched at tool-change.
230
+ * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans.
231
+ */
232
+#define FANMUX0_PIN -1
233
+#define FANMUX1_PIN -1
234
+#define FANMUX2_PIN -1
235
+
236
+/**
224 237
  * M355 Case Light on-off / brightness
225 238
  */
226 239
 //#define CASE_LIGHT_ENABLE
@@ -246,48 +259,49 @@
246 259
 
247 260
 //#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
248 261
 
249
-// Dual X Steppers
250
-// Uncomment this option to drive two X axis motors.
251
-// The next unused E driver will be assigned to the second X stepper.
262
+/**
263
+ * Dual Steppers / Dual Endstops
264
+ *
265
+ * This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
266
+ *
267
+ * For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
268
+ * spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
269
+ * set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
270
+ * that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
271
+ *
272
+ * Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
273
+ * this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
274
+ * in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
275
+ */
276
+
252 277
 //#define X_DUAL_STEPPER_DRIVERS
253 278
 #if ENABLED(X_DUAL_STEPPER_DRIVERS)
254
-  // Set true if the two X motors need to rotate in opposite directions
255
-  #define INVERT_X2_VS_X_DIR true
279
+  #define INVERT_X2_VS_X_DIR true   // Set 'true' if X motors should rotate in opposite directions
280
+  //#define X_DUAL_ENDSTOPS
281
+  #if ENABLED(X_DUAL_ENDSTOPS)
282
+    #define X2_USE_ENDSTOP _XMAX_
283
+    #define X_DUAL_ENDSTOPS_ADJUSTMENT  0
284
+  #endif
256 285
 #endif
257 286
 
258
-// Dual Y Steppers
259
-// Uncomment this option to drive two Y axis motors.
260
-// The next unused E driver will be assigned to the second Y stepper.
261 287
 //#define Y_DUAL_STEPPER_DRIVERS
262 288
 #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
263
-  // Set true if the two Y motors need to rotate in opposite directions
264
-  #define INVERT_Y2_VS_Y_DIR true
289
+  #define INVERT_Y2_VS_Y_DIR true   // Set 'true' if Y motors should rotate in opposite directions
290
+  //#define Y_DUAL_ENDSTOPS
291
+  #if ENABLED(Y_DUAL_ENDSTOPS)
292
+    #define Y2_USE_ENDSTOP _YMAX_
293
+    #define Y_DUAL_ENDSTOPS_ADJUSTMENT  0
294
+  #endif
265 295
 #endif
266 296
 
267
-// A single Z stepper driver is usually used to drive 2 stepper motors.
268
-// Uncomment this option to use a separate stepper driver for each Z axis motor.
269
-// The next unused E driver will be assigned to the second Z stepper.
270 297
 //#define Z_DUAL_STEPPER_DRIVERS
271
-
272 298
 #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
273
-
274
-  // Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper.
275
-  // That way the machine is capable to align the bed during home, since both Z steppers are homed.
276
-  // There is also an implementation of M666 (software endstops adjustment) to this feature.
277
-  // After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
278
-  // One just need to home the Z axis and measure the distance difference between both Z axis and apply the math: Z adjust = Z - Z2.
279
-  // If the Z stepper axis is closer to the bed, the measure Z > Z2 (yes, it is.. think about it) and the Z adjust would be positive.
280
-  // Play a little bit with small adjustments (0.5mm) and check the behaviour.
281
-  // The M119 (endstops report) will start reporting the Z2 Endstop as well.
282
-
283 299
   //#define Z_DUAL_ENDSTOPS
284
-
285 300
   #if ENABLED(Z_DUAL_ENDSTOPS)
286 301
     #define Z2_USE_ENDSTOP _XMAX_
287
-    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0  // use M666 command to determine this value
302
+    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0
288 303
   #endif
289
-
290
-#endif // Z_DUAL_STEPPER_DRIVERS
304
+#endif
291 305
 
292 306
 // Enable this for dual x-carriage printers.
293 307
 // A dual x-carriage design has the advantage that the inactive extruder can be parked which
@@ -334,12 +348,12 @@
334 348
 
335 349
 // @section homing
336 350
 
337
-//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
351
+// Homing hits each endstop, retracts by these distances, then does a slower bump.
338 352
 #define X_HOME_BUMP_MM 5
339 353
 #define Y_HOME_BUMP_MM 5
340 354
 #define Z_HOME_BUMP_MM 2
341
-#define HOMING_BUMP_DIVISOR {2, 2, 4}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
342
-//#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
355
+#define HOMING_BUMP_DIVISOR { 2, 2, 4 }  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
356
+//#define QUICK_HOME                     // If homing includes X and Y, do a diagonal move initially
343 357
 
344 358
 // When G28 is called, this option will make Y home before X
345 359
 //#define HOME_Y_BEFORE_X
@@ -394,7 +408,7 @@
394 408
 // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
395 409
 // of the buffer and all stops. This should not be much greater than zero and should only be changed
396 410
 // if unwanted behavior is observed on a user's machine when running at very slow speeds.
397
-#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
411
+#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
398 412
 
399 413
 // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
400 414
 #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
@@ -423,8 +437,21 @@
423 437
 //#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 }   // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
424 438
 //#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 }    // Default drive percent - X, Y, Z, E axis
425 439
 
426
-// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
440
+// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
427 441
 //#define DIGIPOT_I2C
442
+#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
443
+  /**
444
+   * Common slave addresses:
445
+   *
446
+   *                    A   (A shifted)   B   (B shifted)  IC
447
+   * Smoothie          0x2C (0x58)       0x2D (0x5A)       MCP4451
448
+   * AZTEEG_X3_PRO     0x2C (0x58)       0x2E (0x5C)       MCP4451
449
+   * MIGHTYBOARD_REVE  0x2F (0x5E)                         MCP4018
450
+   */
451
+  #define DIGIPOT_I2C_ADDRESS_A 0x2C  // unshifted slave address for first DIGIPOT
452
+  #define DIGIPOT_I2C_ADDRESS_B 0x2D  // unshifted slave address for second DIGIPOT
453
+#endif
454
+
428 455
 //#define DIGIPOT_MCP4018          // Requires library from https://github.com/stawel/SlowSoftI2CMaster
429 456
 #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4     AZTEEG_X3_PRO: 8
430 457
 // Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
@@ -452,6 +479,26 @@
452 479
 // On the Info Screen, display XY with one decimal place when possible
453 480
 //#define LCD_DECIMAL_SMALL_XY
454 481
 
482
+// The timeout (in ms) to return to the status screen from sub-menus
483
+//#define LCD_TIMEOUT_TO_STATUS 15000
484
+
485
+/**
486
+ * LED Control Menu
487
+ * Enable this feature to add LED Control to the LCD menu
488
+ */
489
+//#define LED_CONTROL_MENU
490
+#if ENABLED(LED_CONTROL_MENU)
491
+  #define LED_COLOR_PRESETS                 // Enable the Preset Color menu option
492
+  #if ENABLED(LED_COLOR_PRESETS)
493
+    #define LED_USER_PRESET_RED        255  // User defined RED value
494
+    #define LED_USER_PRESET_GREEN      128  // User defined GREEN value
495
+    #define LED_USER_PRESET_BLUE         0  // User defined BLUE value
496
+    #define LED_USER_PRESET_WHITE      255  // User defined WHITE value
497
+    #define LED_USER_PRESET_BRIGHTNESS 255  // User defined intensity
498
+    //#define LED_USER_PRESET_STARTUP       // Have the printer display the user preset color on startup
499
+  #endif
500
+#endif // LED_CONTROL_MENU
501
+
455 502
 #if ENABLED(SDSUPPORT)
456 503
 
457 504
   // Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -461,12 +508,14 @@
461 508
   // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
462 509
   #define SD_DETECT_INVERTED
463 510
 
464
-  #define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
511
+  #define SD_FINISHED_STEPPERRELEASE true          // Disable steppers when SD Print is finished
465 512
   #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
466 513
 
467
-  #define SDCARD_RATHERRECENTFIRST  //reverse file order of sd card menu display. Its sorted practically after the file system block order.
468
-  // if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that.
469
-  // using:
514
+  // Reverse SD sort to show "more recent" files first, according to the card's FAT.
515
+  // Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
516
+  #define SDCARD_RATHERRECENTFIRST
517
+
518
+  // Add an option in the menu to run all auto#.g files
470 519
   //#define MENU_ADDAUTOSTART
471 520
 
472 521
   /**
@@ -496,13 +545,15 @@
496 545
 
497 546
   // SD Card Sorting options
498 547
   #if ENABLED(SDCARD_SORT_ALPHA)
499
-    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256).
548
+    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256). Costs 27 bytes each.
500 549
     #define FOLDER_SORTING     -1     // -1=above  0=none  1=below
501 550
     #define SDSORT_GCODE       false  // Allow turning sorting on/off with LCD and M34 g-code.
502 551
     #define SDSORT_USES_RAM    false  // Pre-allocate a static array for faster pre-sorting.
503 552
     #define SDSORT_USES_STACK  false  // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
504 553
     #define SDSORT_CACHE_NAMES false  // Keep sorted items in RAM longer for speedy performance. Most expensive option.
505 554
     #define SDSORT_DYNAMIC_RAM false  // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
555
+    #define SDSORT_CACHE_VFATS 2      // Maximum number of 13-byte VFAT entries to use for sorting.
556
+                                      // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
506 557
   #endif
507 558
 
508 559
   // Show a progress bar on HD44780 LCDs for SD printing
@@ -521,14 +572,29 @@
521 572
     //#define LCD_PROGRESS_BAR_TEST
522 573
   #endif
523 574
 
575
+  // Add an 'M73' G-code to set the current percentage
576
+  //#define LCD_SET_PROGRESS_MANUALLY
577
+
524 578
   // This allows hosts to request long names for files and folders with M33
525 579
   //#define LONG_FILENAME_HOST_SUPPORT
526 580
 
527
-  // This option allows you to abort SD printing when any endstop is triggered.
528
-  // This feature must be enabled with "M540 S1" or from the LCD menu.
529
-  // To have any effect, endstops must be enabled during SD printing.
581
+  // Enable this option to scroll long filenames in the SD card menu
582
+  //#define SCROLL_LONG_FILENAMES
583
+
584
+  /**
585
+   * This option allows you to abort SD printing when any endstop is triggered.
586
+   * This feature must be enabled with "M540 S1" or from the LCD menu.
587
+   * To have any effect, endstops must be enabled during SD printing.
588
+   */
530 589
   //#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
531 590
 
591
+  /**
592
+   * This option makes it easier to print the same SD Card file again.
593
+   * On print completion the LCD Menu will open with the file selected.
594
+   * You can just click to start the print, or navigate elsewhere.
595
+   */
596
+  //#define SD_REPRINT_LAST_SELECTED_FILE
597
+
532 598
 #endif // SDSUPPORT
533 599
 
534 600
 /**
@@ -561,6 +627,10 @@
561 627
   // Enable this option and reduce the value to optimize screen updates.
562 628
   // The normal delay is 10µs. Use the lowest value that still gives a reliable display.
563 629
   //#define DOGM_SPI_DELAY_US 5
630
+
631
+  // Swap the CW/CCW indicators in the graphics overlay
632
+  //#define OVERLAY_GFX_REVERSE
633
+
564 634
 #endif // DOGLCD
565 635
 
566 636
 // @section safety
@@ -587,31 +657,18 @@
587 657
  */
588 658
 //#define BABYSTEPPING
589 659
 #if ENABLED(BABYSTEPPING)
590
-  #define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
591
-  #define BABYSTEP_INVERT_Z false  // Change if Z babysteps should go the other way
592
-  #define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
593
-  //#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
660
+  //#define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
661
+  #define BABYSTEP_INVERT_Z false    // Change if Z babysteps should go the other way
662
+  #define BABYSTEP_MULTIPLICATOR 1   // Babysteps are very small. Increase for faster motion.
663
+  //#define BABYSTEP_ZPROBE_OFFSET   // Enable to combine M851 and Babystepping
594 664
   //#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
595 665
   #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
596 666
                                         // Note: Extra time may be added to mitigate controller latency.
667
+  //#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
597 668
 #endif
598 669
 
599 670
 // @section extruder
600 671
 
601
-// extruder advance constant (s2/mm3)
602
-//
603
-// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
604
-//
605
-// Hooke's law says:    force = k * distance
606
-// Bernoulli's principle says:  v ^ 2 / 2 + g . h + pressure / density = constant
607
-// so: v ^ 2 is proportional to number of steps we advance the extruder
608
-//#define ADVANCE
609
-
610
-#if ENABLED(ADVANCE)
611
-  #define EXTRUDER_ADVANCE_K .0
612
-  #define D_FILAMENT 1.75
613
-#endif
614
-
615 672
 /**
616 673
  * Implementation of linear pressure control
617 674
  *
@@ -645,7 +702,7 @@
645 702
    *
646 703
    * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
647 704
    *
648
-   * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode.
705
+   * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
649 706
    * Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
650 707
    */
651 708
   #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
@@ -654,19 +711,18 @@
654 711
 
655 712
 // @section leveling
656 713
 
657
-// Default mesh area is an area with an inset margin on the print area.
658
-// Below are the macros that are used to define the borders for the mesh area,
659
-// made available here for specialized needs, ie dual extruder setup.
660
-#if ENABLED(MESH_BED_LEVELING)
661
-  #define MESH_MIN_X (X_MIN_POS + MESH_INSET)
662
-  #define MESH_MAX_X (X_MAX_POS - (MESH_INSET))
663
-  #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET)
664
-  #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET))
665
-#elif ENABLED(AUTO_BED_LEVELING_UBL)
666
-  #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET)
667
-  #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET))
668
-  #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET)
669
-  #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET))
714
+#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
715
+  #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
716
+#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
717
+  #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
718
+#endif
719
+
720
+#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
721
+  // Override the mesh area if the automatic (max) area is too large
722
+  //#define MESH_MIN_X MESH_INSET
723
+  //#define MESH_MIN_Y MESH_INSET
724
+  //#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
725
+  //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
670 726
 #endif
671 727
 
672 728
 // @section extras
@@ -686,7 +742,7 @@
686 742
 //#define BEZIER_CURVE_SUPPORT
687 743
 
688 744
 // G38.2 and G38.3 Probe Target
689
-// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
745
+// Set MULTIPLE_PROBING if you want G38 to double touch
690 746
 //#define G38_PROBE_TARGET
691 747
 #if ENABLED(G38_PROBE_TARGET)
692 748
   #define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
@@ -711,7 +767,7 @@
711 767
 // @section hidden
712 768
 
713 769
 // The number of linear motions that can be in the plan at any give time.
714
-// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
770
+// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
715 771
 #if ENABLED(SDSUPPORT)
716 772
   #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
717 773
 #else
@@ -724,7 +780,7 @@
724 780
 #define MAX_CMD_SIZE 96
725 781
 #define BUFSIZE 4
726 782
 
727
-// Transfer Buffer Size
783
+// Transmission to Host Buffer Size
728 784
 // To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0.
729 785
 // To buffer a simple "ok" you need 4 bytes.
730 786
 // For ADVANCED_OK (M105) you need 32 bytes.
@@ -733,6 +789,28 @@
733 789
 // :[0, 2, 4, 8, 16, 32, 64, 128, 256]
734 790
 #define TX_BUFFER_SIZE 0
735 791
 
792
+// Host Receive Buffer Size
793
+// Without XON/XOFF flow control (see SERIAL_XON_XOFF below) 32 bytes should be enough.
794
+// To use flow control, set this buffer size to at least 1024 bytes.
795
+// :[0, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048]
796
+//#define RX_BUFFER_SIZE 1024
797
+
798
+#if RX_BUFFER_SIZE >= 1024
799
+  // Enable to have the controller send XON/XOFF control characters to
800
+  // the host to signal the RX buffer is becoming full.
801
+  //#define SERIAL_XON_XOFF
802
+#endif
803
+
804
+#if ENABLED(SDSUPPORT)
805
+  // Enable this option to collect and display the maximum
806
+  // RX queue usage after transferring a file to SD.
807
+  //#define SERIAL_STATS_MAX_RX_QUEUED
808
+
809
+  // Enable this option to collect and display the number
810
+  // of dropped bytes after a file transfer to SD.
811
+  //#define SERIAL_STATS_DROPPED_RX
812
+#endif
813
+
736 814
 // Enable an emergency-command parser to intercept certain commands as they
737 815
 // enter the serial receive buffer, so they cannot be blocked.
738 816
 // Currently handles M108, M112, M410
@@ -748,27 +826,47 @@
748 826
 // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary.
749 827
 //#define ADVANCED_OK
750 828
 
751
-// @section fwretract
752
-
753
-// Firmware based and LCD controlled retract
754
-// M207 and M208 can be used to define parameters for the retraction.
755
-// The retraction can be called by the slicer using G10 and G11
756
-// until then, intended retractions can be detected by moves that only extrude and the direction.
757
-// the moves are than replaced by the firmware controlled ones.
829
+// @section extras
758 830
 
759
-//#define FWRETRACT  //ONLY PARTIALLY TESTED
831
+/**
832
+ * Firmware-based and LCD-controlled retract
833
+ *
834
+ * Add G10 / G11 commands for automatic firmware-based retract / recover.
835
+ * Use M207 and M208 to define parameters for retract / recover.
836
+ *
837
+ * Use M209 to enable or disable auto-retract.
838
+ * With auto-retract enabled, all G1 E moves within the set range
839
+ * will be converted to firmware-based retract/recover moves.
840
+ *
841
+ * Be sure to turn off auto-retract during filament change.
842
+ *
843
+ * Note that M207 / M208 / M209 settings are saved to EEPROM.
844
+ *
845
+ */
846
+//#define FWRETRACT  // ONLY PARTIALLY TESTED
760 847
 #if ENABLED(FWRETRACT)
761
-  #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
762
-  #define RETRACT_LENGTH 3               //default retract length (positive mm)
763
-  #define RETRACT_LENGTH_SWAP 13         //default swap retract length (positive mm), for extruder change
764
-  #define RETRACT_FEEDRATE 80            //default feedrate for retracting (mm/s)
765
-  #define RETRACT_ZLIFT 0                //default retract Z-lift
766
-  #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
767
-  //#define RETRACT_RECOVER_LENGTH_SWAP 0  //default additional swap recover length (mm, added to retract length when recovering from extruder change)
768
-  #define RETRACT_RECOVER_FEEDRATE 8     //default feedrate for recovering from retraction (mm/s)
848
+  #define MIN_AUTORETRACT 0.1             // When auto-retract is on, convert E moves of this length and over
849
+  #define MAX_AUTORETRACT 10.0            // Upper limit for auto-retract conversion
850
+  #define RETRACT_LENGTH 3                // Default retract length (positive mm)
851
+  #define RETRACT_LENGTH_SWAP 13          // Default swap retract length (positive mm), for extruder change
852
+  #define RETRACT_FEEDRATE 45             // Default feedrate for retracting (mm/s)
853
+  #define RETRACT_ZLIFT 0                 // Default retract Z-lift
854
+  #define RETRACT_RECOVER_LENGTH 0        // Default additional recover length (mm, added to retract length when recovering)
855
+  #define RETRACT_RECOVER_LENGTH_SWAP 0   // Default additional swap recover length (mm, added to retract length when recovering from extruder change)
856
+  #define RETRACT_RECOVER_FEEDRATE 8      // Default feedrate for recovering from retraction (mm/s)
857
+  #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
769 858
 #endif
770 859
 
771 860
 /**
861
+ * Extra Fan Speed
862
+ * Adds a secondary fan speed for each print-cooling fan.
863
+ *   'M106 P<fan> T3-255' : Set a secondary speed for <fan>
864
+ *   'M106 P<fan> T2'     : Use the set secondary speed
865
+ *   'M106 P<fan> T1'     : Restore the previous fan speed
866
+ */
867
+//#define EXTRA_FAN_SPEED
868
+
869
+/**
772 870
  * Advanced Pause
773 871
  * Experimental feature for filament change support and for parking the nozzle when paused.
774 872
  * Adds the GCode M600 for initiating filament change.
@@ -878,7 +976,7 @@
878 976
 
879 977
 #endif
880 978
 
881
-// @section TMC2130
979
+// @section TMC2130, TMC2208
882 980
 
883 981
 /**
884 982
  * Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
@@ -892,7 +990,19 @@
892 990
  */
893 991
 //#define HAVE_TMC2130
894 992
 
895
-#if ENABLED(HAVE_TMC2130)
993
+/**
994
+ * Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
995
+ * Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
996
+ * To use the reading capabilities, also connect #_SERIAL_RX_PIN
997
+ * to #_SERIAL_TX_PIN with a 1K resistor.
998
+ * The drivers can also be used with hardware serial.
999
+ *
1000
+ * You'll also need the TMC2208Stepper Arduino library
1001
+ * (https://github.com/teemuatlut/TMC2208Stepper).
1002
+ */
1003
+//#define HAVE_TMC2208
1004
+
1005
+#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
896 1006
 
897 1007
   // CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
898 1008
   //#define X_IS_TMC2130
@@ -907,46 +1017,58 @@
907 1017
   //#define E3_IS_TMC2130
908 1018
   //#define E4_IS_TMC2130
909 1019
 
1020
+  //#define X_IS_TMC2208
1021
+  //#define X2_IS_TMC2208
1022
+  //#define Y_IS_TMC2208
1023
+  //#define Y2_IS_TMC2208
1024
+  //#define Z_IS_TMC2208
1025
+  //#define Z2_IS_TMC2208
1026
+  //#define E0_IS_TMC2208
1027
+  //#define E1_IS_TMC2208
1028
+  //#define E2_IS_TMC2208
1029
+  //#define E3_IS_TMC2208
1030
+  //#define E4_IS_TMC2208
1031
+
910 1032
   /**
911 1033
    * Stepper driver settings
912 1034
    */
913 1035
 
914 1036
   #define R_SENSE           0.11  // R_sense resistor for SilentStepStick2130
915 1037
   #define HOLD_MULTIPLIER    0.5  // Scales down the holding current from run current
916
-  #define INTERPOLATE          1  // Interpolate X/Y/Z_MICROSTEPS to 256
1038
+  #define INTERPOLATE       true  // Interpolate X/Y/Z_MICROSTEPS to 256
917 1039
 
918
-  #define X_CURRENT         1000  // rms current in mA. Multiply by 1.41 for peak current.
1040
+  #define X_CURRENT          800  // rms current in mA. Multiply by 1.41 for peak current.
919 1041
   #define X_MICROSTEPS        16  // 0..256
920 1042
 
921
-  #define Y_CURRENT         1000
1043
+  #define Y_CURRENT          800
922 1044
   #define Y_MICROSTEPS        16
923 1045
 
924
-  #define Z_CURRENT         1000
1046
+  #define Z_CURRENT          800
925 1047
   #define Z_MICROSTEPS        16
926 1048
 
927
-  //#define X2_CURRENT      1000
928
-  //#define X2_MICROSTEPS     16
1049
+  #define X2_CURRENT         800
1050
+  #define X2_MICROSTEPS       16
929 1051
 
930
-  //#define Y2_CURRENT      1000
931
-  //#define Y2_MICROSTEPS     16
1052
+  #define Y2_CURRENT         800
1053
+  #define Y2_MICROSTEPS       16
932 1054
 
933
-  //#define Z2_CURRENT      1000
934
-  //#define Z2_MICROSTEPS     16
1055
+  #define Z2_CURRENT         800
1056
+  #define Z2_MICROSTEPS       16
935 1057
 
936
-  //#define E0_CURRENT      1000
937
-  //#define E0_MICROSTEPS     16
1058
+  #define E0_CURRENT         800
1059
+  #define E0_MICROSTEPS       16
938 1060
 
939
-  //#define E1_CURRENT      1000
940
-  //#define E1_MICROSTEPS     16
1061
+  #define E1_CURRENT         800
1062
+  #define E1_MICROSTEPS       16
941 1063
 
942
-  //#define E2_CURRENT      1000
943
-  //#define E2_MICROSTEPS     16
1064
+  #define E2_CURRENT         800
1065
+  #define E2_MICROSTEPS       16
944 1066
 
945
-  //#define E3_CURRENT      1000
946
-  //#define E3_MICROSTEPS     16
1067
+  #define E3_CURRENT         800
1068
+  #define E3_MICROSTEPS       16
947 1069
 
948
-  //#define E4_CURRENT      1000
949
-  //#define E4_MICROSTEPS     16
1070
+  #define E4_CURRENT         800
1071
+  #define E4_MICROSTEPS       16
950 1072
 
951 1073
   /**
952 1074
    * Use Trinamic's ultra quiet stepping mode.
@@ -955,24 +1077,22 @@
955 1077
   #define STEALTHCHOP
956 1078
 
957 1079
   /**
958
-   * Let Marlin automatically control stepper current.
959
-   * This is still an experimental feature.
960
-   * Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
961
-   * then decrease current by CURRENT_STEP until temperature prewarn is cleared.
962
-   * Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
1080
+   * Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
1081
+   * like overtemperature and short to ground. TMC2208 requires hardware serial.
1082
+   * In the case of overtemperature Marlin can decrease the driver current until error condition clears.
1083
+   * Other detected conditions can be used to stop the current print.
963 1084
    * Relevant g-codes:
964 1085
    * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
965
-   * M906 S1 - Start adjusting current
966
-   * M906 S0 - Stop adjusting current
967 1086
    * M911 - Report stepper driver overtemperature pre-warn condition.
968 1087
    * M912 - Clear stepper driver overtemperature pre-warn condition flag.
1088
+   * M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
969 1089
    */
970
-  //#define AUTOMATIC_CURRENT_CONTROL
1090
+  //#define MONITOR_DRIVER_STATUS
971 1091
 
972
-  #if ENABLED(AUTOMATIC_CURRENT_CONTROL)
973
-    #define CURRENT_STEP          50  // [mA]
974
-    #define AUTO_ADJUST_MAX     1300  // [mA], 1300mA_rms = 1840mA_peak
1092
+  #if ENABLED(MONITOR_DRIVER_STATUS)
1093
+    #define CURRENT_STEP_DOWN     50  // [mA]
975 1094
     #define REPORT_CURRENT_CHANGE
1095
+    #define STOP_ON_ERROR
976 1096
   #endif
977 1097
 
978 1098
   /**
@@ -987,8 +1107,8 @@
987 1107
   #define X2_HYBRID_THRESHOLD    100
988 1108
   #define Y_HYBRID_THRESHOLD     100
989 1109
   #define Y2_HYBRID_THRESHOLD    100
990
-  #define Z_HYBRID_THRESHOLD       4
991
-  #define Z2_HYBRID_THRESHOLD      4
1110
+  #define Z_HYBRID_THRESHOLD       3
1111
+  #define Z2_HYBRID_THRESHOLD      3
992 1112
   #define E0_HYBRID_THRESHOLD     30
993 1113
   #define E1_HYBRID_THRESHOLD     30
994 1114
   #define E2_HYBRID_THRESHOLD     30
@@ -998,7 +1118,7 @@
998 1118
   /**
999 1119
    * Use stallGuard2 to sense an obstacle and trigger an endstop.
1000 1120
    * You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
1001
-   * If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
1121
+   * X and Y homing will always be done in spreadCycle mode.
1002 1122
    *
1003 1123
    * X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
1004 1124
    * Higher values make the system LESS sensitive.
@@ -1007,27 +1127,34 @@
1007 1127
    * It is advised to set X/Y_HOME_BUMP_MM to 0.
1008 1128
    * M914 X/Y to live tune the setting
1009 1129
    */
1010
-  //#define SENSORLESS_HOMING
1130
+  //#define SENSORLESS_HOMING // TMC2130 only
1011 1131
 
1012 1132
   #if ENABLED(SENSORLESS_HOMING)
1013
-    #define X_HOMING_SENSITIVITY  19
1014
-    #define Y_HOMING_SENSITIVITY  19
1133
+    #define X_HOMING_SENSITIVITY  8
1134
+    #define Y_HOMING_SENSITIVITY  8
1015 1135
   #endif
1016 1136
 
1017 1137
   /**
1138
+   * Enable M122 debugging command for TMC stepper drivers.
1139
+   * M122 S0/1 will enable continous reporting.
1140
+   */
1141
+  //#define TMC_DEBUG
1142
+
1143
+  /**
1018 1144
    * You can set your own advanced settings by filling in predefined functions.
1019 1145
    * A list of available functions can be found on the library github page
1020 1146
    * https://github.com/teemuatlut/TMC2130Stepper
1147
+   * https://github.com/teemuatlut/TMC2208Stepper
1021 1148
    *
1022 1149
    * Example:
1023
-   * #define TMC2130_ADV() { \
1150
+   * #define TMC_ADV() { \
1024 1151
    *   stepperX.diag0_temp_prewarn(1); \
1025
-   *   stepperX.interpolate(0); \
1152
+   *   stepperY.interpolate(0); \
1026 1153
    * }
1027 1154
    */
1028
-  #define  TMC2130_ADV() {  }
1155
+  #define  TMC_ADV() {  }
1029 1156
 
1030
-#endif // HAVE_TMC2130
1157
+#endif // TMC2130 || TMC2208
1031 1158
 
1032 1159
 // @section L6470
1033 1160
 
@@ -1192,6 +1319,48 @@
1192 1319
 #endif
1193 1320
 
1194 1321
 /**
1322
+ * Filament Width Sensor
1323
+ *
1324
+ * Measures the filament width in real-time and adjusts
1325
+ * flow rate to compensate for any irregularities.
1326
+ *
1327
+ * Also allows the measured filament diameter to set the
1328
+ * extrusion rate, so the slicer only has to specify the
1329
+ * volume.
1330
+ *
1331
+ * Only a single extruder is supported at this time.
1332
+ *
1333
+ *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1334
+ *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1335
+ * 301 RAMBO       : Analog input 3
1336
+ *
1337
+ * Note: May require analog pins to be defined for other boards.
1338
+ */
1339
+//#define FILAMENT_WIDTH_SENSOR
1340
+
1341
+#if ENABLED(FILAMENT_WIDTH_SENSOR)
1342
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
1343
+  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1344
+
1345
+  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1346
+  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1347
+  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1348
+
1349
+  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1350
+
1351
+  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1352
+  //#define FILAMENT_LCD_DISPLAY
1353
+#endif
1354
+
1355
+/**
1356
+ * CNC Coordinate Systems
1357
+ *
1358
+ * Enables G53 and G54-G59.3 commands to select coordinate systems
1359
+ * and G92.1 to reset the workspace to native machine space.
1360
+ */
1361
+//#define CNC_COORDINATE_SYSTEMS
1362
+
1363
+/**
1195 1364
  * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
1196 1365
  */
1197 1366
 //#define PINS_DEBUGGING
@@ -1244,6 +1413,8 @@
1244 1413
 //#define CUSTOM_USER_MENUS
1245 1414
 #if ENABLED(CUSTOM_USER_MENUS)
1246 1415
   #define USER_SCRIPT_DONE "M117 User Script Done"
1416
+  #define USER_SCRIPT_AUDIBLE_FEEDBACK
1417
+  //#define USER_SCRIPT_RETURN  // Return to status screen after a script
1247 1418
 
1248 1419
   #define USER_DESC_1 "Home & UBL Info"
1249 1420
   #define USER_GCODE_1 "G28\nG29 W"
@@ -1271,6 +1442,7 @@
1271 1442
 //===========================================================================
1272 1443
 //====================== I2C Position Encoder Settings ======================
1273 1444
 //===========================================================================
1445
+
1274 1446
 /**
1275 1447
  *  I2C position encoders for closed loop control.
1276 1448
  *  Developed by Chris Barr at Aus3D.
@@ -1351,4 +1523,45 @@
1351 1523
 
1352 1524
 #endif // I2C_POSITION_ENCODERS
1353 1525
 
1526
+/**
1527
+ * MAX7219 Debug Matrix
1528
+ *
1529
+ * Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
1530
+ * display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
1531
+ *
1532
+ * Fully assembled MAX7219 boards can be found on the internet for under $2(US).
1533
+ * For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
1534
+ */
1535
+//#define MAX7219_DEBUG
1536
+#if ENABLED(MAX7219_DEBUG)
1537
+  #define MAX7219_CLK_PIN   64  // 77 on Re-ARM       // Configuration of the 3 pins to control the display
1538
+  #define MAX7219_DIN_PIN   57  // 78 on Re-ARM
1539
+  #define MAX7219_LOAD_PIN  44  // 79 on Re-ARM
1540
+
1541
+  /**
1542
+   * Sample debug features
1543
+   * If you add more debug displays, be careful to avoid conflicts!
1544
+   */
1545
+  #define MAX7219_DEBUG_PRINTER_ALIVE    // Blink corner LED of 8x8 matrix to show that the firmware is functioning
1546
+  #define MAX7219_DEBUG_STEPPER_HEAD  3  // Show the stepper queue head position on this and the next LED matrix row
1547
+  #define MAX7219_DEBUG_STEPPER_TAIL  5  // Show the stepper queue tail position on this and the next LED matrix row
1548
+
1549
+  #define MAX7219_DEBUG_STEPPER_QUEUE 0  // Show the current stepper queue depth on this and the next LED matrix row
1550
+                                         // If you experience stuttering, reboots, etc. this option can reveal how
1551
+                                         // tweaks made to the configuration are affecting the printer in real-time.
1552
+#endif
1553
+
1554
+/**
1555
+ * NanoDLP Sync support
1556
+ *
1557
+ * Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
1558
+ * string to enable synchronization with DLP projector exposure. This change will allow to use
1559
+ * [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
1560
+ */
1561
+//#define NANODLP_Z_SYNC
1562
+#if ENABLED(NANODLP_Z_SYNC)
1563
+  //#define NANODLP_ALL_AXIS  // Enables "Z_move_comp" output on any axis move.
1564
+                              // Default behaviour is limited to Z axis only.
1565
+#endif
1566
+
1354 1567
 #endif // CONFIGURATION_ADV_H

Marlin/example_configurations/Hephestos_2/Configuration.h → Marlin/example_configurations/BQ/Hephestos_2/Configuration.h 파일 보기

@@ -20,24 +20,23 @@
20 20
  *
21 21
  */
22 22
 
23
+#ifndef CONFIGURATION_H
24
+#define CONFIGURATION_H
25
+#define CONFIGURATION_H_VERSION 010107
26
+
27
+//===========================================================================
28
+//================================= README ==================================
29
+//===========================================================================
30
+
23 31
 /**
24
- * Configuration.h
25
- *
26
- * Basic settings such as:
32
+ * BQ Hephestos 2 Configuration
27 33
  *
28
- * - Type of electronics
29
- * - Type of temperature sensor
30
- * - Printer geometry
31
- * - Endstop configuration
32
- * - LCD controller
33
- * - Extra features
34
- *
35
- * Advanced settings can be found in Configuration_adv.h
34
+ * This configuration supports the standard Hephestos 2 with or without the
35
+ * heated bed kit featured at https://store.bq.com/en/heated-bed-kit-hephestos2
36 36
  *
37
+ * Enable the following option to activate all functionality related to the heated bed.
37 38
  */
38
-#ifndef CONFIGURATION_H
39
-#define CONFIGURATION_H
40
-#define CONFIGURATION_H_VERSION 010100
39
+//#define HEPHESTOS2_HEATED_BED_KIT
41 40
 
42 41
 //===========================================================================
43 42
 //============================= Getting Started =============================
@@ -107,8 +106,9 @@
107 106
  *
108 107
  * 250000 works in most cases, but you might try a lower speed if
109 108
  * you commonly experience drop-outs during host printing.
109
+ * You may try up to 1000000 to speed up SD file transfer.
110 110
  *
111
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
111
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
112 112
  */
113 113
 #define BAUDRATE 115200
114 114
 
@@ -135,6 +135,9 @@
135 135
 // :[1, 2, 3, 4, 5]
136 136
 #define EXTRUDERS 1
137 137
 
138
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
139
+#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
140
+
138 141
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
139 142
 //#define SINGLENOZZLE
140 143
 
@@ -161,7 +164,10 @@
161 164
 //#define SWITCHING_EXTRUDER
162 165
 #if ENABLED(SWITCHING_EXTRUDER)
163 166
   #define SWITCHING_EXTRUDER_SERVO_NR 0
164
-  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1
167
+  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3]
168
+  #if EXTRUDERS > 3
169
+    #define SWITCHING_EXTRUDER_E23_SERVO_NR 1
170
+  #endif
165 171
 #endif
166 172
 
167 173
 // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles
@@ -173,6 +179,21 @@
173 179
 #endif
174 180
 
175 181
 /**
182
+ * Two separate X-carriages with extruders that connect to a moving part
183
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
184
+ */
185
+//#define PARKING_EXTRUDER
186
+#if ENABLED(PARKING_EXTRUDER)
187
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
188
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
189
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
190
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
191
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
192
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
193
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
194
+#endif
195
+
196
+/**
176 197
  * "Mixing Extruder"
177 198
  *   - Adds a new code, M165, to set the current mix factors.
178 199
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -269,7 +290,13 @@
269 290
 #define TEMP_SENSOR_2 0
270 291
 #define TEMP_SENSOR_3 0
271 292
 #define TEMP_SENSOR_4 0
272
-#define TEMP_SENSOR_BED 0
293
+
294
+#if ENABLED(HEPHESTOS2_HEATED_BED_KIT)
295
+  #define TEMP_SENSOR_BED 70
296
+  #define HEATER_BED_INVERTING true
297
+#else
298
+  #define TEMP_SENSOR_BED 0
299
+#endif
273 300
 
274 301
 // Dummy thermistor constant temperature readings, for use with 998 and 999
275 302
 #define DUMMY_THERMISTOR_998_VALUE 25
@@ -293,7 +320,7 @@
293 320
 // The minimal temperature defines the temperature below which the heater will not be enabled It is used
294 321
 // to check that the wiring to the thermistor is not broken.
295 322
 // Otherwise this would lead to the heater being powered on all the time.
296
-#define HEATER_0_MINTEMP 15
323
+#define HEATER_0_MINTEMP 5
297 324
 #define HEATER_1_MINTEMP 5
298 325
 #define HEATER_2_MINTEMP 5
299 326
 #define HEATER_3_MINTEMP 5
@@ -303,12 +330,12 @@
303 330
 // When temperature exceeds max temp, your heater will be switched off.
304 331
 // This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure!
305 332
 // You should use MINTEMP for thermistor short/failure protection.
306
-#define HEATER_0_MAXTEMP 250
333
+#define HEATER_0_MAXTEMP 275
307 334
 #define HEATER_1_MAXTEMP 275
308 335
 #define HEATER_2_MAXTEMP 275
309 336
 #define HEATER_3_MAXTEMP 275
310 337
 #define HEATER_4_MAXTEMP 275
311
-#define BED_MAXTEMP 150
338
+#define BED_MAXTEMP      110
312 339
 
313 340
 //===========================================================================
314 341
 //============================= PID Settings ================================
@@ -317,8 +344,9 @@
317 344
 
318 345
 // Comment the following line to disable PID and enable bang-bang.
319 346
 #define PIDTEMP
320
-#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
321
-#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
347
+#define BANG_MAX 255     // Limits current to nozzle while in bang-bang mode; 255=full current
348
+#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
349
+#define PID_K1 0.95      // Smoothing factor within the PID
322 350
 #if ENABLED(PIDTEMP)
323 351
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
324 352
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -328,7 +356,6 @@
328 356
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
329 357
   #define PID_FUNCTIONAL_RANGE 50 // If the temperature difference between the target temperature and the actual temperature
330 358
                                     // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
331
-  #define K1 0.95 //smoothing factor within the PID
332 359
 
333 360
   // Tuned PID values using M303
334 361
   #define  DEFAULT_Kp 19.18
@@ -362,7 +389,10 @@
362 389
 // all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
363 390
 // setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
364 391
 // so you shouldn't use it unless you are OK with PWM on your bed.  (see the comment on enabling PIDTEMPBED)
365
-//#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
392
+
393
+#if ENABLED(HEPHESTOS2_HEATED_BED_KIT)
394
+  #define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
395
+#endif
366 396
 
367 397
 #if ENABLED(PIDTEMPBED)
368 398
 
@@ -402,19 +432,20 @@
402 432
 //===========================================================================
403 433
 
404 434
 /**
405
- * Thermal Protection protects your printer from damage and fire if a
406
- * thermistor falls out or temperature sensors fail in any way.
435
+ * Thermal Protection provides additional protection to your printer from damage
436
+ * and fire. Marlin always includes safe min and max temperature ranges which
437
+ * protect against a broken or disconnected thermistor wire.
407 438
  *
408
- * The issue: If a thermistor falls out or a temperature sensor fails,
409
- * Marlin can no longer sense the actual temperature. Since a disconnected
410
- * thermistor reads as a low temperature, the firmware will keep the heater on.
439
+ * The issue: If a thermistor falls out, it will report the much lower
440
+ * temperature of the air in the room, and the the firmware will keep
441
+ * the heater on.
411 442
  *
412 443
  * If you get "Thermal Runaway" or "Heating failed" errors the
413 444
  * details can be tuned in Configuration_adv.h
414 445
  */
415 446
 
416 447
 #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
417
-//#define THERMAL_PROTECTION_BED     // Enable thermal protection for the heated bed
448
+#define THERMAL_PROTECTION_BED     // Enable thermal protection for the heated bed
418 449
 
419 450
 //===========================================================================
420 451
 //============================= Mechanical Settings =========================
@@ -499,14 +530,14 @@
499 530
  * Override with M92
500 531
  *                                      X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]]
501 532
  */
502
-#define DEFAULT_AXIS_STEPS_PER_UNIT   { 160, 160, 8000, 204 }
533
+#define DEFAULT_AXIS_STEPS_PER_UNIT   { 160, 160, 8000, 210.02 }
503 534
 
504 535
 /**
505 536
  * Default Max Feed Rate (mm/s)
506 537
  * Override with M203
507 538
  *                                      X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]]
508 539
  */
509
-#define DEFAULT_MAX_FEEDRATE          { 250, 250, 2, 200 }
540
+#define DEFAULT_MAX_FEEDRATE          { 167, 167, 3.3, 167 }
510 541
 
511 542
 /**
512 543
  * Default Max Acceleration (change/s) change = mm/s
@@ -514,7 +545,7 @@
514 545
  * Override with M201
515 546
  *                                      X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]]
516 547
  */
517
-#define DEFAULT_MAX_ACCELERATION      { 800, 800, 20, 1000 }
548
+#define DEFAULT_MAX_ACCELERATION      { 1000, 1000, 100, 3000 }
518 549
 
519 550
 /**
520 551
  * Default Acceleration (change/s) change = mm/s
@@ -524,8 +555,8 @@
524 555
  *   M204 R    Retract Acceleration
525 556
  *   M204 T    Travel Acceleration
526 557
  */
527
-#define DEFAULT_ACCELERATION           800    // X, Y, Z and E acceleration for printing moves
528
-#define DEFAULT_RETRACT_ACCELERATION  1000    // E acceleration for retracts
558
+#define DEFAULT_ACCELERATION          1000    // X, Y, Z and E acceleration for printing moves
559
+#define DEFAULT_RETRACT_ACCELERATION  3000    // E acceleration for retracts
529 560
 #define DEFAULT_TRAVEL_ACCELERATION   1000    // X, Y, Z acceleration for travel (non printing) moves
530 561
 
531 562
 /**
@@ -536,8 +567,8 @@
536 567
  * When changing speed and direction, if the difference is less than the
537 568
  * value set here, it may happen instantaneously.
538 569
  */
539
-#define DEFAULT_XJERK                 10.0
540
-#define DEFAULT_YJERK                 10.0
570
+#define DEFAULT_XJERK                 20.0
571
+#define DEFAULT_YJERK                 20.0
541 572
 #define DEFAULT_ZJERK                  0.4
542 573
 #define DEFAULT_EJERK                  1.0
543 574
 
@@ -547,7 +578,7 @@
547 578
 // @section probes
548 579
 
549 580
 //
550
-// See http://marlinfw.org/configuration/probes.html
581
+// See http://marlinfw.org/docs/configuration/probes.html
551 582
 //
552 583
 
553 584
 /**
@@ -613,14 +644,15 @@
613 644
 #endif
614 645
 
615 646
 /**
616
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
617
- * options selected below - will be disabled during probing so as to minimize
618
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
619
- * in current flowing through the wires).  This is likely most useful to users of the
620
- * BLTouch probe, but may also help those with inductive or other probe types.
647
+ * Enable one or more of the following if probing seems unreliable.
648
+ * Heaters and/or fans can be disabled during probing to minimize electrical
649
+ * noise. A delay can also be added to allow noise and vibration to settle.
650
+ * These options are most useful for the BLTouch probe, but may also improve
651
+ * readings with inductive probes and piezo sensors.
621 652
  */
622 653
 //#define PROBING_HEATERS_OFF       // Turn heaters off when probing
623 654
 //#define PROBING_FANS_OFF          // Turn fans off when probing
655
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
624 656
 
625 657
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
626 658
 //#define SOLENOID_PROBE
@@ -654,19 +686,21 @@
654 686
  */
655 687
 #define X_PROBE_OFFSET_FROM_EXTRUDER 34  // X offset: -left  +right  [of the nozzle]
656 688
 #define Y_PROBE_OFFSET_FROM_EXTRUDER 15  // Y offset: -front +behind [the nozzle]
657
-#define Z_PROBE_OFFSET_FROM_EXTRUDER 0   // Z offset: -below +above  [the nozzle]
689
+#define Z_PROBE_OFFSET_FROM_EXTRUDER  0  // Z offset: -below +above  [the nozzle]
658 690
 
659 691
 // X and Y axis travel speed (mm/m) between probes
660 692
 #define XY_PROBE_SPEED 8000
661 693
 
662
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
694
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
663 695
 #define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
664 696
 
665 697
 // Speed for the "accurate" probe of each point
666 698
 #define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
667 699
 
668
-// Use double touch for probing
669
-//#define PROBE_DOUBLE_TOUCH
700
+// The number of probes to perform at each point.
701
+//   Set to 2 for a fast/slow probe, using the second probe result.
702
+//   Set to 3 or more for slow probes, averaging the results.
703
+//#define MULTIPLE_PROBING 2
670 704
 
671 705
 /**
672 706
  * Z probes require clearance when deploying, stowing, and moving between
@@ -690,7 +724,7 @@
690 724
 #define Z_PROBE_OFFSET_RANGE_MAX  0
691 725
 
692 726
 // Enable the M48 repeatability test to test probe accuracy
693
-//#define Z_MIN_PROBE_REPEATABILITY_TEST
727
+#define Z_MIN_PROBE_REPEATABILITY_TEST
694 728
 
695 729
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
696 730
 // :{ 0:'Low', 1:'High' }
@@ -733,6 +767,8 @@
733 767
 
734 768
 // @section homing
735 769
 
770
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
771
+
736 772
 #define Z_HOMING_HEIGHT 5    // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
737 773
                              // Be sure you have this distance over your Z_MAX_POS in case.
738 774
 
@@ -744,18 +780,42 @@
744 780
 
745 781
 // @section machine
746 782
 
747
-// Travel limits after homing (units are in mm)
783
+// The size of the print bed
784
+#define X_BED_SIZE 210
785
+#define Y_BED_SIZE 297
786
+
787
+// Travel limits (mm) after homing, corresponding to endstop positions.
748 788
 #define X_MIN_POS 0
749 789
 #define Y_MIN_POS 0
750 790
 #define Z_MIN_POS 0
751
-#define X_MAX_POS 210
752
-#define Y_MAX_POS 297
791
+#define X_MAX_POS X_BED_SIZE
792
+#define Y_MAX_POS Y_BED_SIZE
753 793
 #define Z_MAX_POS 210
754 794
 
755
-// If enabled, axes won't move below MIN_POS in response to movement commands.
795
+/**
796
+ * Software Endstops
797
+ *
798
+ * - Prevent moves outside the set machine bounds.
799
+ * - Individual axes can be disabled, if desired.
800
+ * - X and Y only apply to Cartesian robots.
801
+ * - Use 'M211' to set software endstops on/off or report current state
802
+ */
803
+
804
+// Min software endstops curtail movement below minimum coordinate bounds
756 805
 #define MIN_SOFTWARE_ENDSTOPS
757
-// If enabled, axes won't move above MAX_POS in response to movement commands.
806
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
807
+  #define MIN_SOFTWARE_ENDSTOP_X
808
+  #define MIN_SOFTWARE_ENDSTOP_Y
809
+  #define MIN_SOFTWARE_ENDSTOP_Z
810
+#endif
811
+
812
+// Max software endstops curtail movement above maximum coordinate bounds
758 813
 #define MAX_SOFTWARE_ENDSTOPS
814
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
815
+  #define MAX_SOFTWARE_ENDSTOP_X
816
+  #define MAX_SOFTWARE_ENDSTOP_Y
817
+  #define MAX_SOFTWARE_ENDSTOP_Z
818
+#endif
759 819
 
760 820
 /**
761 821
  * Filament Runout Sensor
@@ -775,7 +835,7 @@
775 835
 //===========================================================================
776 836
 //=============================== Bed Leveling ==============================
777 837
 //===========================================================================
778
-// @section bedlevel
838
+// @section calibrate
779 839
 
780 840
 /**
781 841
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -801,12 +861,7 @@
801 861
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
802 862
  *   A comprehensive bed leveling system combining the features and benefits
803 863
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
804
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
805
- *   for Cartesian Printers. That said, it was primarily designed to correct
806
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
807
- *   please post an issue if something doesn't work correctly. Initially,
808
- *   you will need to set a reduced bed size so you have a rectangular area
809
- *   to test on.
864
+ *   Validation and Mesh Editing systems.
810 865
  *
811 866
  * - MESH_BED_LEVELING
812 867
  *   Probe a grid manually
@@ -817,7 +872,7 @@
817 872
  */
818 873
 //#define AUTO_BED_LEVELING_3POINT
819 874
 //#define AUTO_BED_LEVELING_LINEAR
820
-//#define AUTO_BED_LEVELING_BILINEAR
875
+#define AUTO_BED_LEVELING_BILINEAR
821 876
 //#define AUTO_BED_LEVELING_UBL
822 877
 //#define MESH_BED_LEVELING
823 878
 
@@ -833,18 +888,36 @@
833 888
   // at which point movement will be level to the machine's XY plane.
834 889
   // The height can be set with M420 Z<height>
835 890
   #define ENABLE_LEVELING_FADE_HEIGHT
891
+
892
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
893
+  // split up moves into short segments like a Delta. This follows the
894
+  // contours of the bed more closely than edge-to-edge straight moves.
895
+  #define SEGMENT_LEVELED_MOVES
896
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
897
+
898
+  /**
899
+   * Enable the G26 Mesh Validation Pattern tool.
900
+   */
901
+  //#define G26_MESH_VALIDATION   // Enable G26 mesh validation
902
+  #if ENABLED(G26_MESH_VALIDATION)
903
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
904
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
905
+    #define MESH_TEST_HOTEND_TEMP   205.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
906
+    #define MESH_TEST_BED_TEMP       60.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
907
+  #endif
908
+
836 909
 #endif
837 910
 
838 911
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
839 912
 
840 913
   // Set the number of grid points per dimension.
841 914
   #define GRID_MAX_POINTS_X 3
842
-  #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
915
+  #define GRID_MAX_POINTS_Y 4
843 916
 
844 917
   // Set the boundaries for probing (where the probe can reach).
845
-  #define LEFT_PROBE_BED_POSITION  X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER
918
+  #define LEFT_PROBE_BED_POSITION  X_MIN_POS + (X_PROBE_OFFSET_FROM_EXTRUDER)
846 919
   #define RIGHT_PROBE_BED_POSITION X_MAX_POS - (X_PROBE_OFFSET_FROM_EXTRUDER)
847
-  #define FRONT_PROBE_BED_POSITION Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER
920
+  #define FRONT_PROBE_BED_POSITION Y_MIN_POS + (Y_PROBE_OFFSET_FROM_EXTRUDER)
848 921
   #define BACK_PROBE_BED_POSITION  Y_MAX_POS - (Y_PROBE_OFFSET_FROM_EXTRUDER)
849 922
 
850 923
   // The Z probe minimum outer margin (to validate G29 parameters).
@@ -888,7 +961,9 @@
888 961
   //========================= Unified Bed Leveling ============================
889 962
   //===========================================================================
890 963
 
891
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
964
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
965
+
966
+  #define MESH_INSET 1              // Mesh inset margin on print area
892 967
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
893 968
   #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
894 969
 
@@ -899,8 +974,8 @@
899 974
   #define UBL_PROBE_PT_3_X 180
900 975
   #define UBL_PROBE_PT_3_Y 20
901 976
 
902
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
903 977
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
978
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
904 979
 
905 980
 #elif ENABLED(MESH_BED_LEVELING)
906 981
 
@@ -927,6 +1002,9 @@
927 1002
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
928 1003
 #endif
929 1004
 
1005
+// Add a menu item to move between bed corners for manual bed adjustment
1006
+//#define LEVEL_BED_CORNERS
1007
+
930 1008
 /**
931 1009
  * Commands to execute at the end of G29 probing.
932 1010
  * Useful to retract or move the Z probe out of the way.
@@ -957,14 +1035,71 @@
957 1035
 #define Z_SAFE_HOMING
958 1036
 
959 1037
 #if ENABLED(Z_SAFE_HOMING)
960
-  #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
961
-  #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
1038
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1039
+  #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2)    // Y point for Z homing when homing all axes (G28).
962 1040
 #endif
963 1041
 
964 1042
 // Homing speeds (mm/m)
965 1043
 #define HOMING_FEEDRATE_XY (60*60)
966 1044
 #define HOMING_FEEDRATE_Z  120
967 1045
 
1046
+// @section calibrate
1047
+
1048
+/**
1049
+ * Bed Skew Compensation
1050
+ *
1051
+ * This feature corrects for misalignment in the XYZ axes.
1052
+ *
1053
+ * Take the following steps to get the bed skew in the XY plane:
1054
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1055
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1056
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1057
+ *  4. For XY_SIDE_AD measure the edge A to D
1058
+ *
1059
+ * Marlin automatically computes skew factors from these measurements.
1060
+ * Skew factors may also be computed and set manually:
1061
+ *
1062
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1063
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1064
+ *
1065
+ * If desired, follow the same procedure for XZ and YZ.
1066
+ * Use these diagrams for reference:
1067
+ *
1068
+ *    Y                     Z                     Z
1069
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1070
+ *    |    /       /        |    /       /        |    /       /
1071
+ *    |   /       /         |   /       /         |   /       /
1072
+ *    |  A-------D          |  A-------D          |  A-------D
1073
+ *    +-------------->X     +-------------->X     +-------------->Y
1074
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1075
+ */
1076
+//#define SKEW_CORRECTION
1077
+
1078
+#if ENABLED(SKEW_CORRECTION)
1079
+  // Input all length measurements here:
1080
+  #define XY_DIAG_AC 282.8427124746
1081
+  #define XY_DIAG_BD 282.8427124746
1082
+  #define XY_SIDE_AD 200
1083
+
1084
+  // Or, set the default skew factors directly here
1085
+  // to override the above measurements:
1086
+  #define XY_SKEW_FACTOR 0.0
1087
+
1088
+  //#define SKEW_CORRECTION_FOR_Z
1089
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1090
+    #define XZ_DIAG_AC 282.8427124746
1091
+    #define XZ_DIAG_BD 282.8427124746
1092
+    #define YZ_DIAG_AC 282.8427124746
1093
+    #define YZ_DIAG_BD 282.8427124746
1094
+    #define YZ_SIDE_AD 200
1095
+    #define XZ_SKEW_FACTOR 0.0
1096
+    #define YZ_SKEW_FACTOR 0.0
1097
+  #endif
1098
+
1099
+  // Enable this option for M852 to set skew at runtime
1100
+  //#define SKEW_CORRECTION_GCODE
1101
+#endif
1102
+
968 1103
 //=============================================================================
969 1104
 //============================= Additional Features ===========================
970 1105
 //=============================================================================
@@ -991,11 +1126,12 @@
991 1126
 //
992 1127
 #define HOST_KEEPALIVE_FEATURE        // Disable this if your host doesn't like keepalive messages
993 1128
 #define DEFAULT_KEEPALIVE_INTERVAL 10 // Number of seconds between "busy" messages. Set with M113.
1129
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
994 1130
 
995 1131
 //
996 1132
 // M100 Free Memory Watcher
997 1133
 //
998
-//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1134
+//#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
999 1135
 
1000 1136
 //
1001 1137
 // G20/G21 Inch mode support
@@ -1010,12 +1146,12 @@
1010 1146
 // @section temperature
1011 1147
 
1012 1148
 // Preheat Constants
1013
-#define PREHEAT_1_TEMP_HOTEND 210
1014
-#define PREHEAT_1_TEMP_BED     70
1149
+#define PREHEAT_1_TEMP_HOTEND 205
1150
+#define PREHEAT_1_TEMP_BED     50
1015 1151
 #define PREHEAT_1_FAN_SPEED     0 // Value from 0 to 255
1016 1152
 
1017
-#define PREHEAT_2_TEMP_HOTEND 240
1018
-#define PREHEAT_2_TEMP_BED    110
1153
+#define PREHEAT_2_TEMP_HOTEND 245
1154
+#define PREHEAT_2_TEMP_BED     50
1019 1155
 #define PREHEAT_2_FAN_SPEED     0 // Value from 0 to 255
1020 1156
 
1021 1157
 /**
@@ -1140,11 +1276,11 @@
1140 1276
  *
1141 1277
  * Select the language to display on the LCD. These languages are available:
1142 1278
  *
1143
- *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
1144
- *    it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
1145
- *    zh_CN, zh_TW, test
1279
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1280
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1281
+ *    tr, uk, zh_CN, zh_TW, test
1146 1282
  *
1147
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1283
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1148 1284
  */
1149 1285
 #define LCD_LANGUAGE en
1150 1286
 
@@ -1166,7 +1302,7 @@
1166 1302
  *  - Click the controller to view the LCD menu
1167 1303
  *  - The LCD will display Japanese, Western, or Cyrillic text
1168 1304
  *
1169
- * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1305
+ * See http://marlinfw.org/docs/development/lcd_language.html
1170 1306
  *
1171 1307
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1172 1308
  */
@@ -1272,8 +1408,8 @@
1272 1408
 // Note: Test audio output with the G-Code:
1273 1409
 //  M300 S<frequency Hz> P<duration ms>
1274 1410
 //
1275
-//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
1276
-//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
1411
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
1412
+//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
1277 1413
 
1278 1414
 //
1279 1415
 // CONTROLLER TYPE: Standard
@@ -1381,11 +1517,13 @@
1381 1517
 //#define CARTESIO_UI
1382 1518
 
1383 1519
 //
1384
-// ANET_10 Controller supported displays.
1520
+// ANET and Tronxy Controller supported displays.
1385 1521
 //
1386
-//#define ANET_KEYPAD_LCD         // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1522
+//#define ZONESTAR_LCD            // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1387 1523
                                   // This LCD is known to be susceptible to electrical interference
1388 1524
                                   // which scrambles the display.  Pressing any button clears it up.
1525
+                                  // This is a LCD2004 display with 5 analog buttons.
1526
+
1389 1527
 //#define ANET_FULL_GRAPHICS_LCD  // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1390 1528
                                   // A clone of the RepRapDiscount full graphics display but with
1391 1529
                                   // different pins/wiring (see pins_ANET_10.h).
@@ -1445,11 +1583,6 @@
1445 1583
 //#define U8GLIB_SSD1306
1446 1584
 
1447 1585
 //
1448
-// TinyBoy2 128x64 OLED / Encoder Panel
1449
-//
1450
-//#define OLED_PANEL_TINYBOY2
1451
-
1452
-//
1453 1586
 // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules
1454 1587
 //
1455 1588
 //#define SAV_3DGLCD
@@ -1466,6 +1599,45 @@
1466 1599
 //
1467 1600
 //#define SAV_3DLCD
1468 1601
 
1602
+//
1603
+// TinyBoy2 128x64 OLED / Encoder Panel
1604
+//
1605
+//#define OLED_PANEL_TINYBOY2
1606
+
1607
+//
1608
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1609
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1610
+//
1611
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1612
+
1613
+//
1614
+// MKS MINI12864 with graphic controller and SD support
1615
+// http://reprap.org/wiki/MKS_MINI_12864
1616
+//
1617
+//#define MKS_MINI_12864
1618
+
1619
+//
1620
+// Factory display for Creality CR-10
1621
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1622
+//
1623
+// This is RAMPS-compatible using a single 10-pin connector.
1624
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1625
+//
1626
+//#define CR10_STOCKDISPLAY
1627
+
1628
+//
1629
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1630
+// http://reprap.org/wiki/MKS_12864OLED
1631
+//
1632
+// Tiny, but very sharp OLED display
1633
+//
1634
+//#define MKS_12864OLED
1635
+
1636
+// Silvergate GLCD controller
1637
+// http://github.com/android444/Silvergate
1638
+//
1639
+//#define SILVER_GATE_GLCD_CONTROLLER
1640
+
1469 1641
 //=============================================================================
1470 1642
 //=============================== Extra Features ==============================
1471 1643
 //=============================================================================
@@ -1522,16 +1694,22 @@
1522 1694
  * Adds the M150 command to set the LED (or LED strip) color.
1523 1695
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1524 1696
  * luminance values can be set from 0 to 255.
1697
+ * For Neopixel LED an overall brightness parameter is also available.
1525 1698
  *
1526 1699
  * *** CAUTION ***
1527 1700
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1528 1701
  *  as the Arduino cannot handle the current the LEDs will require.
1529 1702
  *  Failure to follow this precaution can destroy your Arduino!
1703
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1704
+ *  more current than the Arduino 5V linear regulator can produce.
1530 1705
  * *** CAUTION ***
1531 1706
  *
1707
+ * LED Type. Enable only one of the following two options.
1708
+ *
1532 1709
  */
1533 1710
 //#define RGB_LED
1534 1711
 //#define RGBW_LED
1712
+
1535 1713
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1536 1714
   #define RGB_LED_R_PIN 34
1537 1715
   #define RGB_LED_G_PIN 43
@@ -1539,6 +1717,17 @@
1539 1717
   #define RGB_LED_W_PIN -1
1540 1718
 #endif
1541 1719
 
1720
+// Support for Adafruit Neopixel LED driver
1721
+//#define NEOPIXEL_LED
1722
+#if ENABLED(NEOPIXEL_LED)
1723
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1724
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1725
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1726
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1727
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1728
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1729
+#endif
1730
+
1542 1731
 /**
1543 1732
  * Printer Event LEDs
1544 1733
  *
@@ -1550,68 +1739,32 @@
1550 1739
  *  - Change to green once print has finished
1551 1740
  *  - Turn off after the print has finished and the user has pushed a button
1552 1741
  */
1553
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)
1742
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1554 1743
   #define PRINTER_EVENT_LEDS
1555 1744
 #endif
1556 1745
 
1557
-/*********************************************************************\
1558
-* R/C SERVO support
1559
-* Sponsored by TrinityLabs, Reworked by codexmas
1560
-**********************************************************************/
1746
+/**
1747
+ * R/C SERVO support
1748
+ * Sponsored by TrinityLabs, Reworked by codexmas
1749
+ */
1561 1750
 
1562
-// Number of servos
1563
-//
1564
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1565
-// set it manually if you have more servos than extruders and wish to manually control some
1566
-// leaving it undefined or defining as 0 will disable the servo subsystem
1567
-// If unsure, leave commented / disabled
1568
-//
1751
+/**
1752
+ * Number of servos
1753
+ *
1754
+ * For some servo-related options NUM_SERVOS will be set automatically.
1755
+ * Set this manually if there are extra servos needing manual control.
1756
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1757
+ */
1569 1758
 //#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
1570 1759
 
1571 1760
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1572 1761
 // 300ms is a good value but you can try less delay.
1573 1762
 // If the servo can't reach the requested position, increase it.
1574
-#define SERVO_DELAY 300
1763
+#define SERVO_DELAY { 300 }
1575 1764
 
1576 1765
 // Servo deactivation
1577 1766
 //
1578 1767
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1579 1768
 //#define DEACTIVATE_SERVOS_AFTER_MOVE
1580 1769
 
1581
-/**
1582
- * Filament Width Sensor
1583
- *
1584
- * Measures the filament width in real-time and adjusts
1585
- * flow rate to compensate for any irregularities.
1586
- *
1587
- * Also allows the measured filament diameter to set the
1588
- * extrusion rate, so the slicer only has to specify the
1589
- * volume.
1590
- *
1591
- * Only a single extruder is supported at this time.
1592
- *
1593
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1594
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1595
- * 301 RAMBO       : Analog input 3
1596
- *
1597
- * Note: May require analog pins to be defined for other boards.
1598
- */
1599
-//#define FILAMENT_WIDTH_SENSOR
1600
-
1601
-#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00   // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
1602
-
1603
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1604
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1605
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1606
-
1607
-  #define MEASURED_UPPER_LIMIT         2.00 // (mm) Upper limit used to validate sensor reading
1608
-  #define MEASURED_LOWER_LIMIT         1.60 // (mm) Lower limit used to validate sensor reading
1609
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1610
-
1611
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1612
-
1613
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1614
-  //#define FILAMENT_LCD_DISPLAY
1615
-#endif
1616
-
1617 1770
 #endif // CONFIGURATION_H

Marlin/example_configurations/Hephestos_2/Configuration_adv.h → Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h 파일 보기

@@ -32,7 +32,7 @@
32 32
  */
33 33
 #ifndef CONFIGURATION_ADV_H
34 34
 #define CONFIGURATION_ADV_H
35
-#define CONFIGURATION_ADV_H_VERSION 010100
35
+#define CONFIGURATION_ADV_H_VERSION 010107
36 36
 
37 37
 // @section temperature
38 38
 
@@ -48,31 +48,36 @@
48 48
 #endif
49 49
 
50 50
 /**
51
- * Thermal Protection protects your printer from damage and fire if a
52
- * thermistor falls out or temperature sensors fail in any way.
51
+ * Thermal Protection provides additional protection to your printer from damage
52
+ * and fire. Marlin always includes safe min and max temperature ranges which
53
+ * protect against a broken or disconnected thermistor wire.
53 54
  *
54
- * The issue: If a thermistor falls out or a temperature sensor fails,
55
- * Marlin can no longer sense the actual temperature. Since a disconnected
56
- * thermistor reads as a low temperature, the firmware will keep the heater on.
55
+ * The issue: If a thermistor falls out, it will report the much lower
56
+ * temperature of the air in the room, and the the firmware will keep
57
+ * the heater on.
57 58
  *
58 59
  * The solution: Once the temperature reaches the target, start observing.
59
- * If the temperature stays too far below the target (hysteresis) for too long (period),
60
- * the firmware will halt the machine as a safety precaution.
60
+ * If the temperature stays too far below the target (hysteresis) for too
61
+ * long (period), the firmware will halt the machine as a safety precaution.
61 62
  *
62
- * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63
+ * If you get false positives for "Thermal Runaway", increase
64
+ * THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63 65
  */
64 66
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
65 67
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
66 68
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
67 69
 
68 70
   /**
69
-   * Whenever an M104 or M109 increases the target temperature the firmware will wait for the
70
-   * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
71
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
72
-   * but only if the current temperature is far enough below the target for a reliable test.
71
+   * Whenever an M104, M109, or M303 increases the target temperature, the
72
+   * firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
73
+   * hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
74
+   * requires a hard reset. This test restarts with any M104/M109/M303, but only
75
+   * if the current temperature is far enough below the target for a reliable
76
+   * test.
73 77
    *
74
-   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
75
-   * WATCH_TEMP_INCREASE should not be below 2.
78
+   * If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
79
+   * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
80
+   * below 2.
76 81
    */
77 82
   #define WATCH_TEMP_PERIOD 20                // Seconds
78 83
   #define WATCH_TEMP_INCREASE 2               // Degrees Celsius
@@ -86,13 +91,7 @@
86 91
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
87 92
 
88 93
   /**
89
-   * Whenever an M140 or M190 increases the target temperature the firmware will wait for the
90
-   * WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
91
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
92
-   * but only if the current temperature is far enough below the target for a reliable test.
93
-   *
94
-   * If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
95
-   * WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
94
+   * As described above, except for the bed (M140/M190/M303).
96 95
    */
97 96
   #define WATCH_BED_TEMP_PERIOD 60                // Seconds
98 97
   #define WATCH_BED_TEMP_INCREASE 2               // Degrees Celsius
@@ -123,6 +122,9 @@
123 122
   #define AUTOTEMP_OLDWEIGHT 0.98
124 123
 #endif
125 124
 
125
+// Show extra position information in M114
126
+//#define M114_DETAIL
127
+
126 128
 // Show Temperature ADC value
127 129
 // Enable for M105 to include ADC values read from temperature sensors.
128 130
 //#define SHOW_TEMP_ADC_VALUES
@@ -161,8 +163,8 @@
161 163
 // then extrude some filament every couple of SECONDS.
162 164
 #define EXTRUDER_RUNOUT_PREVENT
163 165
 #if ENABLED(EXTRUDER_RUNOUT_PREVENT)
164
-  #define EXTRUDER_RUNOUT_MINTEMP 190
165
-  #define EXTRUDER_RUNOUT_SECONDS 30
166
+  #define EXTRUDER_RUNOUT_MINTEMP 170
167
+  #define EXTRUDER_RUNOUT_SECONDS 60
166 168
   #define EXTRUDER_RUNOUT_SPEED 1500  // mm/m
167 169
   #define EXTRUDER_RUNOUT_EXTRUDE 5   // mm
168 170
 #endif
@@ -221,6 +223,17 @@
221 223
 #define EXTRUDER_AUTO_FAN_SPEED   255  // == full speed
222 224
 
223 225
 /**
226
+ * Part-Cooling Fan Multiplexer
227
+ *
228
+ * This feature allows you to digitally multiplex the fan output.
229
+ * The multiplexer is automatically switched at tool-change.
230
+ * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans.
231
+ */
232
+#define FANMUX0_PIN -1
233
+#define FANMUX1_PIN -1
234
+#define FANMUX2_PIN -1
235
+
236
+/**
224 237
  * M355 Case Light on-off / brightness
225 238
  */
226 239
 //#define CASE_LIGHT_ENABLE
@@ -246,48 +259,49 @@
246 259
 
247 260
 //#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
248 261
 
249
-// Dual X Steppers
250
-// Uncomment this option to drive two X axis motors.
251
-// The next unused E driver will be assigned to the second X stepper.
262
+/**
263
+ * Dual Steppers / Dual Endstops
264
+ *
265
+ * This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
266
+ *
267
+ * For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
268
+ * spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
269
+ * set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
270
+ * that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
271
+ *
272
+ * Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
273
+ * this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
274
+ * in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
275
+ */
276
+
252 277
 //#define X_DUAL_STEPPER_DRIVERS
253 278
 #if ENABLED(X_DUAL_STEPPER_DRIVERS)
254
-  // Set true if the two X motors need to rotate in opposite directions
255
-  #define INVERT_X2_VS_X_DIR true
279
+  #define INVERT_X2_VS_X_DIR true   // Set 'true' if X motors should rotate in opposite directions
280
+  //#define X_DUAL_ENDSTOPS
281
+  #if ENABLED(X_DUAL_ENDSTOPS)
282
+    #define X2_USE_ENDSTOP _XMAX_
283
+    #define X_DUAL_ENDSTOPS_ADJUSTMENT  0
284
+  #endif
256 285
 #endif
257 286
 
258
-// Dual Y Steppers
259
-// Uncomment this option to drive two Y axis motors.
260
-// The next unused E driver will be assigned to the second Y stepper.
261 287
 //#define Y_DUAL_STEPPER_DRIVERS
262 288
 #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
263
-  // Set true if the two Y motors need to rotate in opposite directions
264
-  #define INVERT_Y2_VS_Y_DIR true
289
+  #define INVERT_Y2_VS_Y_DIR true   // Set 'true' if Y motors should rotate in opposite directions
290
+  //#define Y_DUAL_ENDSTOPS
291
+  #if ENABLED(Y_DUAL_ENDSTOPS)
292
+    #define Y2_USE_ENDSTOP _YMAX_
293
+    #define Y_DUAL_ENDSTOPS_ADJUSTMENT  0
294
+  #endif
265 295
 #endif
266 296
 
267
-// A single Z stepper driver is usually used to drive 2 stepper motors.
268
-// Uncomment this option to use a separate stepper driver for each Z axis motor.
269
-// The next unused E driver will be assigned to the second Z stepper.
270 297
 //#define Z_DUAL_STEPPER_DRIVERS
271
-
272 298
 #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
273
-
274
-  // Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper.
275
-  // That way the machine is capable to align the bed during home, since both Z steppers are homed.
276
-  // There is also an implementation of M666 (software endstops adjustment) to this feature.
277
-  // After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
278
-  // One just need to home the Z axis and measure the distance difference between both Z axis and apply the math: Z adjust = Z - Z2.
279
-  // If the Z stepper axis is closer to the bed, the measure Z > Z2 (yes, it is.. think about it) and the Z adjust would be positive.
280
-  // Play a little bit with small adjustments (0.5mm) and check the behaviour.
281
-  // The M119 (endstops report) will start reporting the Z2 Endstop as well.
282
-
283 299
   //#define Z_DUAL_ENDSTOPS
284
-
285 300
   #if ENABLED(Z_DUAL_ENDSTOPS)
286 301
     #define Z2_USE_ENDSTOP _XMAX_
287
-    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0  // use M666 command to determine this value
302
+    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0
288 303
   #endif
289
-
290
-#endif // Z_DUAL_STEPPER_DRIVERS
304
+#endif
291 305
 
292 306
 // Enable this for dual x-carriage printers.
293 307
 // A dual x-carriage design has the advantage that the inactive extruder can be parked which
@@ -334,12 +348,12 @@
334 348
 
335 349
 // @section homing
336 350
 
337
-//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
351
+// Homing hits each endstop, retracts by these distances, then does a slower bump.
338 352
 #define X_HOME_BUMP_MM 5
339 353
 #define Y_HOME_BUMP_MM 5
340 354
 #define Z_HOME_BUMP_MM 2
341
-#define HOMING_BUMP_DIVISOR {2, 2, 4}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
342
-#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
355
+#define HOMING_BUMP_DIVISOR { 2, 2, 4 }  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
356
+#define QUICK_HOME                       // If homing includes X and Y, do a diagonal move initially
343 357
 
344 358
 // When G28 is called, this option will make Y home before X
345 359
 #define HOME_Y_BEFORE_X
@@ -369,7 +383,7 @@
369 383
 #define DEFAULT_MINIMUMFEEDRATE       0.0     // minimum feedrate
370 384
 #define DEFAULT_MINTRAVELFEEDRATE     0.0
371 385
 
372
-//#define HOME_AFTER_DEACTIVATE  // Require rehoming after steppers are deactivated
386
+#define HOME_AFTER_DEACTIVATE  // Require rehoming after steppers are deactivated
373 387
 
374 388
 // @section lcd
375 389
 
@@ -423,8 +437,21 @@
423 437
 #define DIGIPOT_MOTOR_CURRENT { 150, 170, 180, 190, 180 }   // Values 0-255 (bq ZUM Mega 3D (default): X = 150 [~1.17A]; Y = 170 [~1.33A]; Z = 180 [~1.41A]; E0 = 190 [~1.49A])
424 438
 //#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 }      // Default drive percent - X, Y, Z, E axis
425 439
 
426
-// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
440
+// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
427 441
 //#define DIGIPOT_I2C
442
+#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
443
+  /**
444
+   * Common slave addresses:
445
+   *
446
+   *                    A   (A shifted)   B   (B shifted)  IC
447
+   * Smoothie          0x2C (0x58)       0x2D (0x5A)       MCP4451
448
+   * AZTEEG_X3_PRO     0x2C (0x58)       0x2E (0x5C)       MCP4451
449
+   * MIGHTYBOARD_REVE  0x2F (0x5E)                         MCP4018
450
+   */
451
+  #define DIGIPOT_I2C_ADDRESS_A 0x2C  // unshifted slave address for first DIGIPOT
452
+  #define DIGIPOT_I2C_ADDRESS_B 0x2D  // unshifted slave address for second DIGIPOT
453
+#endif
454
+
428 455
 //#define DIGIPOT_MCP4018          // Requires library from https://github.com/stawel/SlowSoftI2CMaster
429 456
 #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4     AZTEEG_X3_PRO: 8
430 457
 // Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
@@ -447,11 +474,31 @@
447 474
 #define LCD_INFO_MENU
448 475
 
449 476
 // Scroll a longer status message into view
450
-//#define STATUS_MESSAGE_SCROLLING
477
+#define STATUS_MESSAGE_SCROLLING
451 478
 
452 479
 // On the Info Screen, display XY with one decimal place when possible
453 480
 #define LCD_DECIMAL_SMALL_XY
454 481
 
482
+// The timeout (in ms) to return to the status screen from sub-menus
483
+//#define LCD_TIMEOUT_TO_STATUS 15000
484
+
485
+/**
486
+ * LED Control Menu
487
+ * Enable this feature to add LED Control to the LCD menu
488
+ */
489
+//#define LED_CONTROL_MENU
490
+#if ENABLED(LED_CONTROL_MENU)
491
+  #define LED_COLOR_PRESETS                 // Enable the Preset Color menu option
492
+  #if ENABLED(LED_COLOR_PRESETS)
493
+    #define LED_USER_PRESET_RED        255  // User defined RED value
494
+    #define LED_USER_PRESET_GREEN      128  // User defined GREEN value
495
+    #define LED_USER_PRESET_BLUE         0  // User defined BLUE value
496
+    #define LED_USER_PRESET_WHITE      255  // User defined WHITE value
497
+    #define LED_USER_PRESET_BRIGHTNESS 255  // User defined intensity
498
+    //#define LED_USER_PRESET_STARTUP       // Have the printer display the user preset color on startup
499
+  #endif
500
+#endif // LED_CONTROL_MENU
501
+
455 502
 #if ENABLED(SDSUPPORT)
456 503
 
457 504
   // Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -461,12 +508,14 @@
461 508
   // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
462 509
   #define SD_DETECT_INVERTED
463 510
 
464
-  #define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
511
+  #define SD_FINISHED_STEPPERRELEASE true          // Disable steppers when SD Print is finished
465 512
   #define SD_FINISHED_RELEASECOMMAND "M104 S0\nM84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
466 513
 
467
-  #define SDCARD_RATHERRECENTFIRST  //reverse file order of sd card menu display. Its sorted practically after the file system block order.
468
-  // if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that.
469
-  // using:
514
+  // Reverse SD sort to show "more recent" files first, according to the card's FAT.
515
+  // Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
516
+  #define SDCARD_RATHERRECENTFIRST
517
+
518
+  // Add an option in the menu to run all auto#.g files
470 519
   //#define MENU_ADDAUTOSTART
471 520
 
472 521
   /**
@@ -496,13 +545,15 @@
496 545
 
497 546
   // SD Card Sorting options
498 547
   #if ENABLED(SDCARD_SORT_ALPHA)
499
-    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256).
548
+    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256). Costs 27 bytes each.
500 549
     #define FOLDER_SORTING     -1     // -1=above  0=none  1=below
501 550
     #define SDSORT_GCODE       false  // Allow turning sorting on/off with LCD and M34 g-code.
502 551
     #define SDSORT_USES_RAM    false  // Pre-allocate a static array for faster pre-sorting.
503 552
     #define SDSORT_USES_STACK  false  // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
504 553
     #define SDSORT_CACHE_NAMES false  // Keep sorted items in RAM longer for speedy performance. Most expensive option.
505 554
     #define SDSORT_DYNAMIC_RAM false  // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
555
+    #define SDSORT_CACHE_VFATS 2      // Maximum number of 13-byte VFAT entries to use for sorting.
556
+                                      // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
506 557
   #endif
507 558
 
508 559
   // Show a progress bar on HD44780 LCDs for SD printing
@@ -521,18 +572,50 @@
521 572
     //#define LCD_PROGRESS_BAR_TEST
522 573
   #endif
523 574
 
575
+  // Add an 'M73' G-code to set the current percentage
576
+  //#define LCD_SET_PROGRESS_MANUALLY
577
+
524 578
   // This allows hosts to request long names for files and folders with M33
525 579
   #define LONG_FILENAME_HOST_SUPPORT
526 580
 
527
-  // This option allows you to abort SD printing when any endstop is triggered.
528
-  // This feature must be enabled with "M540 S1" or from the LCD menu.
529
-  // To have any effect, endstops must be enabled during SD printing.
581
+  // Enable this option to scroll long filenames in the SD card menu
582
+  //#define SCROLL_LONG_FILENAMES
583
+
584
+  /**
585
+   * This option allows you to abort SD printing when any endstop is triggered.
586
+   * This feature must be enabled with "M540 S1" or from the LCD menu.
587
+   * To have any effect, endstops must be enabled during SD printing.
588
+   */
530 589
   //#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
531 590
 
591
+  /**
592
+   * This option makes it easier to print the same SD Card file again.
593
+   * On print completion the LCD Menu will open with the file selected.
594
+   * You can just click to start the print, or navigate elsewhere.
595
+   */
596
+  //#define SD_REPRINT_LAST_SELECTED_FILE
597
+
532 598
 #endif // SDSUPPORT
533 599
 
534
-// Some additional options are available for graphical displays:
600
+/**
601
+ * Additional options for Graphical Displays
602
+ *
603
+ * Use the optimizations here to improve printing performance,
604
+ * which can be adversely affected by graphical display drawing,
605
+ * especially when doing several short moves, and when printing
606
+ * on DELTA and SCARA machines.
607
+ *
608
+ * Some of these options may result in the display lagging behind
609
+ * controller events, as there is a trade-off between reliable
610
+ * printing performance versus fast display updates.
611
+ */
535 612
 #if ENABLED(DOGLCD)
613
+  // Enable to save many cycles by drawing a hollow frame on the Info Screen
614
+  #define XYZ_HOLLOW_FRAME
615
+
616
+  // Enable to save many cycles by drawing a hollow frame on Menu Screens
617
+  #define MENU_HOLLOW_FRAME
618
+
536 619
   // A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
537 620
   // Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
538 621
   #define USE_BIG_EDIT_FONT
@@ -544,6 +627,10 @@
544 627
   // Enable this option and reduce the value to optimize screen updates.
545 628
   // The normal delay is 10µs. Use the lowest value that still gives a reliable display.
546 629
   //#define DOGM_SPI_DELAY_US 5
630
+
631
+  // Swap the CW/CCW indicators in the graphics overlay
632
+  //#define OVERLAY_GFX_REVERSE
633
+
547 634
 #endif // DOGLCD
548 635
 
549 636
 // @section safety
@@ -570,31 +657,18 @@
570 657
  */
571 658
 //#define BABYSTEPPING
572 659
 #if ENABLED(BABYSTEPPING)
573
-  #define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
574
-  #define BABYSTEP_INVERT_Z false  // Change if Z babysteps should go the other way
575
-  #define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
576
-  //#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
660
+  //#define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
661
+  #define BABYSTEP_INVERT_Z false    // Change if Z babysteps should go the other way
662
+  #define BABYSTEP_MULTIPLICATOR 1   // Babysteps are very small. Increase for faster motion.
663
+  //#define BABYSTEP_ZPROBE_OFFSET   // Enable to combine M851 and Babystepping
577 664
   //#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
578 665
   #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
579 666
                                         // Note: Extra time may be added to mitigate controller latency.
667
+  //#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
580 668
 #endif
581 669
 
582 670
 // @section extruder
583 671
 
584
-// extruder advance constant (s2/mm3)
585
-//
586
-// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
587
-//
588
-// Hooke's law says:    force = k * distance
589
-// Bernoulli's principle says:  v ^ 2 / 2 + g . h + pressure / density = constant
590
-// so: v ^ 2 is proportional to number of steps we advance the extruder
591
-//#define ADVANCE
592
-
593
-#if ENABLED(ADVANCE)
594
-  #define EXTRUDER_ADVANCE_K .0
595
-  #define D_FILAMENT 2.85
596
-#endif
597
-
598 672
 /**
599 673
  * Implementation of linear pressure control
600 674
  *
@@ -628,7 +702,7 @@
628 702
    *
629 703
    * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
630 704
    *
631
-   * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode.
705
+   * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
632 706
    * Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
633 707
    */
634 708
   #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
@@ -637,19 +711,18 @@
637 711
 
638 712
 // @section leveling
639 713
 
640
-// Default mesh area is an area with an inset margin on the print area.
641
-// Below are the macros that are used to define the borders for the mesh area,
642
-// made available here for specialized needs, ie dual extruder setup.
643
-#if ENABLED(MESH_BED_LEVELING)
644
-  #define MESH_MIN_X (X_MIN_POS + MESH_INSET)
645
-  #define MESH_MAX_X (X_MAX_POS - (MESH_INSET))
646
-  #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET)
647
-  #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET))
648
-#elif ENABLED(AUTO_BED_LEVELING_UBL)
649
-  #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET)
650
-  #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET))
651
-  #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET)
652
-  #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET))
714
+#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
715
+  #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
716
+#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
717
+  #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
718
+#endif
719
+
720
+#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
721
+  // Override the mesh area if the automatic (max) area is too large
722
+  //#define MESH_MIN_X MESH_INSET
723
+  //#define MESH_MIN_Y MESH_INSET
724
+  //#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
725
+  //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
653 726
 #endif
654 727
 
655 728
 // @section extras
@@ -669,7 +742,7 @@
669 742
 //#define BEZIER_CURVE_SUPPORT
670 743
 
671 744
 // G38.2 and G38.3 Probe Target
672
-// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
745
+// Set MULTIPLE_PROBING if you want G38 to double touch
673 746
 //#define G38_PROBE_TARGET
674 747
 #if ENABLED(G38_PROBE_TARGET)
675 748
   #define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
@@ -694,7 +767,7 @@
694 767
 // @section hidden
695 768
 
696 769
 // The number of linear motions that can be in the plan at any give time.
697
-// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
770
+// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
698 771
 #if ENABLED(SDSUPPORT)
699 772
   #define BLOCK_BUFFER_SIZE 32 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
700 773
 #else
@@ -707,7 +780,7 @@
707 780
 #define MAX_CMD_SIZE 96
708 781
 #define BUFSIZE 4
709 782
 
710
-// Transfer Buffer Size
783
+// Transmission to Host Buffer Size
711 784
 // To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0.
712 785
 // To buffer a simple "ok" you need 4 bytes.
713 786
 // For ADVANCED_OK (M105) you need 32 bytes.
@@ -716,11 +789,33 @@
716 789
 // :[0, 2, 4, 8, 16, 32, 64, 128, 256]
717 790
 #define TX_BUFFER_SIZE 32
718 791
 
792
+// Host Receive Buffer Size
793
+// Without XON/XOFF flow control (see SERIAL_XON_XOFF below) 32 bytes should be enough.
794
+// To use flow control, set this buffer size to at least 1024 bytes.
795
+// :[0, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048]
796
+//#define RX_BUFFER_SIZE 1024
797
+
798
+#if RX_BUFFER_SIZE >= 1024
799
+  // Enable to have the controller send XON/XOFF control characters to
800
+  // the host to signal the RX buffer is becoming full.
801
+  //#define SERIAL_XON_XOFF
802
+#endif
803
+
804
+#if ENABLED(SDSUPPORT)
805
+  // Enable this option to collect and display the maximum
806
+  // RX queue usage after transferring a file to SD.
807
+  //#define SERIAL_STATS_MAX_RX_QUEUED
808
+
809
+  // Enable this option to collect and display the number
810
+  // of dropped bytes after a file transfer to SD.
811
+  //#define SERIAL_STATS_DROPPED_RX
812
+#endif
813
+
719 814
 // Enable an emergency-command parser to intercept certain commands as they
720 815
 // enter the serial receive buffer, so they cannot be blocked.
721 816
 // Currently handles M108, M112, M410
722 817
 // Does not work on boards using AT90USB (USBCON) processors!
723
-//#define EMERGENCY_PARSER
818
+#define EMERGENCY_PARSER
724 819
 
725 820
 // Bad Serial-connections can miss a received command by sending an 'ok'
726 821
 // Therefore some clients abort after 30 seconds in a timeout.
@@ -729,29 +824,49 @@
729 824
 //#define NO_TIMEOUTS 1000 // Milliseconds
730 825
 
731 826
 // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary.
732
-//#define ADVANCED_OK
733
-
734
-// @section fwretract
827
+#define ADVANCED_OK
735 828
 
736
-// Firmware based and LCD controlled retract
737
-// M207 and M208 can be used to define parameters for the retraction.
738
-// The retraction can be called by the slicer using G10 and G11
739
-// until then, intended retractions can be detected by moves that only extrude and the direction.
740
-// the moves are than replaced by the firmware controlled ones.
829
+// @section extras
741 830
 
742
-//#define FWRETRACT  //ONLY PARTIALLY TESTED
831
+/**
832
+ * Firmware-based and LCD-controlled retract
833
+ *
834
+ * Add G10 / G11 commands for automatic firmware-based retract / recover.
835
+ * Use M207 and M208 to define parameters for retract / recover.
836
+ *
837
+ * Use M209 to enable or disable auto-retract.
838
+ * With auto-retract enabled, all G1 E moves within the set range
839
+ * will be converted to firmware-based retract/recover moves.
840
+ *
841
+ * Be sure to turn off auto-retract during filament change.
842
+ *
843
+ * Note that M207 / M208 / M209 settings are saved to EEPROM.
844
+ *
845
+ */
846
+//#define FWRETRACT  // ONLY PARTIALLY TESTED
743 847
 #if ENABLED(FWRETRACT)
744
-  #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
745
-  #define RETRACT_LENGTH 3               //default retract length (positive mm)
746
-  #define RETRACT_LENGTH_SWAP 13         //default swap retract length (positive mm), for extruder change
747
-  #define RETRACT_FEEDRATE 45            //default feedrate for retracting (mm/s)
748
-  #define RETRACT_ZLIFT 0                //default retract Z-lift
749
-  #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
750
-  #define RETRACT_RECOVER_LENGTH_SWAP 0  //default additional swap recover length (mm, added to retract length when recovering from extruder change)
751
-  #define RETRACT_RECOVER_FEEDRATE 8     //default feedrate for recovering from retraction (mm/s)
848
+  #define MIN_AUTORETRACT 0.1             // When auto-retract is on, convert E moves of this length and over
849
+  #define MAX_AUTORETRACT 10.0            // Upper limit for auto-retract conversion
850
+  #define RETRACT_LENGTH 3                // Default retract length (positive mm)
851
+  #define RETRACT_LENGTH_SWAP 13          // Default swap retract length (positive mm), for extruder change
852
+  #define RETRACT_FEEDRATE 45             // Default feedrate for retracting (mm/s)
853
+  #define RETRACT_ZLIFT 0                 // Default retract Z-lift
854
+  #define RETRACT_RECOVER_LENGTH 0        // Default additional recover length (mm, added to retract length when recovering)
855
+  #define RETRACT_RECOVER_LENGTH_SWAP 0   // Default additional swap recover length (mm, added to retract length when recovering from extruder change)
856
+  #define RETRACT_RECOVER_FEEDRATE 8      // Default feedrate for recovering from retraction (mm/s)
857
+  #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
752 858
 #endif
753 859
 
754 860
 /**
861
+ * Extra Fan Speed
862
+ * Adds a secondary fan speed for each print-cooling fan.
863
+ *   'M106 P<fan> T3-255' : Set a secondary speed for <fan>
864
+ *   'M106 P<fan> T2'     : Use the set secondary speed
865
+ *   'M106 P<fan> T1'     : Restore the previous fan speed
866
+ */
867
+//#define EXTRA_FAN_SPEED
868
+
869
+/**
755 870
  * Advanced Pause
756 871
  * Experimental feature for filament change support and for parking the nozzle when paused.
757 872
  * Adds the GCode M600 for initiating filament change.
@@ -861,7 +976,7 @@
861 976
 
862 977
 #endif
863 978
 
864
-// @section TMC2130
979
+// @section TMC2130, TMC2208
865 980
 
866 981
 /**
867 982
  * Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
@@ -875,7 +990,19 @@
875 990
  */
876 991
 //#define HAVE_TMC2130
877 992
 
878
-#if ENABLED(HAVE_TMC2130)
993
+/**
994
+ * Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
995
+ * Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
996
+ * To use the reading capabilities, also connect #_SERIAL_RX_PIN
997
+ * to #_SERIAL_TX_PIN with a 1K resistor.
998
+ * The drivers can also be used with hardware serial.
999
+ *
1000
+ * You'll also need the TMC2208Stepper Arduino library
1001
+ * (https://github.com/teemuatlut/TMC2208Stepper).
1002
+ */
1003
+//#define HAVE_TMC2208
1004
+
1005
+#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
879 1006
 
880 1007
   // CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
881 1008
   //#define X_IS_TMC2130
@@ -890,46 +1017,58 @@
890 1017
   //#define E3_IS_TMC2130
891 1018
   //#define E4_IS_TMC2130
892 1019
 
1020
+  //#define X_IS_TMC2208
1021
+  //#define X2_IS_TMC2208
1022
+  //#define Y_IS_TMC2208
1023
+  //#define Y2_IS_TMC2208
1024
+  //#define Z_IS_TMC2208
1025
+  //#define Z2_IS_TMC2208
1026
+  //#define E0_IS_TMC2208
1027
+  //#define E1_IS_TMC2208
1028
+  //#define E2_IS_TMC2208
1029
+  //#define E3_IS_TMC2208
1030
+  //#define E4_IS_TMC2208
1031
+
893 1032
   /**
894 1033
    * Stepper driver settings
895 1034
    */
896 1035
 
897 1036
   #define R_SENSE           0.11  // R_sense resistor for SilentStepStick2130
898 1037
   #define HOLD_MULTIPLIER    0.5  // Scales down the holding current from run current
899
-  #define INTERPOLATE          1  // Interpolate X/Y/Z_MICROSTEPS to 256
1038
+  #define INTERPOLATE       true  // Interpolate X/Y/Z_MICROSTEPS to 256
900 1039
 
901
-  #define X_CURRENT         1000  // rms current in mA. Multiply by 1.41 for peak current.
1040
+  #define X_CURRENT          800  // rms current in mA. Multiply by 1.41 for peak current.
902 1041
   #define X_MICROSTEPS        16  // 0..256
903 1042
 
904
-  #define Y_CURRENT         1000
1043
+  #define Y_CURRENT          800
905 1044
   #define Y_MICROSTEPS        16
906 1045
 
907
-  #define Z_CURRENT         1000
1046
+  #define Z_CURRENT          800
908 1047
   #define Z_MICROSTEPS        16
909 1048
 
910
-  //#define X2_CURRENT      1000
911
-  //#define X2_MICROSTEPS     16
1049
+  #define X2_CURRENT         800
1050
+  #define X2_MICROSTEPS       16
912 1051
 
913
-  //#define Y2_CURRENT      1000
914
-  //#define Y2_MICROSTEPS     16
1052
+  #define Y2_CURRENT         800
1053
+  #define Y2_MICROSTEPS       16
915 1054
 
916
-  //#define Z2_CURRENT      1000
917
-  //#define Z2_MICROSTEPS     16
1055
+  #define Z2_CURRENT         800
1056
+  #define Z2_MICROSTEPS       16
918 1057
 
919
-  //#define E0_CURRENT      1000
920
-  //#define E0_MICROSTEPS     16
1058
+  #define E0_CURRENT         800
1059
+  #define E0_MICROSTEPS       16
921 1060
 
922
-  //#define E1_CURRENT      1000
923
-  //#define E1_MICROSTEPS     16
1061
+  #define E1_CURRENT         800
1062
+  #define E1_MICROSTEPS       16
924 1063
 
925
-  //#define E2_CURRENT      1000
926
-  //#define E2_MICROSTEPS     16
1064
+  #define E2_CURRENT         800
1065
+  #define E2_MICROSTEPS       16
927 1066
 
928
-  //#define E3_CURRENT      1000
929
-  //#define E3_MICROSTEPS     16
1067
+  #define E3_CURRENT         800
1068
+  #define E3_MICROSTEPS       16
930 1069
 
931
-  //#define E3_CURRENT      1000
932
-  //#define E3_MICROSTEPS     16
1070
+  #define E4_CURRENT         800
1071
+  #define E4_MICROSTEPS       16
933 1072
 
934 1073
   /**
935 1074
    * Use Trinamic's ultra quiet stepping mode.
@@ -938,24 +1077,22 @@
938 1077
   #define STEALTHCHOP
939 1078
 
940 1079
   /**
941
-   * Let Marlin automatically control stepper current.
942
-   * This is still an experimental feature.
943
-   * Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
944
-   * then decrease current by CURRENT_STEP until temperature prewarn is cleared.
945
-   * Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
1080
+   * Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
1081
+   * like overtemperature and short to ground. TMC2208 requires hardware serial.
1082
+   * In the case of overtemperature Marlin can decrease the driver current until error condition clears.
1083
+   * Other detected conditions can be used to stop the current print.
946 1084
    * Relevant g-codes:
947 1085
    * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
948
-   * M906 S1 - Start adjusting current
949
-   * M906 S0 - Stop adjusting current
950 1086
    * M911 - Report stepper driver overtemperature pre-warn condition.
951 1087
    * M912 - Clear stepper driver overtemperature pre-warn condition flag.
1088
+   * M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
952 1089
    */
953
-  //#define AUTOMATIC_CURRENT_CONTROL
1090
+  //#define MONITOR_DRIVER_STATUS
954 1091
 
955
-  #if ENABLED(AUTOMATIC_CURRENT_CONTROL)
956
-    #define CURRENT_STEP          50  // [mA]
957
-    #define AUTO_ADJUST_MAX     1300  // [mA], 1300mA_rms = 1840mA_peak
1092
+  #if ENABLED(MONITOR_DRIVER_STATUS)
1093
+    #define CURRENT_STEP_DOWN     50  // [mA]
958 1094
     #define REPORT_CURRENT_CHANGE
1095
+    #define STOP_ON_ERROR
959 1096
   #endif
960 1097
 
961 1098
   /**
@@ -970,8 +1107,8 @@
970 1107
   #define X2_HYBRID_THRESHOLD    100
971 1108
   #define Y_HYBRID_THRESHOLD     100
972 1109
   #define Y2_HYBRID_THRESHOLD    100
973
-  #define Z_HYBRID_THRESHOLD       4
974
-  #define Z2_HYBRID_THRESHOLD      4
1110
+  #define Z_HYBRID_THRESHOLD       3
1111
+  #define Z2_HYBRID_THRESHOLD      3
975 1112
   #define E0_HYBRID_THRESHOLD     30
976 1113
   #define E1_HYBRID_THRESHOLD     30
977 1114
   #define E2_HYBRID_THRESHOLD     30
@@ -981,7 +1118,7 @@
981 1118
   /**
982 1119
    * Use stallGuard2 to sense an obstacle and trigger an endstop.
983 1120
    * You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
984
-   * If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
1121
+   * X and Y homing will always be done in spreadCycle mode.
985 1122
    *
986 1123
    * X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
987 1124
    * Higher values make the system LESS sensitive.
@@ -990,27 +1127,34 @@
990 1127
    * It is advised to set X/Y_HOME_BUMP_MM to 0.
991 1128
    * M914 X/Y to live tune the setting
992 1129
    */
993
-  //#define SENSORLESS_HOMING
1130
+  //#define SENSORLESS_HOMING // TMC2130 only
994 1131
 
995 1132
   #if ENABLED(SENSORLESS_HOMING)
996
-    #define X_HOMING_SENSITIVITY  19
997
-    #define Y_HOMING_SENSITIVITY  19
1133
+    #define X_HOMING_SENSITIVITY  8
1134
+    #define Y_HOMING_SENSITIVITY  8
998 1135
   #endif
999 1136
 
1000 1137
   /**
1138
+   * Enable M122 debugging command for TMC stepper drivers.
1139
+   * M122 S0/1 will enable continous reporting.
1140
+   */
1141
+  //#define TMC_DEBUG
1142
+
1143
+  /**
1001 1144
    * You can set your own advanced settings by filling in predefined functions.
1002 1145
    * A list of available functions can be found on the library github page
1003 1146
    * https://github.com/teemuatlut/TMC2130Stepper
1147
+   * https://github.com/teemuatlut/TMC2208Stepper
1004 1148
    *
1005 1149
    * Example:
1006
-   * #define TMC2130_ADV() { \
1150
+   * #define TMC_ADV() { \
1007 1151
    *   stepperX.diag0_temp_prewarn(1); \
1008
-   *   stepperX.interpolate(0); \
1152
+   *   stepperY.interpolate(0); \
1009 1153
    * }
1010 1154
    */
1011
-  #define  TMC2130_ADV() {  }
1155
+  #define  TMC_ADV() {  }
1012 1156
 
1013
-#endif // HAVE_TMC2130
1157
+#endif // TMC2130 || TMC2208
1014 1158
 
1015 1159
 // @section L6470
1016 1160
 
@@ -1175,6 +1319,48 @@
1175 1319
 #endif
1176 1320
 
1177 1321
 /**
1322
+ * Filament Width Sensor
1323
+ *
1324
+ * Measures the filament width in real-time and adjusts
1325
+ * flow rate to compensate for any irregularities.
1326
+ *
1327
+ * Also allows the measured filament diameter to set the
1328
+ * extrusion rate, so the slicer only has to specify the
1329
+ * volume.
1330
+ *
1331
+ * Only a single extruder is supported at this time.
1332
+ *
1333
+ *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1334
+ *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1335
+ * 301 RAMBO       : Analog input 3
1336
+ *
1337
+ * Note: May require analog pins to be defined for other boards.
1338
+ */
1339
+//#define FILAMENT_WIDTH_SENSOR
1340
+
1341
+#if ENABLED(FILAMENT_WIDTH_SENSOR)
1342
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
1343
+  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1344
+
1345
+  #define MEASURED_UPPER_LIMIT         2.00 // (mm) Upper limit used to validate sensor reading
1346
+  #define MEASURED_LOWER_LIMIT         1.60 // (mm) Lower limit used to validate sensor reading
1347
+  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1348
+
1349
+  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1350
+
1351
+  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1352
+  //#define FILAMENT_LCD_DISPLAY
1353
+#endif
1354
+
1355
+/**
1356
+ * CNC Coordinate Systems
1357
+ *
1358
+ * Enables G53 and G54-G59.3 commands to select coordinate systems
1359
+ * and G92.1 to reset the workspace to native machine space.
1360
+ */
1361
+//#define CNC_COORDINATE_SYSTEMS
1362
+
1363
+/**
1178 1364
  * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
1179 1365
  */
1180 1366
 //#define PINS_DEBUGGING
@@ -1227,6 +1413,8 @@
1227 1413
 //#define CUSTOM_USER_MENUS
1228 1414
 #if ENABLED(CUSTOM_USER_MENUS)
1229 1415
   #define USER_SCRIPT_DONE "M117 User Script Done"
1416
+  #define USER_SCRIPT_AUDIBLE_FEEDBACK
1417
+  //#define USER_SCRIPT_RETURN  // Return to status screen after a script
1230 1418
 
1231 1419
   #define USER_DESC_1 "Home & UBL Info"
1232 1420
   #define USER_GCODE_1 "G28\nG29 W"
@@ -1254,6 +1442,7 @@
1254 1442
 //===========================================================================
1255 1443
 //====================== I2C Position Encoder Settings ======================
1256 1444
 //===========================================================================
1445
+
1257 1446
 /**
1258 1447
  *  I2C position encoders for closed loop control.
1259 1448
  *  Developed by Chris Barr at Aus3D.
@@ -1334,4 +1523,45 @@
1334 1523
 
1335 1524
 #endif // I2C_POSITION_ENCODERS
1336 1525
 
1526
+/**
1527
+ * MAX7219 Debug Matrix
1528
+ *
1529
+ * Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
1530
+ * display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
1531
+ *
1532
+ * Fully assembled MAX7219 boards can be found on the internet for under $2(US).
1533
+ * For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
1534
+ */
1535
+//#define MAX7219_DEBUG
1536
+#if ENABLED(MAX7219_DEBUG)
1537
+  #define MAX7219_CLK_PIN   64  // 77 on Re-ARM       // Configuration of the 3 pins to control the display
1538
+  #define MAX7219_DIN_PIN   57  // 78 on Re-ARM
1539
+  #define MAX7219_LOAD_PIN  44  // 79 on Re-ARM
1540
+
1541
+  /**
1542
+   * Sample debug features
1543
+   * If you add more debug displays, be careful to avoid conflicts!
1544
+   */
1545
+  #define MAX7219_DEBUG_PRINTER_ALIVE    // Blink corner LED of 8x8 matrix to show that the firmware is functioning
1546
+  #define MAX7219_DEBUG_STEPPER_HEAD  3  // Show the stepper queue head position on this and the next LED matrix row
1547
+  #define MAX7219_DEBUG_STEPPER_TAIL  5  // Show the stepper queue tail position on this and the next LED matrix row
1548
+
1549
+  #define MAX7219_DEBUG_STEPPER_QUEUE 0  // Show the current stepper queue depth on this and the next LED matrix row
1550
+                                         // If you experience stuttering, reboots, etc. this option can reveal how
1551
+                                         // tweaks made to the configuration are affecting the printer in real-time.
1552
+#endif
1553
+
1554
+/**
1555
+ * NanoDLP Sync support
1556
+ *
1557
+ * Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
1558
+ * string to enable synchronization with DLP projector exposure. This change will allow to use
1559
+ * [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
1560
+ */
1561
+//#define NANODLP_Z_SYNC
1562
+#if ENABLED(NANODLP_Z_SYNC)
1563
+  //#define NANODLP_ALL_AXIS  // Enables "Z_move_comp" output on any axis move.
1564
+                              // Default behaviour is limited to Z axis only.
1565
+#endif
1566
+
1337 1567
 #endif // CONFIGURATION_ADV_H

Marlin/example_configurations/Hephestos_2/README.md → Marlin/example_configurations/BQ/Hephestos_2/README.md 파일 보기

@@ -5,11 +5,18 @@ NOTE: The look and feel of the Hephestos 2 while navigating the LCD menu will ch
5 5
 
6 6
 ## Changelog
7 7
  * 2016/03/01 - Initial release
8
+
8 9
  * 2016/03/21 - Activated 4-point auto leveling by default
9 10
                 Updated miscellaneous z-probe values
11
+
10 12
  * 2016/06/21 - Disabled hot bed related options
11 13
                 Activated software endstops
12 14
                 SD printing now disables the heater when finished
15
+
13 16
  * 2016/07/13 - Update the `DEFAULT_AXIS_STEPS_PER_UNIT` for the Z axis
14 17
                 Increased the `DEFAULT_XYJERK`
18
+
15 19
  * 2016/12/13 - Configuration updated.
20
+
21
+ * 2017/07/06 - Configuration updated to the latest Marlin version.
22
+                Added support for the official BQ heated bed kit.

Marlin/example_configurations/Hephestos_2/_Bootscreen.h → Marlin/example_configurations/BQ/Hephestos_2/_Bootscreen.h 파일 보기


Marlin/example_configurations/WITBOX/Configuration.h → Marlin/example_configurations/BQ/WITBOX/Configuration.h 파일 보기

@@ -37,7 +37,7 @@
37 37
  */
38 38
 #ifndef CONFIGURATION_H
39 39
 #define CONFIGURATION_H
40
-#define CONFIGURATION_H_VERSION 010100
40
+#define CONFIGURATION_H_VERSION 010107
41 41
 
42 42
 //===========================================================================
43 43
 //============================= Getting Started =============================
@@ -107,8 +107,9 @@
107 107
  *
108 108
  * 250000 works in most cases, but you might try a lower speed if
109 109
  * you commonly experience drop-outs during host printing.
110
+ * You may try up to 1000000 to speed up SD file transfer.
110 111
  *
111
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
112
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
112 113
  */
113 114
 #define BAUDRATE 115200
114 115
 
@@ -138,6 +139,9 @@
138 139
 // :[1, 2, 3, 4, 5]
139 140
 #define EXTRUDERS 1
140 141
 
142
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
143
+#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
144
+
141 145
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
142 146
 //#define SINGLENOZZLE
143 147
 
@@ -164,7 +168,10 @@
164 168
 //#define SWITCHING_EXTRUDER
165 169
 #if ENABLED(SWITCHING_EXTRUDER)
166 170
   #define SWITCHING_EXTRUDER_SERVO_NR 0
167
-  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1
171
+  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3]
172
+  #if EXTRUDERS > 3
173
+    #define SWITCHING_EXTRUDER_E23_SERVO_NR 1
174
+  #endif
168 175
 #endif
169 176
 
170 177
 // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles
@@ -176,6 +183,21 @@
176 183
 #endif
177 184
 
178 185
 /**
186
+ * Two separate X-carriages with extruders that connect to a moving part
187
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
188
+ */
189
+//#define PARKING_EXTRUDER
190
+#if ENABLED(PARKING_EXTRUDER)
191
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
192
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
193
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
194
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
195
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
196
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
197
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
198
+#endif
199
+
200
+/**
179 201
  * "Mixing Extruder"
180 202
  *   - Adds a new code, M165, to set the current mix factors.
181 203
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -310,6 +332,7 @@
310 332
 #define HEATER_1_MAXTEMP 260
311 333
 #define HEATER_2_MAXTEMP 260
312 334
 #define HEATER_3_MAXTEMP 260
335
+#define HEATER_4_MAXTEMP 260
313 336
 #define BED_MAXTEMP 150
314 337
 
315 338
 //===========================================================================
@@ -319,8 +342,9 @@
319 342
 
320 343
 // Comment the following line to disable PID and enable bang-bang.
321 344
 #define PIDTEMP
322
-#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
323
-#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
345
+#define BANG_MAX 255     // Limits current to nozzle while in bang-bang mode; 255=full current
346
+#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
347
+#define PID_K1 0.95      // Smoothing factor within the PID
324 348
 #if ENABLED(PIDTEMP)
325 349
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
326 350
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -330,7 +354,6 @@
330 354
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
331 355
   #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
332 356
                                   // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
333
-  #define K1 0.95 //smoothing factor within the PID
334 357
 
335 358
   // Witbox
336 359
   #define  DEFAULT_Kp 22.2
@@ -399,12 +422,13 @@
399 422
 //===========================================================================
400 423
 
401 424
 /**
402
- * Thermal Protection protects your printer from damage and fire if a
403
- * thermistor falls out or temperature sensors fail in any way.
425
+ * Thermal Protection provides additional protection to your printer from damage
426
+ * and fire. Marlin always includes safe min and max temperature ranges which
427
+ * protect against a broken or disconnected thermistor wire.
404 428
  *
405
- * The issue: If a thermistor falls out or a temperature sensor fails,
406
- * Marlin can no longer sense the actual temperature. Since a disconnected
407
- * thermistor reads as a low temperature, the firmware will keep the heater on.
429
+ * The issue: If a thermistor falls out, it will report the much lower
430
+ * temperature of the air in the room, and the the firmware will keep
431
+ * the heater on.
408 432
  *
409 433
  * If you get "Thermal Runaway" or "Heating failed" errors the
410 434
  * details can be tuned in Configuration_adv.h
@@ -544,7 +568,7 @@
544 568
 // @section probes
545 569
 
546 570
 //
547
-// See http://marlinfw.org/configuration/probes.html
571
+// See http://marlinfw.org/docs/configuration/probes.html
548 572
 //
549 573
 
550 574
 /**
@@ -610,14 +634,15 @@
610 634
 #endif
611 635
 
612 636
 /**
613
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
614
- * options selected below - will be disabled during probing so as to minimize
615
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
616
- * in current flowing through the wires).  This is likely most useful to users of the
617
- * BLTouch probe, but may also help those with inductive or other probe types.
637
+ * Enable one or more of the following if probing seems unreliable.
638
+ * Heaters and/or fans can be disabled during probing to minimize electrical
639
+ * noise. A delay can also be added to allow noise and vibration to settle.
640
+ * These options are most useful for the BLTouch probe, but may also improve
641
+ * readings with inductive probes and piezo sensors.
618 642
  */
619 643
 //#define PROBING_HEATERS_OFF       // Turn heaters off when probing
620 644
 //#define PROBING_FANS_OFF          // Turn fans off when probing
645
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
621 646
 
622 647
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
623 648
 //#define SOLENOID_PROBE
@@ -656,14 +681,16 @@
656 681
 // X and Y axis travel speed (mm/m) between probes
657 682
 #define XY_PROBE_SPEED 8000
658 683
 
659
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
684
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
660 685
 #define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
661 686
 
662 687
 // Speed for the "accurate" probe of each point
663 688
 #define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
664 689
 
665
-// Use double touch for probing
666
-//#define PROBE_DOUBLE_TOUCH
690
+// The number of probes to perform at each point.
691
+//   Set to 2 for a fast/slow probe, using the second probe result.
692
+//   Set to 3 or more for slow probes, averaging the results.
693
+//#define MULTIPLE_PROBING 2
667 694
 
668 695
 /**
669 696
  * Z probes require clearance when deploying, stowing, and moving between
@@ -730,6 +757,8 @@
730 757
 
731 758
 // @section homing
732 759
 
760
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
761
+
733 762
 //#define Z_HOMING_HEIGHT 4  // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
734 763
                              // Be sure you have this distance over your Z_MAX_POS in case.
735 764
 
@@ -741,18 +770,42 @@
741 770
 
742 771
 // @section machine
743 772
 
744
-// Travel limits after homing (units are in mm)
773
+// The size of the print bed
774
+#define X_BED_SIZE 297
775
+#define Y_BED_SIZE 210
776
+
777
+// Travel limits (mm) after homing, corresponding to endstop positions.
745 778
 #define X_MIN_POS 0
746 779
 #define Y_MIN_POS 0
747 780
 #define Z_MIN_POS 0
748
-#define X_MAX_POS 297
749
-#define Y_MAX_POS 210
781
+#define X_MAX_POS X_BED_SIZE
782
+#define Y_MAX_POS Y_BED_SIZE
750 783
 #define Z_MAX_POS 200
751 784
 
752
-// If enabled, axes won't move below MIN_POS in response to movement commands.
785
+/**
786
+ * Software Endstops
787
+ *
788
+ * - Prevent moves outside the set machine bounds.
789
+ * - Individual axes can be disabled, if desired.
790
+ * - X and Y only apply to Cartesian robots.
791
+ * - Use 'M211' to set software endstops on/off or report current state
792
+ */
793
+
794
+// Min software endstops curtail movement below minimum coordinate bounds
753 795
 #define MIN_SOFTWARE_ENDSTOPS
754
-// If enabled, axes won't move above MAX_POS in response to movement commands.
796
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
797
+  #define MIN_SOFTWARE_ENDSTOP_X
798
+  #define MIN_SOFTWARE_ENDSTOP_Y
799
+  #define MIN_SOFTWARE_ENDSTOP_Z
800
+#endif
801
+
802
+// Max software endstops curtail movement above maximum coordinate bounds
755 803
 #define MAX_SOFTWARE_ENDSTOPS
804
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
805
+  #define MAX_SOFTWARE_ENDSTOP_X
806
+  #define MAX_SOFTWARE_ENDSTOP_Y
807
+  #define MAX_SOFTWARE_ENDSTOP_Z
808
+#endif
756 809
 
757 810
 /**
758 811
  * Filament Runout Sensor
@@ -772,7 +825,7 @@
772 825
 //===========================================================================
773 826
 //=============================== Bed Leveling ==============================
774 827
 //===========================================================================
775
-// @section bedlevel
828
+// @section calibrate
776 829
 
777 830
 /**
778 831
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -798,12 +851,7 @@
798 851
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
799 852
  *   A comprehensive bed leveling system combining the features and benefits
800 853
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
801
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
802
- *   for Cartesian Printers. That said, it was primarily designed to correct
803
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
804
- *   please post an issue if something doesn't work correctly. Initially,
805
- *   you will need to set a reduced bed size so you have a rectangular area
806
- *   to test on.
854
+ *   Validation and Mesh Editing systems.
807 855
  *
808 856
  * - MESH_BED_LEVELING
809 857
  *   Probe a grid manually
@@ -830,6 +878,24 @@
830 878
   // at which point movement will be level to the machine's XY plane.
831 879
   // The height can be set with M420 Z<height>
832 880
   #define ENABLE_LEVELING_FADE_HEIGHT
881
+
882
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
883
+  // split up moves into short segments like a Delta. This follows the
884
+  // contours of the bed more closely than edge-to-edge straight moves.
885
+  #define SEGMENT_LEVELED_MOVES
886
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
887
+
888
+  /**
889
+   * Enable the G26 Mesh Validation Pattern tool.
890
+   */
891
+  //#define G26_MESH_VALIDATION   // Enable G26 mesh validation
892
+  #if ENABLED(G26_MESH_VALIDATION)
893
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
894
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
895
+    #define MESH_TEST_HOTEND_TEMP   205.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
896
+    #define MESH_TEST_BED_TEMP       60.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
897
+  #endif
898
+
833 899
 #endif
834 900
 
835 901
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -885,7 +951,9 @@
885 951
   //========================= Unified Bed Leveling ============================
886 952
   //===========================================================================
887 953
 
888
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
954
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
955
+
956
+  #define MESH_INSET 1              // Mesh inset margin on print area
889 957
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
890 958
   #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
891 959
 
@@ -896,8 +964,8 @@
896 964
   #define UBL_PROBE_PT_3_X 180
897 965
   #define UBL_PROBE_PT_3_Y 20
898 966
 
899
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
900 967
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
968
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
901 969
 
902 970
 #elif ENABLED(MESH_BED_LEVELING)
903 971
 
@@ -924,6 +992,9 @@
924 992
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
925 993
 #endif
926 994
 
995
+// Add a menu item to move between bed corners for manual bed adjustment
996
+//#define LEVEL_BED_CORNERS
997
+
927 998
 /**
928 999
  * Commands to execute at the end of G29 probing.
929 1000
  * Useful to retract or move the Z probe out of the way.
@@ -954,14 +1025,71 @@
954 1025
 //#define Z_SAFE_HOMING
955 1026
 
956 1027
 #if ENABLED(Z_SAFE_HOMING)
957
-  #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
958
-  #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
1028
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1029
+  #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2)    // Y point for Z homing when homing all axes (G28).
959 1030
 #endif
960 1031
 
961 1032
 // Homing speeds (mm/m)
962 1033
 #define HOMING_FEEDRATE_XY (120*60)
963 1034
 #define HOMING_FEEDRATE_Z  432
964 1035
 
1036
+// @section calibrate
1037
+
1038
+/**
1039
+ * Bed Skew Compensation
1040
+ *
1041
+ * This feature corrects for misalignment in the XYZ axes.
1042
+ *
1043
+ * Take the following steps to get the bed skew in the XY plane:
1044
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1045
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1046
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1047
+ *  4. For XY_SIDE_AD measure the edge A to D
1048
+ *
1049
+ * Marlin automatically computes skew factors from these measurements.
1050
+ * Skew factors may also be computed and set manually:
1051
+ *
1052
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1053
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1054
+ *
1055
+ * If desired, follow the same procedure for XZ and YZ.
1056
+ * Use these diagrams for reference:
1057
+ *
1058
+ *    Y                     Z                     Z
1059
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1060
+ *    |    /       /        |    /       /        |    /       /
1061
+ *    |   /       /         |   /       /         |   /       /
1062
+ *    |  A-------D          |  A-------D          |  A-------D
1063
+ *    +-------------->X     +-------------->X     +-------------->Y
1064
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1065
+ */
1066
+//#define SKEW_CORRECTION
1067
+
1068
+#if ENABLED(SKEW_CORRECTION)
1069
+  // Input all length measurements here:
1070
+  #define XY_DIAG_AC 282.8427124746
1071
+  #define XY_DIAG_BD 282.8427124746
1072
+  #define XY_SIDE_AD 200
1073
+
1074
+  // Or, set the default skew factors directly here
1075
+  // to override the above measurements:
1076
+  #define XY_SKEW_FACTOR 0.0
1077
+
1078
+  //#define SKEW_CORRECTION_FOR_Z
1079
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1080
+    #define XZ_DIAG_AC 282.8427124746
1081
+    #define XZ_DIAG_BD 282.8427124746
1082
+    #define YZ_DIAG_AC 282.8427124746
1083
+    #define YZ_DIAG_BD 282.8427124746
1084
+    #define YZ_SIDE_AD 200
1085
+    #define XZ_SKEW_FACTOR 0.0
1086
+    #define YZ_SKEW_FACTOR 0.0
1087
+  #endif
1088
+
1089
+  // Enable this option for M852 to set skew at runtime
1090
+  //#define SKEW_CORRECTION_GCODE
1091
+#endif
1092
+
965 1093
 //=============================================================================
966 1094
 //============================= Additional Features ===========================
967 1095
 //=============================================================================
@@ -988,11 +1116,12 @@
988 1116
 //
989 1117
 #define HOST_KEEPALIVE_FEATURE        // Disable this if your host doesn't like keepalive messages
990 1118
 #define DEFAULT_KEEPALIVE_INTERVAL 2  // Number of seconds between "busy" messages. Set with M113.
1119
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
991 1120
 
992 1121
 //
993 1122
 // M100 Free Memory Watcher
994 1123
 //
995
-//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1124
+//#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
996 1125
 
997 1126
 //
998 1127
 // G20/G21 Inch mode support
@@ -1137,13 +1266,13 @@
1137 1266
  *
1138 1267
  * Select the language to display on the LCD. These languages are available:
1139 1268
  *
1140
- *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
1141
- *    it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
1142
- *    zh_CN, zh_TW, test
1269
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1270
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1271
+ *    tr, uk, zh_CN, zh_TW, test
1143 1272
  *
1144
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1273
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1145 1274
  */
1146
-//#define LCD_LANGUAGE en
1275
+#define LCD_LANGUAGE en
1147 1276
 
1148 1277
 /**
1149 1278
  * LCD Character Set
@@ -1163,7 +1292,7 @@
1163 1292
  *  - Click the controller to view the LCD menu
1164 1293
  *  - The LCD will display Japanese, Western, or Cyrillic text
1165 1294
  *
1166
- * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1295
+ * See http://marlinfw.org/docs/development/lcd_language.html
1167 1296
  *
1168 1297
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1169 1298
  */
@@ -1269,8 +1398,8 @@
1269 1398
 // Note: Test audio output with the G-Code:
1270 1399
 //  M300 S<frequency Hz> P<duration ms>
1271 1400
 //
1272
-//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
1273
-//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
1401
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
1402
+//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
1274 1403
 
1275 1404
 //
1276 1405
 // CONTROLLER TYPE: Standard
@@ -1378,11 +1507,13 @@
1378 1507
 //#define CARTESIO_UI
1379 1508
 
1380 1509
 //
1381
-// ANET_10 Controller supported displays.
1510
+// ANET and Tronxy Controller supported displays.
1382 1511
 //
1383
-//#define ANET_KEYPAD_LCD         // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1512
+//#define ZONESTAR_LCD            // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1384 1513
                                   // This LCD is known to be susceptible to electrical interference
1385 1514
                                   // which scrambles the display.  Pressing any button clears it up.
1515
+                                  // This is a LCD2004 display with 5 analog buttons.
1516
+
1386 1517
 //#define ANET_FULL_GRAPHICS_LCD  // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1387 1518
                                   // A clone of the RepRapDiscount full graphics display but with
1388 1519
                                   // different pins/wiring (see pins_ANET_10.h).
@@ -1442,11 +1573,6 @@
1442 1573
 //#define U8GLIB_SSD1306
1443 1574
 
1444 1575
 //
1445
-// TinyBoy2 128x64 OLED / Encoder Panel
1446
-//
1447
-//#define OLED_PANEL_TINYBOY2
1448
-
1449
-//
1450 1576
 // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules
1451 1577
 //
1452 1578
 //#define SAV_3DGLCD
@@ -1463,6 +1589,45 @@
1463 1589
 //
1464 1590
 //#define SAV_3DLCD
1465 1591
 
1592
+//
1593
+// TinyBoy2 128x64 OLED / Encoder Panel
1594
+//
1595
+//#define OLED_PANEL_TINYBOY2
1596
+
1597
+//
1598
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1599
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1600
+//
1601
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1602
+
1603
+//
1604
+// MKS MINI12864 with graphic controller and SD support
1605
+// http://reprap.org/wiki/MKS_MINI_12864
1606
+//
1607
+//#define MKS_MINI_12864
1608
+
1609
+//
1610
+// Factory display for Creality CR-10
1611
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1612
+//
1613
+// This is RAMPS-compatible using a single 10-pin connector.
1614
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1615
+//
1616
+//#define CR10_STOCKDISPLAY
1617
+
1618
+//
1619
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1620
+// http://reprap.org/wiki/MKS_12864OLED
1621
+//
1622
+// Tiny, but very sharp OLED display
1623
+//
1624
+//#define MKS_12864OLED
1625
+
1626
+// Silvergate GLCD controller
1627
+// http://github.com/android444/Silvergate
1628
+//
1629
+//#define SILVER_GATE_GLCD_CONTROLLER
1630
+
1466 1631
 //=============================================================================
1467 1632
 //=============================== Extra Features ==============================
1468 1633
 //=============================================================================
@@ -1519,16 +1684,22 @@
1519 1684
  * Adds the M150 command to set the LED (or LED strip) color.
1520 1685
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1521 1686
  * luminance values can be set from 0 to 255.
1687
+ * For Neopixel LED an overall brightness parameter is also available.
1522 1688
  *
1523 1689
  * *** CAUTION ***
1524 1690
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1525 1691
  *  as the Arduino cannot handle the current the LEDs will require.
1526 1692
  *  Failure to follow this precaution can destroy your Arduino!
1693
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1694
+ *  more current than the Arduino 5V linear regulator can produce.
1527 1695
  * *** CAUTION ***
1528 1696
  *
1697
+ * LED Type. Enable only one of the following two options.
1698
+ *
1529 1699
  */
1530 1700
 //#define RGB_LED
1531 1701
 //#define RGBW_LED
1702
+
1532 1703
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1533 1704
   #define RGB_LED_R_PIN 34
1534 1705
   #define RGB_LED_G_PIN 43
@@ -1536,6 +1707,17 @@
1536 1707
   #define RGB_LED_W_PIN -1
1537 1708
 #endif
1538 1709
 
1710
+// Support for Adafruit Neopixel LED driver
1711
+//#define NEOPIXEL_LED
1712
+#if ENABLED(NEOPIXEL_LED)
1713
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1714
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1715
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1716
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1717
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1718
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1719
+#endif
1720
+
1539 1721
 /**
1540 1722
  * Printer Event LEDs
1541 1723
  *
@@ -1547,68 +1729,32 @@
1547 1729
  *  - Change to green once print has finished
1548 1730
  *  - Turn off after the print has finished and the user has pushed a button
1549 1731
  */
1550
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)
1732
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1551 1733
   #define PRINTER_EVENT_LEDS
1552 1734
 #endif
1553 1735
 
1554
-/*********************************************************************\
1555
-* R/C SERVO support
1556
-* Sponsored by TrinityLabs, Reworked by codexmas
1557
-**********************************************************************/
1736
+/**
1737
+ * R/C SERVO support
1738
+ * Sponsored by TrinityLabs, Reworked by codexmas
1739
+ */
1558 1740
 
1559
-// Number of servos
1560
-//
1561
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1562
-// set it manually if you have more servos than extruders and wish to manually control some
1563
-// leaving it undefined or defining as 0 will disable the servo subsystem
1564
-// If unsure, leave commented / disabled
1565
-//
1741
+/**
1742
+ * Number of servos
1743
+ *
1744
+ * For some servo-related options NUM_SERVOS will be set automatically.
1745
+ * Set this manually if there are extra servos needing manual control.
1746
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1747
+ */
1566 1748
 //#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
1567 1749
 
1568 1750
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1569 1751
 // 300ms is a good value but you can try less delay.
1570 1752
 // If the servo can't reach the requested position, increase it.
1571
-#define SERVO_DELAY 300
1753
+#define SERVO_DELAY { 300 }
1572 1754
 
1573 1755
 // Servo deactivation
1574 1756
 //
1575 1757
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1576 1758
 //#define DEACTIVATE_SERVOS_AFTER_MOVE
1577 1759
 
1578
-/**
1579
- * Filament Width Sensor
1580
- *
1581
- * Measures the filament width in real-time and adjusts
1582
- * flow rate to compensate for any irregularities.
1583
- *
1584
- * Also allows the measured filament diameter to set the
1585
- * extrusion rate, so the slicer only has to specify the
1586
- * volume.
1587
- *
1588
- * Only a single extruder is supported at this time.
1589
- *
1590
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1591
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1592
- * 301 RAMBO       : Analog input 3
1593
- *
1594
- * Note: May require analog pins to be defined for other boards.
1595
- */
1596
-//#define FILAMENT_WIDTH_SENSOR
1597
-
1598
-#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00   // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
1599
-
1600
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1601
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1602
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1603
-
1604
-  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1605
-  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1606
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1607
-
1608
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1609
-
1610
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1611
-  //#define FILAMENT_LCD_DISPLAY
1612
-#endif
1613
-
1614 1760
 #endif // CONFIGURATION_H

Marlin/example_configurations/WITBOX/Configuration_adv.h → Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h 파일 보기

@@ -32,7 +32,7 @@
32 32
  */
33 33
 #ifndef CONFIGURATION_ADV_H
34 34
 #define CONFIGURATION_ADV_H
35
-#define CONFIGURATION_ADV_H_VERSION 010100
35
+#define CONFIGURATION_ADV_H_VERSION 010107
36 36
 
37 37
 // @section temperature
38 38
 
@@ -48,31 +48,36 @@
48 48
 #endif
49 49
 
50 50
 /**
51
- * Thermal Protection protects your printer from damage and fire if a
52
- * thermistor falls out or temperature sensors fail in any way.
51
+ * Thermal Protection provides additional protection to your printer from damage
52
+ * and fire. Marlin always includes safe min and max temperature ranges which
53
+ * protect against a broken or disconnected thermistor wire.
53 54
  *
54
- * The issue: If a thermistor falls out or a temperature sensor fails,
55
- * Marlin can no longer sense the actual temperature. Since a disconnected
56
- * thermistor reads as a low temperature, the firmware will keep the heater on.
55
+ * The issue: If a thermistor falls out, it will report the much lower
56
+ * temperature of the air in the room, and the the firmware will keep
57
+ * the heater on.
57 58
  *
58 59
  * The solution: Once the temperature reaches the target, start observing.
59
- * If the temperature stays too far below the target (hysteresis) for too long (period),
60
- * the firmware will halt the machine as a safety precaution.
60
+ * If the temperature stays too far below the target (hysteresis) for too
61
+ * long (period), the firmware will halt the machine as a safety precaution.
61 62
  *
62
- * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63
+ * If you get false positives for "Thermal Runaway", increase
64
+ * THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63 65
  */
64 66
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
65 67
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
66 68
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
67 69
 
68 70
   /**
69
-   * Whenever an M104 or M109 increases the target temperature the firmware will wait for the
70
-   * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
71
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
72
-   * but only if the current temperature is far enough below the target for a reliable test.
71
+   * Whenever an M104, M109, or M303 increases the target temperature, the
72
+   * firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
73
+   * hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
74
+   * requires a hard reset. This test restarts with any M104/M109/M303, but only
75
+   * if the current temperature is far enough below the target for a reliable
76
+   * test.
73 77
    *
74
-   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
75
-   * WATCH_TEMP_INCREASE should not be below 2.
78
+   * If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
79
+   * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
80
+   * below 2.
76 81
    */
77 82
   #define WATCH_TEMP_PERIOD 20                // Seconds
78 83
   #define WATCH_TEMP_INCREASE 2               // Degrees Celsius
@@ -86,13 +91,7 @@
86 91
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
87 92
 
88 93
   /**
89
-   * Whenever an M140 or M190 increases the target temperature the firmware will wait for the
90
-   * WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
91
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
92
-   * but only if the current temperature is far enough below the target for a reliable test.
93
-   *
94
-   * If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
95
-   * WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
94
+   * As described above, except for the bed (M140/M190/M303).
96 95
    */
97 96
   #define WATCH_BED_TEMP_PERIOD 60                // Seconds
98 97
   #define WATCH_BED_TEMP_INCREASE 2               // Degrees Celsius
@@ -123,6 +122,9 @@
123 122
   #define AUTOTEMP_OLDWEIGHT 0.98
124 123
 #endif
125 124
 
125
+// Show extra position information in M114
126
+//#define M114_DETAIL
127
+
126 128
 // Show Temperature ADC value
127 129
 // Enable for M105 to include ADC values read from temperature sensors.
128 130
 //#define SHOW_TEMP_ADC_VALUES
@@ -221,6 +223,17 @@
221 223
 #define EXTRUDER_AUTO_FAN_SPEED   255  // == full speed
222 224
 
223 225
 /**
226
+ * Part-Cooling Fan Multiplexer
227
+ *
228
+ * This feature allows you to digitally multiplex the fan output.
229
+ * The multiplexer is automatically switched at tool-change.
230
+ * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans.
231
+ */
232
+#define FANMUX0_PIN -1
233
+#define FANMUX1_PIN -1
234
+#define FANMUX2_PIN -1
235
+
236
+/**
224 237
  * M355 Case Light on-off / brightness
225 238
  */
226 239
 //#define CASE_LIGHT_ENABLE
@@ -246,48 +259,49 @@
246 259
 
247 260
 //#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
248 261
 
249
-// Dual X Steppers
250
-// Uncomment this option to drive two X axis motors.
251
-// The next unused E driver will be assigned to the second X stepper.
262
+/**
263
+ * Dual Steppers / Dual Endstops
264
+ *
265
+ * This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
266
+ *
267
+ * For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
268
+ * spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
269
+ * set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
270
+ * that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
271
+ *
272
+ * Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
273
+ * this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
274
+ * in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
275
+ */
276
+
252 277
 //#define X_DUAL_STEPPER_DRIVERS
253 278
 #if ENABLED(X_DUAL_STEPPER_DRIVERS)
254
-  // Set true if the two X motors need to rotate in opposite directions
255
-  #define INVERT_X2_VS_X_DIR true
279
+  #define INVERT_X2_VS_X_DIR true   // Set 'true' if X motors should rotate in opposite directions
280
+  //#define X_DUAL_ENDSTOPS
281
+  #if ENABLED(X_DUAL_ENDSTOPS)
282
+    #define X2_USE_ENDSTOP _XMAX_
283
+    #define X_DUAL_ENDSTOPS_ADJUSTMENT  0
284
+  #endif
256 285
 #endif
257 286
 
258
-// Dual Y Steppers
259
-// Uncomment this option to drive two Y axis motors.
260
-// The next unused E driver will be assigned to the second Y stepper.
261 287
 //#define Y_DUAL_STEPPER_DRIVERS
262 288
 #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
263
-  // Set true if the two Y motors need to rotate in opposite directions
264
-  #define INVERT_Y2_VS_Y_DIR true
289
+  #define INVERT_Y2_VS_Y_DIR true   // Set 'true' if Y motors should rotate in opposite directions
290
+  //#define Y_DUAL_ENDSTOPS
291
+  #if ENABLED(Y_DUAL_ENDSTOPS)
292
+    #define Y2_USE_ENDSTOP _YMAX_
293
+    #define Y_DUAL_ENDSTOPS_ADJUSTMENT  0
294
+  #endif
265 295
 #endif
266 296
 
267
-// A single Z stepper driver is usually used to drive 2 stepper motors.
268
-// Uncomment this option to use a separate stepper driver for each Z axis motor.
269
-// The next unused E driver will be assigned to the second Z stepper.
270 297
 //#define Z_DUAL_STEPPER_DRIVERS
271
-
272 298
 #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
273
-
274
-  // Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper.
275
-  // That way the machine is capable to align the bed during home, since both Z steppers are homed.
276
-  // There is also an implementation of M666 (software endstops adjustment) to this feature.
277
-  // After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
278
-  // One just need to home the Z axis and measure the distance difference between both Z axis and apply the math: Z adjust = Z - Z2.
279
-  // If the Z stepper axis is closer to the bed, the measure Z > Z2 (yes, it is.. think about it) and the Z adjust would be positive.
280
-  // Play a little bit with small adjustments (0.5mm) and check the behaviour.
281
-  // The M119 (endstops report) will start reporting the Z2 Endstop as well.
282
-
283 299
   //#define Z_DUAL_ENDSTOPS
284
-
285 300
   #if ENABLED(Z_DUAL_ENDSTOPS)
286 301
     #define Z2_USE_ENDSTOP _XMAX_
287
-    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0  // use M666 command to determine this value
302
+    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0
288 303
   #endif
289
-
290
-#endif // Z_DUAL_STEPPER_DRIVERS
304
+#endif
291 305
 
292 306
 // Enable this for dual x-carriage printers.
293 307
 // A dual x-carriage design has the advantage that the inactive extruder can be parked which
@@ -334,12 +348,12 @@
334 348
 
335 349
 // @section homing
336 350
 
337
-//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
351
+// Homing hits each endstop, retracts by these distances, then does a slower bump.
338 352
 #define X_HOME_BUMP_MM 5
339 353
 #define Y_HOME_BUMP_MM 5
340 354
 #define Z_HOME_BUMP_MM 2
341
-#define HOMING_BUMP_DIVISOR {2, 2, 4}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
342
-//#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
355
+#define HOMING_BUMP_DIVISOR { 2, 2, 4 }  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
356
+//#define QUICK_HOME                     // If homing includes X and Y, do a diagonal move initially
343 357
 
344 358
 // When G28 is called, this option will make Y home before X
345 359
 //#define HOME_Y_BEFORE_X
@@ -394,7 +408,7 @@
394 408
 // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
395 409
 // of the buffer and all stops. This should not be much greater than zero and should only be changed
396 410
 // if unwanted behavior is observed on a user's machine when running at very slow speeds.
397
-#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
411
+#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
398 412
 
399 413
 // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
400 414
 #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
@@ -423,8 +437,21 @@
423 437
 //#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 }   // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
424 438
 //#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 }    // Default drive percent - X, Y, Z, E axis
425 439
 
426
-// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
440
+// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
427 441
 //#define DIGIPOT_I2C
442
+#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
443
+  /**
444
+   * Common slave addresses:
445
+   *
446
+   *                    A   (A shifted)   B   (B shifted)  IC
447
+   * Smoothie          0x2C (0x58)       0x2D (0x5A)       MCP4451
448
+   * AZTEEG_X3_PRO     0x2C (0x58)       0x2E (0x5C)       MCP4451
449
+   * MIGHTYBOARD_REVE  0x2F (0x5E)                         MCP4018
450
+   */
451
+  #define DIGIPOT_I2C_ADDRESS_A 0x2C  // unshifted slave address for first DIGIPOT
452
+  #define DIGIPOT_I2C_ADDRESS_B 0x2D  // unshifted slave address for second DIGIPOT
453
+#endif
454
+
428 455
 //#define DIGIPOT_MCP4018          // Requires library from https://github.com/stawel/SlowSoftI2CMaster
429 456
 #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4     AZTEEG_X3_PRO: 8
430 457
 // Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
@@ -452,6 +479,26 @@
452 479
 // On the Info Screen, display XY with one decimal place when possible
453 480
 //#define LCD_DECIMAL_SMALL_XY
454 481
 
482
+// The timeout (in ms) to return to the status screen from sub-menus
483
+//#define LCD_TIMEOUT_TO_STATUS 15000
484
+
485
+/**
486
+ * LED Control Menu
487
+ * Enable this feature to add LED Control to the LCD menu
488
+ */
489
+//#define LED_CONTROL_MENU
490
+#if ENABLED(LED_CONTROL_MENU)
491
+  #define LED_COLOR_PRESETS                 // Enable the Preset Color menu option
492
+  #if ENABLED(LED_COLOR_PRESETS)
493
+    #define LED_USER_PRESET_RED        255  // User defined RED value
494
+    #define LED_USER_PRESET_GREEN      128  // User defined GREEN value
495
+    #define LED_USER_PRESET_BLUE         0  // User defined BLUE value
496
+    #define LED_USER_PRESET_WHITE      255  // User defined WHITE value
497
+    #define LED_USER_PRESET_BRIGHTNESS 255  // User defined intensity
498
+    //#define LED_USER_PRESET_STARTUP       // Have the printer display the user preset color on startup
499
+  #endif
500
+#endif // LED_CONTROL_MENU
501
+
455 502
 #if ENABLED(SDSUPPORT)
456 503
 
457 504
   // Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -461,12 +508,14 @@
461 508
   // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
462 509
   #define SD_DETECT_INVERTED
463 510
 
464
-  #define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
511
+  #define SD_FINISHED_STEPPERRELEASE true          // Disable steppers when SD Print is finished
465 512
   #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
466 513
 
467
-  #define SDCARD_RATHERRECENTFIRST  //reverse file order of sd card menu display. Its sorted practically after the file system block order.
468
-  // if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that.
469
-  // using:
514
+  // Reverse SD sort to show "more recent" files first, according to the card's FAT.
515
+  // Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
516
+  #define SDCARD_RATHERRECENTFIRST
517
+
518
+  // Add an option in the menu to run all auto#.g files
470 519
   //#define MENU_ADDAUTOSTART
471 520
 
472 521
   /**
@@ -496,13 +545,15 @@
496 545
 
497 546
   // SD Card Sorting options
498 547
   #if ENABLED(SDCARD_SORT_ALPHA)
499
-    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256).
548
+    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256). Costs 27 bytes each.
500 549
     #define FOLDER_SORTING     -1     // -1=above  0=none  1=below
501 550
     #define SDSORT_GCODE       false  // Allow turning sorting on/off with LCD and M34 g-code.
502 551
     #define SDSORT_USES_RAM    false  // Pre-allocate a static array for faster pre-sorting.
503 552
     #define SDSORT_USES_STACK  false  // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
504 553
     #define SDSORT_CACHE_NAMES false  // Keep sorted items in RAM longer for speedy performance. Most expensive option.
505 554
     #define SDSORT_DYNAMIC_RAM false  // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
555
+    #define SDSORT_CACHE_VFATS 2      // Maximum number of 13-byte VFAT entries to use for sorting.
556
+                                      // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
506 557
   #endif
507 558
 
508 559
   // Show a progress bar on HD44780 LCDs for SD printing
@@ -521,14 +572,29 @@
521 572
     //#define LCD_PROGRESS_BAR_TEST
522 573
   #endif
523 574
 
575
+  // Add an 'M73' G-code to set the current percentage
576
+  //#define LCD_SET_PROGRESS_MANUALLY
577
+
524 578
   // This allows hosts to request long names for files and folders with M33
525 579
   //#define LONG_FILENAME_HOST_SUPPORT
526 580
 
527
-  // This option allows you to abort SD printing when any endstop is triggered.
528
-  // This feature must be enabled with "M540 S1" or from the LCD menu.
529
-  // To have any effect, endstops must be enabled during SD printing.
581
+  // Enable this option to scroll long filenames in the SD card menu
582
+  //#define SCROLL_LONG_FILENAMES
583
+
584
+  /**
585
+   * This option allows you to abort SD printing when any endstop is triggered.
586
+   * This feature must be enabled with "M540 S1" or from the LCD menu.
587
+   * To have any effect, endstops must be enabled during SD printing.
588
+   */
530 589
   //#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
531 590
 
591
+  /**
592
+   * This option makes it easier to print the same SD Card file again.
593
+   * On print completion the LCD Menu will open with the file selected.
594
+   * You can just click to start the print, or navigate elsewhere.
595
+   */
596
+  //#define SD_REPRINT_LAST_SELECTED_FILE
597
+
532 598
 #endif // SDSUPPORT
533 599
 
534 600
 /**
@@ -561,6 +627,10 @@
561 627
   // Enable this option and reduce the value to optimize screen updates.
562 628
   // The normal delay is 10µs. Use the lowest value that still gives a reliable display.
563 629
   //#define DOGM_SPI_DELAY_US 5
630
+
631
+  // Swap the CW/CCW indicators in the graphics overlay
632
+  //#define OVERLAY_GFX_REVERSE
633
+
564 634
 #endif // DOGLCD
565 635
 
566 636
 // @section safety
@@ -587,31 +657,18 @@
587 657
  */
588 658
 //#define BABYSTEPPING
589 659
 #if ENABLED(BABYSTEPPING)
590
-  #define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
591
-  #define BABYSTEP_INVERT_Z false  // Change if Z babysteps should go the other way
592
-  #define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
593
-  //#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
660
+  //#define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
661
+  #define BABYSTEP_INVERT_Z false    // Change if Z babysteps should go the other way
662
+  #define BABYSTEP_MULTIPLICATOR 1   // Babysteps are very small. Increase for faster motion.
663
+  //#define BABYSTEP_ZPROBE_OFFSET   // Enable to combine M851 and Babystepping
594 664
   //#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
595 665
   #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
596 666
                                         // Note: Extra time may be added to mitigate controller latency.
667
+  //#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
597 668
 #endif
598 669
 
599 670
 // @section extruder
600 671
 
601
-// extruder advance constant (s2/mm3)
602
-//
603
-// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
604
-//
605
-// Hooke's law says:    force = k * distance
606
-// Bernoulli's principle says:  v ^ 2 / 2 + g . h + pressure / density = constant
607
-// so: v ^ 2 is proportional to number of steps we advance the extruder
608
-//#define ADVANCE
609
-
610
-#if ENABLED(ADVANCE)
611
-  #define EXTRUDER_ADVANCE_K .0
612
-  #define D_FILAMENT 1.75
613
-#endif
614
-
615 672
 /**
616 673
  * Implementation of linear pressure control
617 674
  *
@@ -645,7 +702,7 @@
645 702
    *
646 703
    * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
647 704
    *
648
-   * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode.
705
+   * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
649 706
    * Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
650 707
    */
651 708
   #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
@@ -654,19 +711,18 @@
654 711
 
655 712
 // @section leveling
656 713
 
657
-// Default mesh area is an area with an inset margin on the print area.
658
-// Below are the macros that are used to define the borders for the mesh area,
659
-// made available here for specialized needs, ie dual extruder setup.
660
-#if ENABLED(MESH_BED_LEVELING)
661
-  #define MESH_MIN_X (X_MIN_POS + MESH_INSET)
662
-  #define MESH_MAX_X (X_MAX_POS - (MESH_INSET))
663
-  #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET)
664
-  #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET))
665
-#elif ENABLED(AUTO_BED_LEVELING_UBL)
666
-  #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET)
667
-  #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET))
668
-  #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET)
669
-  #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET))
714
+#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
715
+  #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
716
+#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
717
+  #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
718
+#endif
719
+
720
+#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
721
+  // Override the mesh area if the automatic (max) area is too large
722
+  //#define MESH_MIN_X MESH_INSET
723
+  //#define MESH_MIN_Y MESH_INSET
724
+  //#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
725
+  //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
670 726
 #endif
671 727
 
672 728
 // @section extras
@@ -686,7 +742,7 @@
686 742
 //#define BEZIER_CURVE_SUPPORT
687 743
 
688 744
 // G38.2 and G38.3 Probe Target
689
-// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
745
+// Set MULTIPLE_PROBING if you want G38 to double touch
690 746
 //#define G38_PROBE_TARGET
691 747
 #if ENABLED(G38_PROBE_TARGET)
692 748
   #define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
@@ -711,7 +767,7 @@
711 767
 // @section hidden
712 768
 
713 769
 // The number of linear motions that can be in the plan at any give time.
714
-// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
770
+// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
715 771
 #if ENABLED(SDSUPPORT)
716 772
   #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
717 773
 #else
@@ -724,7 +780,7 @@
724 780
 #define MAX_CMD_SIZE 96
725 781
 #define BUFSIZE 4
726 782
 
727
-// Transfer Buffer Size
783
+// Transmission to Host Buffer Size
728 784
 // To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0.
729 785
 // To buffer a simple "ok" you need 4 bytes.
730 786
 // For ADVANCED_OK (M105) you need 32 bytes.
@@ -733,6 +789,28 @@
733 789
 // :[0, 2, 4, 8, 16, 32, 64, 128, 256]
734 790
 #define TX_BUFFER_SIZE 0
735 791
 
792
+// Host Receive Buffer Size
793
+// Without XON/XOFF flow control (see SERIAL_XON_XOFF below) 32 bytes should be enough.
794
+// To use flow control, set this buffer size to at least 1024 bytes.
795
+// :[0, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048]
796
+//#define RX_BUFFER_SIZE 1024
797
+
798
+#if RX_BUFFER_SIZE >= 1024
799
+  // Enable to have the controller send XON/XOFF control characters to
800
+  // the host to signal the RX buffer is becoming full.
801
+  //#define SERIAL_XON_XOFF
802
+#endif
803
+
804
+#if ENABLED(SDSUPPORT)
805
+  // Enable this option to collect and display the maximum
806
+  // RX queue usage after transferring a file to SD.
807
+  //#define SERIAL_STATS_MAX_RX_QUEUED
808
+
809
+  // Enable this option to collect and display the number
810
+  // of dropped bytes after a file transfer to SD.
811
+  //#define SERIAL_STATS_DROPPED_RX
812
+#endif
813
+
736 814
 // Enable an emergency-command parser to intercept certain commands as they
737 815
 // enter the serial receive buffer, so they cannot be blocked.
738 816
 // Currently handles M108, M112, M410
@@ -748,27 +826,47 @@
748 826
 // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary.
749 827
 //#define ADVANCED_OK
750 828
 
751
-// @section fwretract
752
-
753
-// Firmware based and LCD controlled retract
754
-// M207 and M208 can be used to define parameters for the retraction.
755
-// The retraction can be called by the slicer using G10 and G11
756
-// until then, intended retractions can be detected by moves that only extrude and the direction.
757
-// the moves are than replaced by the firmware controlled ones.
829
+// @section extras
758 830
 
759
-//#define FWRETRACT  //ONLY PARTIALLY TESTED
831
+/**
832
+ * Firmware-based and LCD-controlled retract
833
+ *
834
+ * Add G10 / G11 commands for automatic firmware-based retract / recover.
835
+ * Use M207 and M208 to define parameters for retract / recover.
836
+ *
837
+ * Use M209 to enable or disable auto-retract.
838
+ * With auto-retract enabled, all G1 E moves within the set range
839
+ * will be converted to firmware-based retract/recover moves.
840
+ *
841
+ * Be sure to turn off auto-retract during filament change.
842
+ *
843
+ * Note that M207 / M208 / M209 settings are saved to EEPROM.
844
+ *
845
+ */
846
+//#define FWRETRACT  // ONLY PARTIALLY TESTED
760 847
 #if ENABLED(FWRETRACT)
761
-  #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
762
-  #define RETRACT_LENGTH 3               //default retract length (positive mm)
763
-  #define RETRACT_LENGTH_SWAP 13         //default swap retract length (positive mm), for extruder change
764
-  #define RETRACT_FEEDRATE 80            //default feedrate for retracting (mm/s)
765
-  #define RETRACT_ZLIFT 0                //default retract Z-lift
766
-  #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
767
-  //#define RETRACT_RECOVER_LENGTH_SWAP 0  //default additional swap recover length (mm, added to retract length when recovering from extruder change)
768
-  #define RETRACT_RECOVER_FEEDRATE 8     //default feedrate for recovering from retraction (mm/s)
848
+  #define MIN_AUTORETRACT 0.1             // When auto-retract is on, convert E moves of this length and over
849
+  #define MAX_AUTORETRACT 10.0            // Upper limit for auto-retract conversion
850
+  #define RETRACT_LENGTH 3                // Default retract length (positive mm)
851
+  #define RETRACT_LENGTH_SWAP 13          // Default swap retract length (positive mm), for extruder change
852
+  #define RETRACT_FEEDRATE 45             // Default feedrate for retracting (mm/s)
853
+  #define RETRACT_ZLIFT 0                 // Default retract Z-lift
854
+  #define RETRACT_RECOVER_LENGTH 0        // Default additional recover length (mm, added to retract length when recovering)
855
+  #define RETRACT_RECOVER_LENGTH_SWAP 0   // Default additional swap recover length (mm, added to retract length when recovering from extruder change)
856
+  #define RETRACT_RECOVER_FEEDRATE 8      // Default feedrate for recovering from retraction (mm/s)
857
+  #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
769 858
 #endif
770 859
 
771 860
 /**
861
+ * Extra Fan Speed
862
+ * Adds a secondary fan speed for each print-cooling fan.
863
+ *   'M106 P<fan> T3-255' : Set a secondary speed for <fan>
864
+ *   'M106 P<fan> T2'     : Use the set secondary speed
865
+ *   'M106 P<fan> T1'     : Restore the previous fan speed
866
+ */
867
+//#define EXTRA_FAN_SPEED
868
+
869
+/**
772 870
  * Advanced Pause
773 871
  * Experimental feature for filament change support and for parking the nozzle when paused.
774 872
  * Adds the GCode M600 for initiating filament change.
@@ -878,7 +976,7 @@
878 976
 
879 977
 #endif
880 978
 
881
-// @section TMC2130
979
+// @section TMC2130, TMC2208
882 980
 
883 981
 /**
884 982
  * Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
@@ -892,7 +990,19 @@
892 990
  */
893 991
 //#define HAVE_TMC2130
894 992
 
895
-#if ENABLED(HAVE_TMC2130)
993
+/**
994
+ * Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
995
+ * Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
996
+ * To use the reading capabilities, also connect #_SERIAL_RX_PIN
997
+ * to #_SERIAL_TX_PIN with a 1K resistor.
998
+ * The drivers can also be used with hardware serial.
999
+ *
1000
+ * You'll also need the TMC2208Stepper Arduino library
1001
+ * (https://github.com/teemuatlut/TMC2208Stepper).
1002
+ */
1003
+//#define HAVE_TMC2208
1004
+
1005
+#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
896 1006
 
897 1007
   // CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
898 1008
   //#define X_IS_TMC2130
@@ -907,46 +1017,58 @@
907 1017
   //#define E3_IS_TMC2130
908 1018
   //#define E4_IS_TMC2130
909 1019
 
1020
+  //#define X_IS_TMC2208
1021
+  //#define X2_IS_TMC2208
1022
+  //#define Y_IS_TMC2208
1023
+  //#define Y2_IS_TMC2208
1024
+  //#define Z_IS_TMC2208
1025
+  //#define Z2_IS_TMC2208
1026
+  //#define E0_IS_TMC2208
1027
+  //#define E1_IS_TMC2208
1028
+  //#define E2_IS_TMC2208
1029
+  //#define E3_IS_TMC2208
1030
+  //#define E4_IS_TMC2208
1031
+
910 1032
   /**
911 1033
    * Stepper driver settings
912 1034
    */
913 1035
 
914 1036
   #define R_SENSE           0.11  // R_sense resistor for SilentStepStick2130
915 1037
   #define HOLD_MULTIPLIER    0.5  // Scales down the holding current from run current
916
-  #define INTERPOLATE          1  // Interpolate X/Y/Z_MICROSTEPS to 256
1038
+  #define INTERPOLATE       true  // Interpolate X/Y/Z_MICROSTEPS to 256
917 1039
 
918
-  #define X_CURRENT         1000  // rms current in mA. Multiply by 1.41 for peak current.
1040
+  #define X_CURRENT          800  // rms current in mA. Multiply by 1.41 for peak current.
919 1041
   #define X_MICROSTEPS        16  // 0..256
920 1042
 
921
-  #define Y_CURRENT         1000
1043
+  #define Y_CURRENT          800
922 1044
   #define Y_MICROSTEPS        16
923 1045
 
924
-  #define Z_CURRENT         1000
1046
+  #define Z_CURRENT          800
925 1047
   #define Z_MICROSTEPS        16
926 1048
 
927
-  //#define X2_CURRENT      1000
928
-  //#define X2_MICROSTEPS     16
1049
+  #define X2_CURRENT         800
1050
+  #define X2_MICROSTEPS       16
929 1051
 
930
-  //#define Y2_CURRENT      1000
931
-  //#define Y2_MICROSTEPS     16
1052
+  #define Y2_CURRENT         800
1053
+  #define Y2_MICROSTEPS       16
932 1054
 
933
-  //#define Z2_CURRENT      1000
934
-  //#define Z2_MICROSTEPS     16
1055
+  #define Z2_CURRENT         800
1056
+  #define Z2_MICROSTEPS       16
935 1057
 
936
-  //#define E0_CURRENT      1000
937
-  //#define E0_MICROSTEPS     16
1058
+  #define E0_CURRENT         800
1059
+  #define E0_MICROSTEPS       16
938 1060
 
939
-  //#define E1_CURRENT      1000
940
-  //#define E1_MICROSTEPS     16
1061
+  #define E1_CURRENT         800
1062
+  #define E1_MICROSTEPS       16
941 1063
 
942
-  //#define E2_CURRENT      1000
943
-  //#define E2_MICROSTEPS     16
1064
+  #define E2_CURRENT         800
1065
+  #define E2_MICROSTEPS       16
944 1066
 
945
-  //#define E3_CURRENT      1000
946
-  //#define E3_MICROSTEPS     16
1067
+  #define E3_CURRENT         800
1068
+  #define E3_MICROSTEPS       16
947 1069
 
948
-  //#define E4_CURRENT      1000
949
-  //#define E4_MICROSTEPS     16
1070
+  #define E4_CURRENT         800
1071
+  #define E4_MICROSTEPS       16
950 1072
 
951 1073
   /**
952 1074
    * Use Trinamic's ultra quiet stepping mode.
@@ -955,24 +1077,22 @@
955 1077
   #define STEALTHCHOP
956 1078
 
957 1079
   /**
958
-   * Let Marlin automatically control stepper current.
959
-   * This is still an experimental feature.
960
-   * Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
961
-   * then decrease current by CURRENT_STEP until temperature prewarn is cleared.
962
-   * Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
1080
+   * Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
1081
+   * like overtemperature and short to ground. TMC2208 requires hardware serial.
1082
+   * In the case of overtemperature Marlin can decrease the driver current until error condition clears.
1083
+   * Other detected conditions can be used to stop the current print.
963 1084
    * Relevant g-codes:
964 1085
    * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
965
-   * M906 S1 - Start adjusting current
966
-   * M906 S0 - Stop adjusting current
967 1086
    * M911 - Report stepper driver overtemperature pre-warn condition.
968 1087
    * M912 - Clear stepper driver overtemperature pre-warn condition flag.
1088
+   * M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
969 1089
    */
970
-  //#define AUTOMATIC_CURRENT_CONTROL
1090
+  //#define MONITOR_DRIVER_STATUS
971 1091
 
972
-  #if ENABLED(AUTOMATIC_CURRENT_CONTROL)
973
-    #define CURRENT_STEP          50  // [mA]
974
-    #define AUTO_ADJUST_MAX     1300  // [mA], 1300mA_rms = 1840mA_peak
1092
+  #if ENABLED(MONITOR_DRIVER_STATUS)
1093
+    #define CURRENT_STEP_DOWN     50  // [mA]
975 1094
     #define REPORT_CURRENT_CHANGE
1095
+    #define STOP_ON_ERROR
976 1096
   #endif
977 1097
 
978 1098
   /**
@@ -987,8 +1107,8 @@
987 1107
   #define X2_HYBRID_THRESHOLD    100
988 1108
   #define Y_HYBRID_THRESHOLD     100
989 1109
   #define Y2_HYBRID_THRESHOLD    100
990
-  #define Z_HYBRID_THRESHOLD       4
991
-  #define Z2_HYBRID_THRESHOLD      4
1110
+  #define Z_HYBRID_THRESHOLD       3
1111
+  #define Z2_HYBRID_THRESHOLD      3
992 1112
   #define E0_HYBRID_THRESHOLD     30
993 1113
   #define E1_HYBRID_THRESHOLD     30
994 1114
   #define E2_HYBRID_THRESHOLD     30
@@ -998,7 +1118,7 @@
998 1118
   /**
999 1119
    * Use stallGuard2 to sense an obstacle and trigger an endstop.
1000 1120
    * You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
1001
-   * If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
1121
+   * X and Y homing will always be done in spreadCycle mode.
1002 1122
    *
1003 1123
    * X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
1004 1124
    * Higher values make the system LESS sensitive.
@@ -1007,27 +1127,34 @@
1007 1127
    * It is advised to set X/Y_HOME_BUMP_MM to 0.
1008 1128
    * M914 X/Y to live tune the setting
1009 1129
    */
1010
-  //#define SENSORLESS_HOMING
1130
+  //#define SENSORLESS_HOMING // TMC2130 only
1011 1131
 
1012 1132
   #if ENABLED(SENSORLESS_HOMING)
1013
-    #define X_HOMING_SENSITIVITY  19
1014
-    #define Y_HOMING_SENSITIVITY  19
1133
+    #define X_HOMING_SENSITIVITY  8
1134
+    #define Y_HOMING_SENSITIVITY  8
1015 1135
   #endif
1016 1136
 
1017 1137
   /**
1138
+   * Enable M122 debugging command for TMC stepper drivers.
1139
+   * M122 S0/1 will enable continous reporting.
1140
+   */
1141
+  //#define TMC_DEBUG
1142
+
1143
+  /**
1018 1144
    * You can set your own advanced settings by filling in predefined functions.
1019 1145
    * A list of available functions can be found on the library github page
1020 1146
    * https://github.com/teemuatlut/TMC2130Stepper
1147
+   * https://github.com/teemuatlut/TMC2208Stepper
1021 1148
    *
1022 1149
    * Example:
1023
-   * #define TMC2130_ADV() { \
1150
+   * #define TMC_ADV() { \
1024 1151
    *   stepperX.diag0_temp_prewarn(1); \
1025
-   *   stepperX.interpolate(0); \
1152
+   *   stepperY.interpolate(0); \
1026 1153
    * }
1027 1154
    */
1028
-  #define  TMC2130_ADV() {  }
1155
+  #define  TMC_ADV() {  }
1029 1156
 
1030
-#endif // HAVE_TMC2130
1157
+#endif // TMC2130 || TMC2208
1031 1158
 
1032 1159
 // @section L6470
1033 1160
 
@@ -1192,6 +1319,48 @@
1192 1319
 #endif
1193 1320
 
1194 1321
 /**
1322
+ * Filament Width Sensor
1323
+ *
1324
+ * Measures the filament width in real-time and adjusts
1325
+ * flow rate to compensate for any irregularities.
1326
+ *
1327
+ * Also allows the measured filament diameter to set the
1328
+ * extrusion rate, so the slicer only has to specify the
1329
+ * volume.
1330
+ *
1331
+ * Only a single extruder is supported at this time.
1332
+ *
1333
+ *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1334
+ *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1335
+ * 301 RAMBO       : Analog input 3
1336
+ *
1337
+ * Note: May require analog pins to be defined for other boards.
1338
+ */
1339
+//#define FILAMENT_WIDTH_SENSOR
1340
+
1341
+#if ENABLED(FILAMENT_WIDTH_SENSOR)
1342
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
1343
+  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1344
+
1345
+  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1346
+  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1347
+  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1348
+
1349
+  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1350
+
1351
+  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1352
+  //#define FILAMENT_LCD_DISPLAY
1353
+#endif
1354
+
1355
+/**
1356
+ * CNC Coordinate Systems
1357
+ *
1358
+ * Enables G53 and G54-G59.3 commands to select coordinate systems
1359
+ * and G92.1 to reset the workspace to native machine space.
1360
+ */
1361
+//#define CNC_COORDINATE_SYSTEMS
1362
+
1363
+/**
1195 1364
  * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
1196 1365
  */
1197 1366
 //#define PINS_DEBUGGING
@@ -1244,6 +1413,8 @@
1244 1413
 //#define CUSTOM_USER_MENUS
1245 1414
 #if ENABLED(CUSTOM_USER_MENUS)
1246 1415
   #define USER_SCRIPT_DONE "M117 User Script Done"
1416
+  #define USER_SCRIPT_AUDIBLE_FEEDBACK
1417
+  //#define USER_SCRIPT_RETURN  // Return to status screen after a script
1247 1418
 
1248 1419
   #define USER_DESC_1 "Home & UBL Info"
1249 1420
   #define USER_GCODE_1 "G28\nG29 W"
@@ -1271,6 +1442,7 @@
1271 1442
 //===========================================================================
1272 1443
 //====================== I2C Position Encoder Settings ======================
1273 1444
 //===========================================================================
1445
+
1274 1446
 /**
1275 1447
  *  I2C position encoders for closed loop control.
1276 1448
  *  Developed by Chris Barr at Aus3D.
@@ -1351,4 +1523,45 @@
1351 1523
 
1352 1524
 #endif // I2C_POSITION_ENCODERS
1353 1525
 
1526
+/**
1527
+ * MAX7219 Debug Matrix
1528
+ *
1529
+ * Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
1530
+ * display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
1531
+ *
1532
+ * Fully assembled MAX7219 boards can be found on the internet for under $2(US).
1533
+ * For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
1534
+ */
1535
+//#define MAX7219_DEBUG
1536
+#if ENABLED(MAX7219_DEBUG)
1537
+  #define MAX7219_CLK_PIN   64  // 77 on Re-ARM       // Configuration of the 3 pins to control the display
1538
+  #define MAX7219_DIN_PIN   57  // 78 on Re-ARM
1539
+  #define MAX7219_LOAD_PIN  44  // 79 on Re-ARM
1540
+
1541
+  /**
1542
+   * Sample debug features
1543
+   * If you add more debug displays, be careful to avoid conflicts!
1544
+   */
1545
+  #define MAX7219_DEBUG_PRINTER_ALIVE    // Blink corner LED of 8x8 matrix to show that the firmware is functioning
1546
+  #define MAX7219_DEBUG_STEPPER_HEAD  3  // Show the stepper queue head position on this and the next LED matrix row
1547
+  #define MAX7219_DEBUG_STEPPER_TAIL  5  // Show the stepper queue tail position on this and the next LED matrix row
1548
+
1549
+  #define MAX7219_DEBUG_STEPPER_QUEUE 0  // Show the current stepper queue depth on this and the next LED matrix row
1550
+                                         // If you experience stuttering, reboots, etc. this option can reveal how
1551
+                                         // tweaks made to the configuration are affecting the printer in real-time.
1552
+#endif
1553
+
1554
+/**
1555
+ * NanoDLP Sync support
1556
+ *
1557
+ * Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
1558
+ * string to enable synchronization with DLP projector exposure. This change will allow to use
1559
+ * [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
1560
+ */
1561
+//#define NANODLP_Z_SYNC
1562
+#if ENABLED(NANODLP_Z_SYNC)
1563
+  //#define NANODLP_ALL_AXIS  // Enables "Z_move_comp" output on any axis move.
1564
+                              // Default behaviour is limited to Z axis only.
1565
+#endif
1566
+
1354 1567
 #endif // CONFIGURATION_ADV_H

+ 244
- 98
Marlin/example_configurations/Cartesio/Configuration.h 파일 보기

@@ -37,7 +37,7 @@
37 37
  */
38 38
 #ifndef CONFIGURATION_H
39 39
 #define CONFIGURATION_H
40
-#define CONFIGURATION_H_VERSION 010100
40
+#define CONFIGURATION_H_VERSION 010107
41 41
 
42 42
 //===========================================================================
43 43
 //============================= Getting Started =============================
@@ -107,8 +107,9 @@
107 107
  *
108 108
  * 250000 works in most cases, but you might try a lower speed if
109 109
  * you commonly experience drop-outs during host printing.
110
+ * You may try up to 1000000 to speed up SD file transfer.
110 111
  *
111
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
112
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
112 113
  */
113 114
 #define BAUDRATE 115200
114 115
 
@@ -136,6 +137,9 @@
136 137
 // :[1, 2, 3, 4, 5]
137 138
 #define EXTRUDERS 3
138 139
 
140
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
141
+#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
142
+
139 143
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
140 144
 //#define SINGLENOZZLE
141 145
 
@@ -162,7 +166,10 @@
162 166
 //#define SWITCHING_EXTRUDER
163 167
 #if ENABLED(SWITCHING_EXTRUDER)
164 168
   #define SWITCHING_EXTRUDER_SERVO_NR 0
165
-  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1
169
+  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3]
170
+  #if EXTRUDERS > 3
171
+    #define SWITCHING_EXTRUDER_E23_SERVO_NR 1
172
+  #endif
166 173
 #endif
167 174
 
168 175
 // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles
@@ -174,6 +181,21 @@
174 181
 #endif
175 182
 
176 183
 /**
184
+ * Two separate X-carriages with extruders that connect to a moving part
185
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
186
+ */
187
+//#define PARKING_EXTRUDER
188
+#if ENABLED(PARKING_EXTRUDER)
189
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
190
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
191
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
192
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
193
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
194
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
195
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
196
+#endif
197
+
198
+/**
177 199
  * "Mixing Extruder"
178 200
  *   - Adds a new code, M165, to set the current mix factors.
179 201
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -308,6 +330,7 @@
308 330
 #define HEATER_1_MAXTEMP 415
309 331
 #define HEATER_2_MAXTEMP 415
310 332
 #define HEATER_3_MAXTEMP 415
333
+#define HEATER_4_MAXTEMP 415
311 334
 #define BED_MAXTEMP 165
312 335
 
313 336
 //===========================================================================
@@ -317,8 +340,9 @@
317 340
 
318 341
 // Comment the following line to disable PID and enable bang-bang.
319 342
 #define PIDTEMP
320
-#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
321
-#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
343
+#define BANG_MAX 255     // Limits current to nozzle while in bang-bang mode; 255=full current
344
+#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
345
+#define PID_K1 0.95      // Smoothing factor within the PID
322 346
 #if ENABLED(PIDTEMP)
323 347
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
324 348
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -328,7 +352,6 @@
328 352
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
329 353
   #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
330 354
                                   // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
331
-  #define K1 0.95 //smoothing factor within the PID
332 355
 
333 356
   // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
334 357
 
@@ -407,12 +430,13 @@
407 430
 //===========================================================================
408 431
 
409 432
 /**
410
- * Thermal Protection protects your printer from damage and fire if a
411
- * thermistor falls out or temperature sensors fail in any way.
433
+ * Thermal Protection provides additional protection to your printer from damage
434
+ * and fire. Marlin always includes safe min and max temperature ranges which
435
+ * protect against a broken or disconnected thermistor wire.
412 436
  *
413
- * The issue: If a thermistor falls out or a temperature sensor fails,
414
- * Marlin can no longer sense the actual temperature. Since a disconnected
415
- * thermistor reads as a low temperature, the firmware will keep the heater on.
437
+ * The issue: If a thermistor falls out, it will report the much lower
438
+ * temperature of the air in the room, and the the firmware will keep
439
+ * the heater on.
416 440
  *
417 441
  * If you get "Thermal Runaway" or "Heating failed" errors the
418 442
  * details can be tuned in Configuration_adv.h
@@ -552,7 +576,7 @@
552 576
 // @section probes
553 577
 
554 578
 //
555
-// See http://marlinfw.org/configuration/probes.html
579
+// See http://marlinfw.org/docs/configuration/probes.html
556 580
 //
557 581
 
558 582
 /**
@@ -618,14 +642,15 @@
618 642
 #endif
619 643
 
620 644
 /**
621
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
622
- * options selected below - will be disabled during probing so as to minimize
623
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
624
- * in current flowing through the wires).  This is likely most useful to users of the
625
- * BLTouch probe, but may also help those with inductive or other probe types.
645
+ * Enable one or more of the following if probing seems unreliable.
646
+ * Heaters and/or fans can be disabled during probing to minimize electrical
647
+ * noise. A delay can also be added to allow noise and vibration to settle.
648
+ * These options are most useful for the BLTouch probe, but may also improve
649
+ * readings with inductive probes and piezo sensors.
626 650
  */
627 651
 //#define PROBING_HEATERS_OFF       // Turn heaters off when probing
628 652
 //#define PROBING_FANS_OFF          // Turn fans off when probing
653
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
629 654
 
630 655
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
631 656
 //#define SOLENOID_PROBE
@@ -664,14 +689,16 @@
664 689
 // X and Y axis travel speed (mm/m) between probes
665 690
 #define XY_PROBE_SPEED 8000
666 691
 
667
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
692
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
668 693
 #define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
669 694
 
670 695
 // Speed for the "accurate" probe of each point
671 696
 #define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
672 697
 
673
-// Use double touch for probing
674
-//#define PROBE_DOUBLE_TOUCH
698
+// The number of probes to perform at each point.
699
+//   Set to 2 for a fast/slow probe, using the second probe result.
700
+//   Set to 3 or more for slow probes, averaging the results.
701
+//#define MULTIPLE_PROBING 2
675 702
 
676 703
 /**
677 704
  * Z probes require clearance when deploying, stowing, and moving between
@@ -738,6 +765,8 @@
738 765
 
739 766
 // @section homing
740 767
 
768
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
769
+
741 770
 //#define Z_HOMING_HEIGHT 4  // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
742 771
                              // Be sure you have this distance over your Z_MAX_POS in case.
743 772
 
@@ -749,18 +778,42 @@
749 778
 
750 779
 // @section machine
751 780
 
752
-// Travel limits after homing (units are in mm)
781
+// The size of the print bed
782
+#define X_BED_SIZE 435
783
+#define Y_BED_SIZE 270
784
+
785
+// Travel limits (mm) after homing, corresponding to endstop positions.
753 786
 #define X_MIN_POS 0
754 787
 #define Y_MIN_POS 0
755 788
 #define Z_MIN_POS 0
756
-#define X_MAX_POS 435
757
-#define Y_MAX_POS 270
789
+#define X_MAX_POS X_BED_SIZE
790
+#define Y_MAX_POS Y_BED_SIZE
758 791
 #define Z_MAX_POS 400
759 792
 
760
-// If enabled, axes won't move below MIN_POS in response to movement commands.
793
+/**
794
+ * Software Endstops
795
+ *
796
+ * - Prevent moves outside the set machine bounds.
797
+ * - Individual axes can be disabled, if desired.
798
+ * - X and Y only apply to Cartesian robots.
799
+ * - Use 'M211' to set software endstops on/off or report current state
800
+ */
801
+
802
+// Min software endstops curtail movement below minimum coordinate bounds
761 803
 #define MIN_SOFTWARE_ENDSTOPS
762
-// If enabled, axes won't move above MAX_POS in response to movement commands.
804
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
805
+  #define MIN_SOFTWARE_ENDSTOP_X
806
+  #define MIN_SOFTWARE_ENDSTOP_Y
807
+  #define MIN_SOFTWARE_ENDSTOP_Z
808
+#endif
809
+
810
+// Max software endstops curtail movement above maximum coordinate bounds
763 811
 #define MAX_SOFTWARE_ENDSTOPS
812
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
813
+  #define MAX_SOFTWARE_ENDSTOP_X
814
+  #define MAX_SOFTWARE_ENDSTOP_Y
815
+  #define MAX_SOFTWARE_ENDSTOP_Z
816
+#endif
764 817
 
765 818
 /**
766 819
  * Filament Runout Sensor
@@ -780,7 +833,7 @@
780 833
 //===========================================================================
781 834
 //=============================== Bed Leveling ==============================
782 835
 //===========================================================================
783
-// @section bedlevel
836
+// @section calibrate
784 837
 
785 838
 /**
786 839
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -806,12 +859,7 @@
806 859
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
807 860
  *   A comprehensive bed leveling system combining the features and benefits
808 861
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
809
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
810
- *   for Cartesian Printers. That said, it was primarily designed to correct
811
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
812
- *   please post an issue if something doesn't work correctly. Initially,
813
- *   you will need to set a reduced bed size so you have a rectangular area
814
- *   to test on.
862
+ *   Validation and Mesh Editing systems.
815 863
  *
816 864
  * - MESH_BED_LEVELING
817 865
  *   Probe a grid manually
@@ -838,6 +886,24 @@
838 886
   // at which point movement will be level to the machine's XY plane.
839 887
   // The height can be set with M420 Z<height>
840 888
   #define ENABLE_LEVELING_FADE_HEIGHT
889
+
890
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
891
+  // split up moves into short segments like a Delta. This follows the
892
+  // contours of the bed more closely than edge-to-edge straight moves.
893
+  #define SEGMENT_LEVELED_MOVES
894
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
895
+
896
+  /**
897
+   * Enable the G26 Mesh Validation Pattern tool.
898
+   */
899
+  //#define G26_MESH_VALIDATION   // Enable G26 mesh validation
900
+  #if ENABLED(G26_MESH_VALIDATION)
901
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
902
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
903
+    #define MESH_TEST_HOTEND_TEMP   205.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
904
+    #define MESH_TEST_BED_TEMP       60.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
905
+  #endif
906
+
841 907
 #endif
842 908
 
843 909
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -893,7 +959,9 @@
893 959
   //========================= Unified Bed Leveling ============================
894 960
   //===========================================================================
895 961
 
896
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
962
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
963
+
964
+  #define MESH_INSET 1              // Mesh inset margin on print area
897 965
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
898 966
   #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
899 967
 
@@ -904,8 +972,8 @@
904 972
   #define UBL_PROBE_PT_3_X 180
905 973
   #define UBL_PROBE_PT_3_Y 20
906 974
 
907
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
908 975
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
976
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
909 977
 
910 978
 #elif ENABLED(MESH_BED_LEVELING)
911 979
 
@@ -932,6 +1000,9 @@
932 1000
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
933 1001
 #endif
934 1002
 
1003
+// Add a menu item to move between bed corners for manual bed adjustment
1004
+//#define LEVEL_BED_CORNERS
1005
+
935 1006
 /**
936 1007
  * Commands to execute at the end of G29 probing.
937 1008
  * Useful to retract or move the Z probe out of the way.
@@ -962,14 +1033,71 @@
962 1033
 //#define Z_SAFE_HOMING
963 1034
 
964 1035
 #if ENABLED(Z_SAFE_HOMING)
965
-  #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
966
-  #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
1036
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1037
+  #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2)    // Y point for Z homing when homing all axes (G28).
967 1038
 #endif
968 1039
 
969 1040
 // Homing speeds (mm/m)
970 1041
 #define HOMING_FEEDRATE_XY (50*60)
971 1042
 #define HOMING_FEEDRATE_Z  (10*60)
972 1043
 
1044
+// @section calibrate
1045
+
1046
+/**
1047
+ * Bed Skew Compensation
1048
+ *
1049
+ * This feature corrects for misalignment in the XYZ axes.
1050
+ *
1051
+ * Take the following steps to get the bed skew in the XY plane:
1052
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1053
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1054
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1055
+ *  4. For XY_SIDE_AD measure the edge A to D
1056
+ *
1057
+ * Marlin automatically computes skew factors from these measurements.
1058
+ * Skew factors may also be computed and set manually:
1059
+ *
1060
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1061
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1062
+ *
1063
+ * If desired, follow the same procedure for XZ and YZ.
1064
+ * Use these diagrams for reference:
1065
+ *
1066
+ *    Y                     Z                     Z
1067
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1068
+ *    |    /       /        |    /       /        |    /       /
1069
+ *    |   /       /         |   /       /         |   /       /
1070
+ *    |  A-------D          |  A-------D          |  A-------D
1071
+ *    +-------------->X     +-------------->X     +-------------->Y
1072
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1073
+ */
1074
+//#define SKEW_CORRECTION
1075
+
1076
+#if ENABLED(SKEW_CORRECTION)
1077
+  // Input all length measurements here:
1078
+  #define XY_DIAG_AC 282.8427124746
1079
+  #define XY_DIAG_BD 282.8427124746
1080
+  #define XY_SIDE_AD 200
1081
+
1082
+  // Or, set the default skew factors directly here
1083
+  // to override the above measurements:
1084
+  #define XY_SKEW_FACTOR 0.0
1085
+
1086
+  //#define SKEW_CORRECTION_FOR_Z
1087
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1088
+    #define XZ_DIAG_AC 282.8427124746
1089
+    #define XZ_DIAG_BD 282.8427124746
1090
+    #define YZ_DIAG_AC 282.8427124746
1091
+    #define YZ_DIAG_BD 282.8427124746
1092
+    #define YZ_SIDE_AD 200
1093
+    #define XZ_SKEW_FACTOR 0.0
1094
+    #define YZ_SKEW_FACTOR 0.0
1095
+  #endif
1096
+
1097
+  // Enable this option for M852 to set skew at runtime
1098
+  //#define SKEW_CORRECTION_GCODE
1099
+#endif
1100
+
973 1101
 //=============================================================================
974 1102
 //============================= Additional Features ===========================
975 1103
 //=============================================================================
@@ -996,11 +1124,12 @@
996 1124
 //
997 1125
 #define HOST_KEEPALIVE_FEATURE        // Disable this if your host doesn't like keepalive messages
998 1126
 #define DEFAULT_KEEPALIVE_INTERVAL 2  // Number of seconds between "busy" messages. Set with M113.
1127
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
999 1128
 
1000 1129
 //
1001 1130
 // M100 Free Memory Watcher
1002 1131
 //
1003
-//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1132
+//#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
1004 1133
 
1005 1134
 //
1006 1135
 // G20/G21 Inch mode support
@@ -1145,11 +1274,11 @@
1145 1274
  *
1146 1275
  * Select the language to display on the LCD. These languages are available:
1147 1276
  *
1148
- *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
1149
- *    it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
1150
- *    zh_CN, zh_TW, test
1277
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1278
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1279
+ *    tr, uk, zh_CN, zh_TW, test
1151 1280
  *
1152
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1281
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1153 1282
  */
1154 1283
 #define LCD_LANGUAGE en
1155 1284
 
@@ -1171,7 +1300,7 @@
1171 1300
  *  - Click the controller to view the LCD menu
1172 1301
  *  - The LCD will display Japanese, Western, or Cyrillic text
1173 1302
  *
1174
- * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1303
+ * See http://marlinfw.org/docs/development/lcd_language.html
1175 1304
  *
1176 1305
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1177 1306
  */
@@ -1386,11 +1515,13 @@
1386 1515
 #define CARTESIO_UI
1387 1516
 
1388 1517
 //
1389
-// ANET_10 Controller supported displays.
1518
+// ANET and Tronxy Controller supported displays.
1390 1519
 //
1391
-//#define ANET_KEYPAD_LCD         // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1520
+//#define ZONESTAR_LCD            // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1392 1521
                                   // This LCD is known to be susceptible to electrical interference
1393 1522
                                   // which scrambles the display.  Pressing any button clears it up.
1523
+                                  // This is a LCD2004 display with 5 analog buttons.
1524
+
1394 1525
 //#define ANET_FULL_GRAPHICS_LCD  // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1395 1526
                                   // A clone of the RepRapDiscount full graphics display but with
1396 1527
                                   // different pins/wiring (see pins_ANET_10.h).
@@ -1450,11 +1581,6 @@
1450 1581
 //#define U8GLIB_SSD1306
1451 1582
 
1452 1583
 //
1453
-// TinyBoy2 128x64 OLED / Encoder Panel
1454
-//
1455
-//#define OLED_PANEL_TINYBOY2
1456
-
1457
-//
1458 1584
 // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules
1459 1585
 //
1460 1586
 //#define SAV_3DGLCD
@@ -1471,6 +1597,45 @@
1471 1597
 //
1472 1598
 //#define SAV_3DLCD
1473 1599
 
1600
+//
1601
+// TinyBoy2 128x64 OLED / Encoder Panel
1602
+//
1603
+//#define OLED_PANEL_TINYBOY2
1604
+
1605
+//
1606
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1607
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1608
+//
1609
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1610
+
1611
+//
1612
+// MKS MINI12864 with graphic controller and SD support
1613
+// http://reprap.org/wiki/MKS_MINI_12864
1614
+//
1615
+//#define MKS_MINI_12864
1616
+
1617
+//
1618
+// Factory display for Creality CR-10
1619
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1620
+//
1621
+// This is RAMPS-compatible using a single 10-pin connector.
1622
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1623
+//
1624
+//#define CR10_STOCKDISPLAY
1625
+
1626
+//
1627
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1628
+// http://reprap.org/wiki/MKS_12864OLED
1629
+//
1630
+// Tiny, but very sharp OLED display
1631
+//
1632
+//#define MKS_12864OLED
1633
+
1634
+// Silvergate GLCD controller
1635
+// http://github.com/android444/Silvergate
1636
+//
1637
+//#define SILVER_GATE_GLCD_CONTROLLER
1638
+
1474 1639
 //=============================================================================
1475 1640
 //=============================== Extra Features ==============================
1476 1641
 //=============================================================================
@@ -1527,16 +1692,22 @@
1527 1692
  * Adds the M150 command to set the LED (or LED strip) color.
1528 1693
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1529 1694
  * luminance values can be set from 0 to 255.
1695
+ * For Neopixel LED an overall brightness parameter is also available.
1530 1696
  *
1531 1697
  * *** CAUTION ***
1532 1698
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1533 1699
  *  as the Arduino cannot handle the current the LEDs will require.
1534 1700
  *  Failure to follow this precaution can destroy your Arduino!
1701
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1702
+ *  more current than the Arduino 5V linear regulator can produce.
1535 1703
  * *** CAUTION ***
1536 1704
  *
1705
+ * LED Type. Enable only one of the following two options.
1706
+ *
1537 1707
  */
1538 1708
 //#define RGB_LED
1539 1709
 //#define RGBW_LED
1710
+
1540 1711
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1541 1712
   #define RGB_LED_R_PIN 34
1542 1713
   #define RGB_LED_G_PIN 43
@@ -1544,6 +1715,17 @@
1544 1715
   #define RGB_LED_W_PIN -1
1545 1716
 #endif
1546 1717
 
1718
+// Support for Adafruit Neopixel LED driver
1719
+//#define NEOPIXEL_LED
1720
+#if ENABLED(NEOPIXEL_LED)
1721
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1722
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1723
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1724
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1725
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1726
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1727
+#endif
1728
+
1547 1729
 /**
1548 1730
  * Printer Event LEDs
1549 1731
  *
@@ -1555,68 +1737,32 @@
1555 1737
  *  - Change to green once print has finished
1556 1738
  *  - Turn off after the print has finished and the user has pushed a button
1557 1739
  */
1558
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)
1740
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1559 1741
   #define PRINTER_EVENT_LEDS
1560 1742
 #endif
1561 1743
 
1562
-/*********************************************************************\
1563
-* R/C SERVO support
1564
-* Sponsored by TrinityLabs, Reworked by codexmas
1565
-**********************************************************************/
1744
+/**
1745
+ * R/C SERVO support
1746
+ * Sponsored by TrinityLabs, Reworked by codexmas
1747
+ */
1566 1748
 
1567
-// Number of servos
1568
-//
1569
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1570
-// set it manually if you have more servos than extruders and wish to manually control some
1571
-// leaving it undefined or defining as 0 will disable the servo subsystem
1572
-// If unsure, leave commented / disabled
1573
-//
1749
+/**
1750
+ * Number of servos
1751
+ *
1752
+ * For some servo-related options NUM_SERVOS will be set automatically.
1753
+ * Set this manually if there are extra servos needing manual control.
1754
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1755
+ */
1574 1756
 //#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
1575 1757
 
1576 1758
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1577 1759
 // 300ms is a good value but you can try less delay.
1578 1760
 // If the servo can't reach the requested position, increase it.
1579
-#define SERVO_DELAY 300
1761
+#define SERVO_DELAY { 300 }
1580 1762
 
1581 1763
 // Servo deactivation
1582 1764
 //
1583 1765
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1584 1766
 //#define DEACTIVATE_SERVOS_AFTER_MOVE
1585 1767
 
1586
-/**
1587
- * Filament Width Sensor
1588
- *
1589
- * Measures the filament width in real-time and adjusts
1590
- * flow rate to compensate for any irregularities.
1591
- *
1592
- * Also allows the measured filament diameter to set the
1593
- * extrusion rate, so the slicer only has to specify the
1594
- * volume.
1595
- *
1596
- * Only a single extruder is supported at this time.
1597
- *
1598
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1599
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1600
- * 301 RAMBO       : Analog input 3
1601
- *
1602
- * Note: May require analog pins to be defined for other boards.
1603
- */
1604
-//#define FILAMENT_WIDTH_SENSOR
1605
-
1606
-#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00   // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
1607
-
1608
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1609
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1610
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1611
-
1612
-  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1613
-  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1614
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1615
-
1616
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1617
-
1618
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1619
-  //#define FILAMENT_LCD_DISPLAY
1620
-#endif
1621
-
1622 1768
 #endif // CONFIGURATION_H

+ 370
- 157
Marlin/example_configurations/Cartesio/Configuration_adv.h 파일 보기

@@ -32,7 +32,7 @@
32 32
  */
33 33
 #ifndef CONFIGURATION_ADV_H
34 34
 #define CONFIGURATION_ADV_H
35
-#define CONFIGURATION_ADV_H_VERSION 010100
35
+#define CONFIGURATION_ADV_H_VERSION 010107
36 36
 
37 37
 // @section temperature
38 38
 
@@ -48,31 +48,36 @@
48 48
 #endif
49 49
 
50 50
 /**
51
- * Thermal Protection protects your printer from damage and fire if a
52
- * thermistor falls out or temperature sensors fail in any way.
51
+ * Thermal Protection provides additional protection to your printer from damage
52
+ * and fire. Marlin always includes safe min and max temperature ranges which
53
+ * protect against a broken or disconnected thermistor wire.
53 54
  *
54
- * The issue: If a thermistor falls out or a temperature sensor fails,
55
- * Marlin can no longer sense the actual temperature. Since a disconnected
56
- * thermistor reads as a low temperature, the firmware will keep the heater on.
55
+ * The issue: If a thermistor falls out, it will report the much lower
56
+ * temperature of the air in the room, and the the firmware will keep
57
+ * the heater on.
57 58
  *
58 59
  * The solution: Once the temperature reaches the target, start observing.
59
- * If the temperature stays too far below the target (hysteresis) for too long (period),
60
- * the firmware will halt the machine as a safety precaution.
60
+ * If the temperature stays too far below the target (hysteresis) for too
61
+ * long (period), the firmware will halt the machine as a safety precaution.
61 62
  *
62
- * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63
+ * If you get false positives for "Thermal Runaway", increase
64
+ * THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63 65
  */
64 66
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
65 67
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
66 68
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
67 69
 
68 70
   /**
69
-   * Whenever an M104 or M109 increases the target temperature the firmware will wait for the
70
-   * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
71
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
72
-   * but only if the current temperature is far enough below the target for a reliable test.
71
+   * Whenever an M104, M109, or M303 increases the target temperature, the
72
+   * firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
73
+   * hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
74
+   * requires a hard reset. This test restarts with any M104/M109/M303, but only
75
+   * if the current temperature is far enough below the target for a reliable
76
+   * test.
73 77
    *
74
-   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
75
-   * WATCH_TEMP_INCREASE should not be below 2.
78
+   * If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
79
+   * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
80
+   * below 2.
76 81
    */
77 82
   #define WATCH_TEMP_PERIOD 20                // Seconds
78 83
   #define WATCH_TEMP_INCREASE 2               // Degrees Celsius
@@ -86,13 +91,7 @@
86 91
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
87 92
 
88 93
   /**
89
-   * Whenever an M140 or M190 increases the target temperature the firmware will wait for the
90
-   * WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
91
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
92
-   * but only if the current temperature is far enough below the target for a reliable test.
93
-   *
94
-   * If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
95
-   * WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
94
+   * As described above, except for the bed (M140/M190/M303).
96 95
    */
97 96
   #define WATCH_BED_TEMP_PERIOD 60                // Seconds
98 97
   #define WATCH_BED_TEMP_INCREASE 2               // Degrees Celsius
@@ -123,6 +122,9 @@
123 122
   #define AUTOTEMP_OLDWEIGHT 0.98
124 123
 #endif
125 124
 
125
+// Show extra position information in M114
126
+//#define M114_DETAIL
127
+
126 128
 // Show Temperature ADC value
127 129
 // Enable for M105 to include ADC values read from temperature sensors.
128 130
 //#define SHOW_TEMP_ADC_VALUES
@@ -221,6 +223,17 @@
221 223
 #define EXTRUDER_AUTO_FAN_SPEED   255  // == full speed
222 224
 
223 225
 /**
226
+ * Part-Cooling Fan Multiplexer
227
+ *
228
+ * This feature allows you to digitally multiplex the fan output.
229
+ * The multiplexer is automatically switched at tool-change.
230
+ * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans.
231
+ */
232
+#define FANMUX0_PIN -1
233
+#define FANMUX1_PIN -1
234
+#define FANMUX2_PIN -1
235
+
236
+/**
224 237
  * M355 Case Light on-off / brightness
225 238
  */
226 239
 //#define CASE_LIGHT_ENABLE
@@ -246,48 +259,49 @@
246 259
 
247 260
 //#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
248 261
 
249
-// Dual X Steppers
250
-// Uncomment this option to drive two X axis motors.
251
-// The next unused E driver will be assigned to the second X stepper.
262
+/**
263
+ * Dual Steppers / Dual Endstops
264
+ *
265
+ * This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
266
+ *
267
+ * For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
268
+ * spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
269
+ * set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
270
+ * that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
271
+ *
272
+ * Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
273
+ * this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
274
+ * in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
275
+ */
276
+
252 277
 //#define X_DUAL_STEPPER_DRIVERS
253 278
 #if ENABLED(X_DUAL_STEPPER_DRIVERS)
254
-  // Set true if the two X motors need to rotate in opposite directions
255
-  #define INVERT_X2_VS_X_DIR true
279
+  #define INVERT_X2_VS_X_DIR true   // Set 'true' if X motors should rotate in opposite directions
280
+  //#define X_DUAL_ENDSTOPS
281
+  #if ENABLED(X_DUAL_ENDSTOPS)
282
+    #define X2_USE_ENDSTOP _XMAX_
283
+    #define X_DUAL_ENDSTOPS_ADJUSTMENT  0
284
+  #endif
256 285
 #endif
257 286
 
258
-// Dual Y Steppers
259
-// Uncomment this option to drive two Y axis motors.
260
-// The next unused E driver will be assigned to the second Y stepper.
261 287
 //#define Y_DUAL_STEPPER_DRIVERS
262 288
 #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
263
-  // Set true if the two Y motors need to rotate in opposite directions
264
-  #define INVERT_Y2_VS_Y_DIR true
289
+  #define INVERT_Y2_VS_Y_DIR true   // Set 'true' if Y motors should rotate in opposite directions
290
+  //#define Y_DUAL_ENDSTOPS
291
+  #if ENABLED(Y_DUAL_ENDSTOPS)
292
+    #define Y2_USE_ENDSTOP _YMAX_
293
+    #define Y_DUAL_ENDSTOPS_ADJUSTMENT  0
294
+  #endif
265 295
 #endif
266 296
 
267
-// A single Z stepper driver is usually used to drive 2 stepper motors.
268
-// Uncomment this option to use a separate stepper driver for each Z axis motor.
269
-// The next unused E driver will be assigned to the second Z stepper.
270 297
 //#define Z_DUAL_STEPPER_DRIVERS
271
-
272 298
 #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
273
-
274
-  // Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper.
275
-  // That way the machine is capable to align the bed during home, since both Z steppers are homed.
276
-  // There is also an implementation of M666 (software endstops adjustment) to this feature.
277
-  // After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
278
-  // One just need to home the Z axis and measure the distance difference between both Z axis and apply the math: Z adjust = Z - Z2.
279
-  // If the Z stepper axis is closer to the bed, the measure Z > Z2 (yes, it is.. think about it) and the Z adjust would be positive.
280
-  // Play a little bit with small adjustments (0.5mm) and check the behaviour.
281
-  // The M119 (endstops report) will start reporting the Z2 Endstop as well.
282
-
283 299
   //#define Z_DUAL_ENDSTOPS
284
-
285 300
   #if ENABLED(Z_DUAL_ENDSTOPS)
286 301
     #define Z2_USE_ENDSTOP _XMAX_
287
-    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0  // use M666 command to determine this value
302
+    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0
288 303
   #endif
289
-
290
-#endif // Z_DUAL_STEPPER_DRIVERS
304
+#endif
291 305
 
292 306
 // Enable this for dual x-carriage printers.
293 307
 // A dual x-carriage design has the advantage that the inactive extruder can be parked which
@@ -334,12 +348,12 @@
334 348
 
335 349
 // @section homing
336 350
 
337
-//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
351
+// Homing hits each endstop, retracts by these distances, then does a slower bump.
338 352
 #define X_HOME_BUMP_MM 5
339 353
 #define Y_HOME_BUMP_MM 5
340 354
 #define Z_HOME_BUMP_MM 2
341
-#define HOMING_BUMP_DIVISOR {2, 2, 4}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
342
-//#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
355
+#define HOMING_BUMP_DIVISOR { 2, 2, 4 }  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
356
+//#define QUICK_HOME                     // If homing includes X and Y, do a diagonal move initially
343 357
 
344 358
 // When G28 is called, this option will make Y home before X
345 359
 #define HOME_Y_BEFORE_X
@@ -394,7 +408,7 @@
394 408
 // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
395 409
 // of the buffer and all stops. This should not be much greater than zero and should only be changed
396 410
 // if unwanted behavior is observed on a user's machine when running at very slow speeds.
397
-#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
411
+#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
398 412
 
399 413
 // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
400 414
 #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
@@ -423,8 +437,21 @@
423 437
 //#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 }   // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
424 438
 //#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 }    // Default drive percent - X, Y, Z, E axis
425 439
 
426
-// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
440
+// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
427 441
 //#define DIGIPOT_I2C
442
+#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
443
+  /**
444
+   * Common slave addresses:
445
+   *
446
+   *                    A   (A shifted)   B   (B shifted)  IC
447
+   * Smoothie          0x2C (0x58)       0x2D (0x5A)       MCP4451
448
+   * AZTEEG_X3_PRO     0x2C (0x58)       0x2E (0x5C)       MCP4451
449
+   * MIGHTYBOARD_REVE  0x2F (0x5E)                         MCP4018
450
+   */
451
+  #define DIGIPOT_I2C_ADDRESS_A 0x2C  // unshifted slave address for first DIGIPOT
452
+  #define DIGIPOT_I2C_ADDRESS_B 0x2D  // unshifted slave address for second DIGIPOT
453
+#endif
454
+
428 455
 //#define DIGIPOT_MCP4018          // Requires library from https://github.com/stawel/SlowSoftI2CMaster
429 456
 #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4     AZTEEG_X3_PRO: 8
430 457
 // Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
@@ -452,6 +479,26 @@
452 479
 // On the Info Screen, display XY with one decimal place when possible
453 480
 //#define LCD_DECIMAL_SMALL_XY
454 481
 
482
+// The timeout (in ms) to return to the status screen from sub-menus
483
+//#define LCD_TIMEOUT_TO_STATUS 15000
484
+
485
+/**
486
+ * LED Control Menu
487
+ * Enable this feature to add LED Control to the LCD menu
488
+ */
489
+//#define LED_CONTROL_MENU
490
+#if ENABLED(LED_CONTROL_MENU)
491
+  #define LED_COLOR_PRESETS                 // Enable the Preset Color menu option
492
+  #if ENABLED(LED_COLOR_PRESETS)
493
+    #define LED_USER_PRESET_RED        255  // User defined RED value
494
+    #define LED_USER_PRESET_GREEN      128  // User defined GREEN value
495
+    #define LED_USER_PRESET_BLUE         0  // User defined BLUE value
496
+    #define LED_USER_PRESET_WHITE      255  // User defined WHITE value
497
+    #define LED_USER_PRESET_BRIGHTNESS 255  // User defined intensity
498
+    //#define LED_USER_PRESET_STARTUP       // Have the printer display the user preset color on startup
499
+  #endif
500
+#endif // LED_CONTROL_MENU
501
+
455 502
 #if ENABLED(SDSUPPORT)
456 503
 
457 504
   // Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -461,12 +508,14 @@
461 508
   // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
462 509
   #define SD_DETECT_INVERTED
463 510
 
464
-  #define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
511
+  #define SD_FINISHED_STEPPERRELEASE true          // Disable steppers when SD Print is finished
465 512
   #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
466 513
 
467
-  #define SDCARD_RATHERRECENTFIRST  //reverse file order of sd card menu display. Its sorted practically after the file system block order.
468
-  // if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that.
469
-  // using:
514
+  // Reverse SD sort to show "more recent" files first, according to the card's FAT.
515
+  // Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
516
+  #define SDCARD_RATHERRECENTFIRST
517
+
518
+  // Add an option in the menu to run all auto#.g files
470 519
   //#define MENU_ADDAUTOSTART
471 520
 
472 521
   /**
@@ -496,13 +545,15 @@
496 545
 
497 546
   // SD Card Sorting options
498 547
   #if ENABLED(SDCARD_SORT_ALPHA)
499
-    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256).
548
+    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256). Costs 27 bytes each.
500 549
     #define FOLDER_SORTING     -1     // -1=above  0=none  1=below
501 550
     #define SDSORT_GCODE       false  // Allow turning sorting on/off with LCD and M34 g-code.
502 551
     #define SDSORT_USES_RAM    false  // Pre-allocate a static array for faster pre-sorting.
503 552
     #define SDSORT_USES_STACK  false  // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
504 553
     #define SDSORT_CACHE_NAMES false  // Keep sorted items in RAM longer for speedy performance. Most expensive option.
505 554
     #define SDSORT_DYNAMIC_RAM false  // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
555
+    #define SDSORT_CACHE_VFATS 2      // Maximum number of 13-byte VFAT entries to use for sorting.
556
+                                      // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
506 557
   #endif
507 558
 
508 559
   // Show a progress bar on HD44780 LCDs for SD printing
@@ -521,14 +572,29 @@
521 572
     //#define LCD_PROGRESS_BAR_TEST
522 573
   #endif
523 574
 
575
+  // Add an 'M73' G-code to set the current percentage
576
+  //#define LCD_SET_PROGRESS_MANUALLY
577
+
524 578
   // This allows hosts to request long names for files and folders with M33
525 579
   //#define LONG_FILENAME_HOST_SUPPORT
526 580
 
527
-  // This option allows you to abort SD printing when any endstop is triggered.
528
-  // This feature must be enabled with "M540 S1" or from the LCD menu.
529
-  // To have any effect, endstops must be enabled during SD printing.
581
+  // Enable this option to scroll long filenames in the SD card menu
582
+  //#define SCROLL_LONG_FILENAMES
583
+
584
+  /**
585
+   * This option allows you to abort SD printing when any endstop is triggered.
586
+   * This feature must be enabled with "M540 S1" or from the LCD menu.
587
+   * To have any effect, endstops must be enabled during SD printing.
588
+   */
530 589
   //#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
531 590
 
591
+  /**
592
+   * This option makes it easier to print the same SD Card file again.
593
+   * On print completion the LCD Menu will open with the file selected.
594
+   * You can just click to start the print, or navigate elsewhere.
595
+   */
596
+  //#define SD_REPRINT_LAST_SELECTED_FILE
597
+
532 598
 #endif // SDSUPPORT
533 599
 
534 600
 /**
@@ -561,6 +627,10 @@
561 627
   // Enable this option and reduce the value to optimize screen updates.
562 628
   // The normal delay is 10µs. Use the lowest value that still gives a reliable display.
563 629
   //#define DOGM_SPI_DELAY_US 5
630
+
631
+  // Swap the CW/CCW indicators in the graphics overlay
632
+  //#define OVERLAY_GFX_REVERSE
633
+
564 634
 #endif // DOGLCD
565 635
 
566 636
 // @section safety
@@ -587,31 +657,18 @@
587 657
  */
588 658
 //#define BABYSTEPPING
589 659
 #if ENABLED(BABYSTEPPING)
590
-  #define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
591
-  #define BABYSTEP_INVERT_Z false  // Change if Z babysteps should go the other way
592
-  #define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
593
-  //#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
660
+  //#define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
661
+  #define BABYSTEP_INVERT_Z false    // Change if Z babysteps should go the other way
662
+  #define BABYSTEP_MULTIPLICATOR 1   // Babysteps are very small. Increase for faster motion.
663
+  //#define BABYSTEP_ZPROBE_OFFSET   // Enable to combine M851 and Babystepping
594 664
   //#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
595 665
   #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
596 666
                                         // Note: Extra time may be added to mitigate controller latency.
667
+  //#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
597 668
 #endif
598 669
 
599 670
 // @section extruder
600 671
 
601
-// extruder advance constant (s2/mm3)
602
-//
603
-// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
604
-//
605
-// Hooke's law says:    force = k * distance
606
-// Bernoulli's principle says:  v ^ 2 / 2 + g . h + pressure / density = constant
607
-// so: v ^ 2 is proportional to number of steps we advance the extruder
608
-//#define ADVANCE
609
-
610
-#if ENABLED(ADVANCE)
611
-  #define EXTRUDER_ADVANCE_K .0
612
-  #define D_FILAMENT 2.85
613
-#endif
614
-
615 672
 /**
616 673
  * Implementation of linear pressure control
617 674
  *
@@ -645,7 +702,7 @@
645 702
    *
646 703
    * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
647 704
    *
648
-   * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode.
705
+   * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
649 706
    * Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
650 707
    */
651 708
   #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
@@ -654,19 +711,18 @@
654 711
 
655 712
 // @section leveling
656 713
 
657
-// Default mesh area is an area with an inset margin on the print area.
658
-// Below are the macros that are used to define the borders for the mesh area,
659
-// made available here for specialized needs, ie dual extruder setup.
660
-#if ENABLED(MESH_BED_LEVELING)
661
-  #define MESH_MIN_X (X_MIN_POS + MESH_INSET)
662
-  #define MESH_MAX_X (X_MAX_POS - (MESH_INSET))
663
-  #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET)
664
-  #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET))
665
-#elif ENABLED(AUTO_BED_LEVELING_UBL)
666
-  #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET)
667
-  #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET))
668
-  #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET)
669
-  #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET))
714
+#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
715
+  #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
716
+#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
717
+  #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
718
+#endif
719
+
720
+#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
721
+  // Override the mesh area if the automatic (max) area is too large
722
+  //#define MESH_MIN_X MESH_INSET
723
+  //#define MESH_MIN_Y MESH_INSET
724
+  //#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
725
+  //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
670 726
 #endif
671 727
 
672 728
 // @section extras
@@ -686,7 +742,7 @@
686 742
 //#define BEZIER_CURVE_SUPPORT
687 743
 
688 744
 // G38.2 and G38.3 Probe Target
689
-// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
745
+// Set MULTIPLE_PROBING if you want G38 to double touch
690 746
 //#define G38_PROBE_TARGET
691 747
 #if ENABLED(G38_PROBE_TARGET)
692 748
   #define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
@@ -711,7 +767,7 @@
711 767
 // @section hidden
712 768
 
713 769
 // The number of linear motions that can be in the plan at any give time.
714
-// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
770
+// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
715 771
 #if ENABLED(SDSUPPORT)
716 772
   #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
717 773
 #else
@@ -724,7 +780,7 @@
724 780
 #define MAX_CMD_SIZE 96
725 781
 #define BUFSIZE 4
726 782
 
727
-// Transfer Buffer Size
783
+// Transmission to Host Buffer Size
728 784
 // To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0.
729 785
 // To buffer a simple "ok" you need 4 bytes.
730 786
 // For ADVANCED_OK (M105) you need 32 bytes.
@@ -733,6 +789,28 @@
733 789
 // :[0, 2, 4, 8, 16, 32, 64, 128, 256]
734 790
 #define TX_BUFFER_SIZE 0
735 791
 
792
+// Host Receive Buffer Size
793
+// Without XON/XOFF flow control (see SERIAL_XON_XOFF below) 32 bytes should be enough.
794
+// To use flow control, set this buffer size to at least 1024 bytes.
795
+// :[0, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048]
796
+//#define RX_BUFFER_SIZE 1024
797
+
798
+#if RX_BUFFER_SIZE >= 1024
799
+  // Enable to have the controller send XON/XOFF control characters to
800
+  // the host to signal the RX buffer is becoming full.
801
+  //#define SERIAL_XON_XOFF
802
+#endif
803
+
804
+#if ENABLED(SDSUPPORT)
805
+  // Enable this option to collect and display the maximum
806
+  // RX queue usage after transferring a file to SD.
807
+  //#define SERIAL_STATS_MAX_RX_QUEUED
808
+
809
+  // Enable this option to collect and display the number
810
+  // of dropped bytes after a file transfer to SD.
811
+  //#define SERIAL_STATS_DROPPED_RX
812
+#endif
813
+
736 814
 // Enable an emergency-command parser to intercept certain commands as they
737 815
 // enter the serial receive buffer, so they cannot be blocked.
738 816
 // Currently handles M108, M112, M410
@@ -748,27 +826,47 @@
748 826
 // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary.
749 827
 //#define ADVANCED_OK
750 828
 
751
-// @section fwretract
752
-
753
-// Firmware based and LCD controlled retract
754
-// M207 and M208 can be used to define parameters for the retraction.
755
-// The retraction can be called by the slicer using G10 and G11
756
-// until then, intended retractions can be detected by moves that only extrude and the direction.
757
-// the moves are than replaced by the firmware controlled ones.
829
+// @section extras
758 830
 
759
-//#define FWRETRACT  //ONLY PARTIALLY TESTED
831
+/**
832
+ * Firmware-based and LCD-controlled retract
833
+ *
834
+ * Add G10 / G11 commands for automatic firmware-based retract / recover.
835
+ * Use M207 and M208 to define parameters for retract / recover.
836
+ *
837
+ * Use M209 to enable or disable auto-retract.
838
+ * With auto-retract enabled, all G1 E moves within the set range
839
+ * will be converted to firmware-based retract/recover moves.
840
+ *
841
+ * Be sure to turn off auto-retract during filament change.
842
+ *
843
+ * Note that M207 / M208 / M209 settings are saved to EEPROM.
844
+ *
845
+ */
846
+//#define FWRETRACT  // ONLY PARTIALLY TESTED
760 847
 #if ENABLED(FWRETRACT)
761
-  #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
762
-  #define RETRACT_LENGTH 3               //default retract length (positive mm)
763
-  #define RETRACT_LENGTH_SWAP 13         //default swap retract length (positive mm), for extruder change
764
-  #define RETRACT_FEEDRATE 45            //default feedrate for retracting (mm/s)
765
-  #define RETRACT_ZLIFT 0                //default retract Z-lift
766
-  #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
767
-  #define RETRACT_RECOVER_LENGTH_SWAP 0  //default additional swap recover length (mm, added to retract length when recovering from extruder change)
768
-  #define RETRACT_RECOVER_FEEDRATE 8     //default feedrate for recovering from retraction (mm/s)
848
+  #define MIN_AUTORETRACT 0.1             // When auto-retract is on, convert E moves of this length and over
849
+  #define MAX_AUTORETRACT 10.0            // Upper limit for auto-retract conversion
850
+  #define RETRACT_LENGTH 3                // Default retract length (positive mm)
851
+  #define RETRACT_LENGTH_SWAP 13          // Default swap retract length (positive mm), for extruder change
852
+  #define RETRACT_FEEDRATE 45             // Default feedrate for retracting (mm/s)
853
+  #define RETRACT_ZLIFT 0                 // Default retract Z-lift
854
+  #define RETRACT_RECOVER_LENGTH 0        // Default additional recover length (mm, added to retract length when recovering)
855
+  #define RETRACT_RECOVER_LENGTH_SWAP 0   // Default additional swap recover length (mm, added to retract length when recovering from extruder change)
856
+  #define RETRACT_RECOVER_FEEDRATE 8      // Default feedrate for recovering from retraction (mm/s)
857
+  #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
769 858
 #endif
770 859
 
771 860
 /**
861
+ * Extra Fan Speed
862
+ * Adds a secondary fan speed for each print-cooling fan.
863
+ *   'M106 P<fan> T3-255' : Set a secondary speed for <fan>
864
+ *   'M106 P<fan> T2'     : Use the set secondary speed
865
+ *   'M106 P<fan> T1'     : Restore the previous fan speed
866
+ */
867
+//#define EXTRA_FAN_SPEED
868
+
869
+/**
772 870
  * Advanced Pause
773 871
  * Experimental feature for filament change support and for parking the nozzle when paused.
774 872
  * Adds the GCode M600 for initiating filament change.
@@ -878,7 +976,7 @@
878 976
 
879 977
 #endif
880 978
 
881
-// @section TMC2130
979
+// @section TMC2130, TMC2208
882 980
 
883 981
 /**
884 982
  * Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
@@ -892,7 +990,19 @@
892 990
  */
893 991
 //#define HAVE_TMC2130
894 992
 
895
-#if ENABLED(HAVE_TMC2130)
993
+/**
994
+ * Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
995
+ * Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
996
+ * To use the reading capabilities, also connect #_SERIAL_RX_PIN
997
+ * to #_SERIAL_TX_PIN with a 1K resistor.
998
+ * The drivers can also be used with hardware serial.
999
+ *
1000
+ * You'll also need the TMC2208Stepper Arduino library
1001
+ * (https://github.com/teemuatlut/TMC2208Stepper).
1002
+ */
1003
+//#define HAVE_TMC2208
1004
+
1005
+#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
896 1006
 
897 1007
   // CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
898 1008
   //#define X_IS_TMC2130
@@ -907,46 +1017,58 @@
907 1017
   //#define E3_IS_TMC2130
908 1018
   //#define E4_IS_TMC2130
909 1019
 
1020
+  //#define X_IS_TMC2208
1021
+  //#define X2_IS_TMC2208
1022
+  //#define Y_IS_TMC2208
1023
+  //#define Y2_IS_TMC2208
1024
+  //#define Z_IS_TMC2208
1025
+  //#define Z2_IS_TMC2208
1026
+  //#define E0_IS_TMC2208
1027
+  //#define E1_IS_TMC2208
1028
+  //#define E2_IS_TMC2208
1029
+  //#define E3_IS_TMC2208
1030
+  //#define E4_IS_TMC2208
1031
+
910 1032
   /**
911 1033
    * Stepper driver settings
912 1034
    */
913 1035
 
914 1036
   #define R_SENSE           0.11  // R_sense resistor for SilentStepStick2130
915 1037
   #define HOLD_MULTIPLIER    0.5  // Scales down the holding current from run current
916
-  #define INTERPOLATE          1  // Interpolate X/Y/Z_MICROSTEPS to 256
1038
+  #define INTERPOLATE       true  // Interpolate X/Y/Z_MICROSTEPS to 256
917 1039
 
918
-  #define X_CURRENT         1000  // rms current in mA. Multiply by 1.41 for peak current.
1040
+  #define X_CURRENT          800  // rms current in mA. Multiply by 1.41 for peak current.
919 1041
   #define X_MICROSTEPS        16  // 0..256
920 1042
 
921
-  #define Y_CURRENT         1000
1043
+  #define Y_CURRENT          800
922 1044
   #define Y_MICROSTEPS        16
923 1045
 
924
-  #define Z_CURRENT         1000
1046
+  #define Z_CURRENT          800
925 1047
   #define Z_MICROSTEPS        16
926 1048
 
927
-  //#define X2_CURRENT      1000
928
-  //#define X2_MICROSTEPS     16
1049
+  #define X2_CURRENT         800
1050
+  #define X2_MICROSTEPS       16
929 1051
 
930
-  //#define Y2_CURRENT      1000
931
-  //#define Y2_MICROSTEPS     16
1052
+  #define Y2_CURRENT         800
1053
+  #define Y2_MICROSTEPS       16
932 1054
 
933
-  //#define Z2_CURRENT      1000
934
-  //#define Z2_MICROSTEPS     16
1055
+  #define Z2_CURRENT         800
1056
+  #define Z2_MICROSTEPS       16
935 1057
 
936
-  //#define E0_CURRENT      1000
937
-  //#define E0_MICROSTEPS     16
1058
+  #define E0_CURRENT         800
1059
+  #define E0_MICROSTEPS       16
938 1060
 
939
-  //#define E1_CURRENT      1000
940
-  //#define E1_MICROSTEPS     16
1061
+  #define E1_CURRENT         800
1062
+  #define E1_MICROSTEPS       16
941 1063
 
942
-  //#define E2_CURRENT      1000
943
-  //#define E2_MICROSTEPS     16
1064
+  #define E2_CURRENT         800
1065
+  #define E2_MICROSTEPS       16
944 1066
 
945
-  //#define E3_CURRENT      1000
946
-  //#define E3_MICROSTEPS     16
1067
+  #define E3_CURRENT         800
1068
+  #define E3_MICROSTEPS       16
947 1069
 
948
-  //#define E4_CURRENT      1000
949
-  //#define E4_MICROSTEPS     16
1070
+  #define E4_CURRENT         800
1071
+  #define E4_MICROSTEPS       16
950 1072
 
951 1073
   /**
952 1074
    * Use Trinamic's ultra quiet stepping mode.
@@ -955,24 +1077,22 @@
955 1077
   #define STEALTHCHOP
956 1078
 
957 1079
   /**
958
-   * Let Marlin automatically control stepper current.
959
-   * This is still an experimental feature.
960
-   * Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
961
-   * then decrease current by CURRENT_STEP until temperature prewarn is cleared.
962
-   * Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
1080
+   * Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
1081
+   * like overtemperature and short to ground. TMC2208 requires hardware serial.
1082
+   * In the case of overtemperature Marlin can decrease the driver current until error condition clears.
1083
+   * Other detected conditions can be used to stop the current print.
963 1084
    * Relevant g-codes:
964 1085
    * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
965
-   * M906 S1 - Start adjusting current
966
-   * M906 S0 - Stop adjusting current
967 1086
    * M911 - Report stepper driver overtemperature pre-warn condition.
968 1087
    * M912 - Clear stepper driver overtemperature pre-warn condition flag.
1088
+   * M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
969 1089
    */
970
-  //#define AUTOMATIC_CURRENT_CONTROL
1090
+  //#define MONITOR_DRIVER_STATUS
971 1091
 
972
-  #if ENABLED(AUTOMATIC_CURRENT_CONTROL)
973
-    #define CURRENT_STEP          50  // [mA]
974
-    #define AUTO_ADJUST_MAX     1300  // [mA], 1300mA_rms = 1840mA_peak
1092
+  #if ENABLED(MONITOR_DRIVER_STATUS)
1093
+    #define CURRENT_STEP_DOWN     50  // [mA]
975 1094
     #define REPORT_CURRENT_CHANGE
1095
+    #define STOP_ON_ERROR
976 1096
   #endif
977 1097
 
978 1098
   /**
@@ -987,8 +1107,8 @@
987 1107
   #define X2_HYBRID_THRESHOLD    100
988 1108
   #define Y_HYBRID_THRESHOLD     100
989 1109
   #define Y2_HYBRID_THRESHOLD    100
990
-  #define Z_HYBRID_THRESHOLD       4
991
-  #define Z2_HYBRID_THRESHOLD      4
1110
+  #define Z_HYBRID_THRESHOLD       3
1111
+  #define Z2_HYBRID_THRESHOLD      3
992 1112
   #define E0_HYBRID_THRESHOLD     30
993 1113
   #define E1_HYBRID_THRESHOLD     30
994 1114
   #define E2_HYBRID_THRESHOLD     30
@@ -998,7 +1118,7 @@
998 1118
   /**
999 1119
    * Use stallGuard2 to sense an obstacle and trigger an endstop.
1000 1120
    * You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
1001
-   * If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
1121
+   * X and Y homing will always be done in spreadCycle mode.
1002 1122
    *
1003 1123
    * X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
1004 1124
    * Higher values make the system LESS sensitive.
@@ -1007,27 +1127,34 @@
1007 1127
    * It is advised to set X/Y_HOME_BUMP_MM to 0.
1008 1128
    * M914 X/Y to live tune the setting
1009 1129
    */
1010
-  //#define SENSORLESS_HOMING
1130
+  //#define SENSORLESS_HOMING // TMC2130 only
1011 1131
 
1012 1132
   #if ENABLED(SENSORLESS_HOMING)
1013
-    #define X_HOMING_SENSITIVITY  19
1014
-    #define Y_HOMING_SENSITIVITY  19
1133
+    #define X_HOMING_SENSITIVITY  8
1134
+    #define Y_HOMING_SENSITIVITY  8
1015 1135
   #endif
1016 1136
 
1017 1137
   /**
1138
+   * Enable M122 debugging command for TMC stepper drivers.
1139
+   * M122 S0/1 will enable continous reporting.
1140
+   */
1141
+  //#define TMC_DEBUG
1142
+
1143
+  /**
1018 1144
    * You can set your own advanced settings by filling in predefined functions.
1019 1145
    * A list of available functions can be found on the library github page
1020 1146
    * https://github.com/teemuatlut/TMC2130Stepper
1147
+   * https://github.com/teemuatlut/TMC2208Stepper
1021 1148
    *
1022 1149
    * Example:
1023
-   * #define TMC2130_ADV() { \
1150
+   * #define TMC_ADV() { \
1024 1151
    *   stepperX.diag0_temp_prewarn(1); \
1025
-   *   stepperX.interpolate(0); \
1152
+   *   stepperY.interpolate(0); \
1026 1153
    * }
1027 1154
    */
1028
-  #define  TMC2130_ADV() {  }
1155
+  #define  TMC_ADV() {  }
1029 1156
 
1030
-#endif // HAVE_TMC2130
1157
+#endif // TMC2130 || TMC2208
1031 1158
 
1032 1159
 // @section L6470
1033 1160
 
@@ -1192,6 +1319,48 @@
1192 1319
 #endif
1193 1320
 
1194 1321
 /**
1322
+ * Filament Width Sensor
1323
+ *
1324
+ * Measures the filament width in real-time and adjusts
1325
+ * flow rate to compensate for any irregularities.
1326
+ *
1327
+ * Also allows the measured filament diameter to set the
1328
+ * extrusion rate, so the slicer only has to specify the
1329
+ * volume.
1330
+ *
1331
+ * Only a single extruder is supported at this time.
1332
+ *
1333
+ *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1334
+ *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1335
+ * 301 RAMBO       : Analog input 3
1336
+ *
1337
+ * Note: May require analog pins to be defined for other boards.
1338
+ */
1339
+//#define FILAMENT_WIDTH_SENSOR
1340
+
1341
+#if ENABLED(FILAMENT_WIDTH_SENSOR)
1342
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
1343
+  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1344
+
1345
+  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1346
+  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1347
+  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1348
+
1349
+  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1350
+
1351
+  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1352
+  //#define FILAMENT_LCD_DISPLAY
1353
+#endif
1354
+
1355
+/**
1356
+ * CNC Coordinate Systems
1357
+ *
1358
+ * Enables G53 and G54-G59.3 commands to select coordinate systems
1359
+ * and G92.1 to reset the workspace to native machine space.
1360
+ */
1361
+//#define CNC_COORDINATE_SYSTEMS
1362
+
1363
+/**
1195 1364
  * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
1196 1365
  */
1197 1366
 //#define PINS_DEBUGGING
@@ -1244,6 +1413,8 @@
1244 1413
 //#define CUSTOM_USER_MENUS
1245 1414
 #if ENABLED(CUSTOM_USER_MENUS)
1246 1415
   #define USER_SCRIPT_DONE "M117 User Script Done"
1416
+  #define USER_SCRIPT_AUDIBLE_FEEDBACK
1417
+  //#define USER_SCRIPT_RETURN  // Return to status screen after a script
1247 1418
 
1248 1419
   #define USER_DESC_1 "Home & UBL Info"
1249 1420
   #define USER_GCODE_1 "G28\nG29 W"
@@ -1271,6 +1442,7 @@
1271 1442
 //===========================================================================
1272 1443
 //====================== I2C Position Encoder Settings ======================
1273 1444
 //===========================================================================
1445
+
1274 1446
 /**
1275 1447
  *  I2C position encoders for closed loop control.
1276 1448
  *  Developed by Chris Barr at Aus3D.
@@ -1351,4 +1523,45 @@
1351 1523
 
1352 1524
 #endif // I2C_POSITION_ENCODERS
1353 1525
 
1526
+/**
1527
+ * MAX7219 Debug Matrix
1528
+ *
1529
+ * Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
1530
+ * display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
1531
+ *
1532
+ * Fully assembled MAX7219 boards can be found on the internet for under $2(US).
1533
+ * For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
1534
+ */
1535
+//#define MAX7219_DEBUG
1536
+#if ENABLED(MAX7219_DEBUG)
1537
+  #define MAX7219_CLK_PIN   64  // 77 on Re-ARM       // Configuration of the 3 pins to control the display
1538
+  #define MAX7219_DIN_PIN   57  // 78 on Re-ARM
1539
+  #define MAX7219_LOAD_PIN  44  // 79 on Re-ARM
1540
+
1541
+  /**
1542
+   * Sample debug features
1543
+   * If you add more debug displays, be careful to avoid conflicts!
1544
+   */
1545
+  #define MAX7219_DEBUG_PRINTER_ALIVE    // Blink corner LED of 8x8 matrix to show that the firmware is functioning
1546
+  #define MAX7219_DEBUG_STEPPER_HEAD  3  // Show the stepper queue head position on this and the next LED matrix row
1547
+  #define MAX7219_DEBUG_STEPPER_TAIL  5  // Show the stepper queue tail position on this and the next LED matrix row
1548
+
1549
+  #define MAX7219_DEBUG_STEPPER_QUEUE 0  // Show the current stepper queue depth on this and the next LED matrix row
1550
+                                         // If you experience stuttering, reboots, etc. this option can reveal how
1551
+                                         // tweaks made to the configuration are affecting the printer in real-time.
1552
+#endif
1553
+
1554
+/**
1555
+ * NanoDLP Sync support
1556
+ *
1557
+ * Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
1558
+ * string to enable synchronization with DLP projector exposure. This change will allow to use
1559
+ * [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
1560
+ */
1561
+//#define NANODLP_Z_SYNC
1562
+#if ENABLED(NANODLP_Z_SYNC)
1563
+  //#define NANODLP_ALL_AXIS  // Enables "Z_move_comp" output on any axis move.
1564
+                              // Default behaviour is limited to Z axis only.
1565
+#endif
1566
+
1354 1567
 #endif // CONFIGURATION_ADV_H

+ 1779
- 0
Marlin/example_configurations/Creality/CR-10/Configuration.h
파일 크기가 너무 크기때문에 변경 상태를 표시하지 않습니다.
파일 보기


+ 1570
- 0
Marlin/example_configurations/Creality/CR-10/Configuration_adv.h
파일 크기가 너무 크기때문에 변경 상태를 표시하지 않습니다.
파일 보기


+ 100
- 0
Marlin/example_configurations/Creality/CR-10/_Bootscreen.h 파일 보기

@@ -0,0 +1,100 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 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
+/**
24
+ * Tongue-in-cheek placeholder for a more Marlin-specific bitmap
25
+ * The joke is that every "CR-10" has different branding!
26
+ * Made using The Gimp and...
27
+ *  - http://www.digole.com/tools/PicturetoC_Hex_converter.php
28
+ */
29
+#include <avr/pgmspace.h>
30
+
31
+#define CUSTOM_BOOTSCREEN_TIMEOUT   2500
32
+#define CUSTOM_BOOTSCREEN_BMPWIDTH  54
33
+#define CUSTOM_BOOTSCREEN_BMPHEIGHT 64
34
+
35
+const unsigned char custom_start_bmp[] PROGMEM = {
36
+  0x00, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00,
37
+  0x00, 0x00, 0x00, 0x3F, 0xF8, 0x00, 0x00,
38
+  0x00, 0x00, 0x03, 0xFF, 0xFC, 0x00, 0x00,
39
+  0x00, 0x00, 0x0F, 0xFF, 0xFC, 0x00, 0x00,
40
+  0x00, 0x00, 0x3F, 0xFF, 0xFC, 0x00, 0x00,
41
+  0x00, 0x00, 0x7F, 0xFF, 0xFC, 0x00, 0x00,
42
+  0x00, 0x00, 0x7F, 0xFF, 0xFC, 0x00, 0x00,
43
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
44
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
45
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
46
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x0F, 0xF0,
47
+  0x00, 0x00, 0xFF, 0xFF, 0xFD, 0xFF, 0xF8,
48
+  0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
49
+  0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
50
+  0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
51
+  0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
52
+  0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
53
+  0x00, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8,
54
+  0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0,
55
+  0x07, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0,
56
+  0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00,
57
+  0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x00,
58
+  0x7F, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
59
+  0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
60
+  0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
61
+  0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
62
+  0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
63
+  0x7F, 0xFC, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
64
+  0x1F, 0x80, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
65
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
66
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
67
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
68
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
69
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
70
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
71
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
72
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
73
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
74
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
75
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
76
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
77
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
78
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
79
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
80
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
81
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
82
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
83
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
84
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
85
+  0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
86
+  0x00, 0x00, 0xFF, 0xFF, 0xFE, 0x3F, 0xF8,
87
+  0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
88
+  0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
89
+  0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
90
+  0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
91
+  0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
92
+  0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8,
93
+  0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8,
94
+  0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0,
95
+  0x00, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xC0,
96
+  0x00, 0x00, 0x3F, 0xFF, 0xFF, 0xFE, 0x00,
97
+  0x00, 0x00, 0x1F, 0xFF, 0xFF, 0xE0, 0x00,
98
+  0x00, 0x00, 0x07, 0xFF, 0xFC, 0x00, 0x00,
99
+  0x00, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x00
100
+};

+ 248
- 103
Marlin/example_configurations/Felix/Configuration.h 파일 보기

@@ -37,7 +37,7 @@
37 37
  */
38 38
 #ifndef CONFIGURATION_H
39 39
 #define CONFIGURATION_H
40
-#define CONFIGURATION_H_VERSION 010100
40
+#define CONFIGURATION_H_VERSION 010107
41 41
 
42 42
 //===========================================================================
43 43
 //============================= Getting Started =============================
@@ -74,7 +74,7 @@
74 74
 // User-specified version info of this build to display in [Pronterface, etc] terminal window during
75 75
 // startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
76 76
 // build by the user have been successfully uploaded into firmware.
77
-#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
77
+#define STRING_CONFIG_H_AUTHOR "(none, Felix)" // Who made the changes.
78 78
 #define SHOW_BOOTSCREEN
79 79
 #define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
80 80
 #define STRING_SPLASH_LINE2 WEBSITE_URL         // will be shown during bootup in line 2
@@ -107,8 +107,9 @@
107 107
  *
108 108
  * 250000 works in most cases, but you might try a lower speed if
109 109
  * you commonly experience drop-outs during host printing.
110
+ * You may try up to 1000000 to speed up SD file transfer.
110 111
  *
111
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
112
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
112 113
  */
113 114
 #define BAUDRATE 250000
114 115
 
@@ -135,6 +136,9 @@
135 136
 // :[1, 2, 3, 4, 5]
136 137
 #define EXTRUDERS 1
137 138
 
139
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
140
+#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
141
+
138 142
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
139 143
 //#define SINGLENOZZLE
140 144
 
@@ -161,7 +165,10 @@
161 165
 //#define SWITCHING_EXTRUDER
162 166
 #if ENABLED(SWITCHING_EXTRUDER)
163 167
   #define SWITCHING_EXTRUDER_SERVO_NR 0
164
-  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1
168
+  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3]
169
+  #if EXTRUDERS > 3
170
+    #define SWITCHING_EXTRUDER_E23_SERVO_NR 1
171
+  #endif
165 172
 #endif
166 173
 
167 174
 // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles
@@ -173,6 +180,21 @@
173 180
 #endif
174 181
 
175 182
 /**
183
+ * Two separate X-carriages with extruders that connect to a moving part
184
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
185
+ */
186
+//#define PARKING_EXTRUDER
187
+#if ENABLED(PARKING_EXTRUDER)
188
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
189
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
190
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
191
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
192
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
193
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
194
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
195
+#endif
196
+
197
+/**
176 198
  * "Mixing Extruder"
177 199
  *   - Adds a new code, M165, to set the current mix factors.
178 200
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -317,8 +339,9 @@
317 339
 
318 340
 // Comment the following line to disable PID and enable bang-bang.
319 341
 #define PIDTEMP
320
-#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
321
-#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
342
+#define BANG_MAX 255     // Limits current to nozzle while in bang-bang mode; 255=full current
343
+#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
344
+#define PID_K1 0.95      // Smoothing factor within the PID
322 345
 #if ENABLED(PIDTEMP)
323 346
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
324 347
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -328,7 +351,6 @@
328 351
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
329 352
   #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
330 353
                                   // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
331
-  #define K1 0.95 //smoothing factor within the PID
332 354
 
333 355
   // Felix 2.0+ electronics with v4 Hotend
334 356
   #define DEFAULT_Kp 12
@@ -390,12 +412,13 @@
390 412
 //===========================================================================
391 413
 
392 414
 /**
393
- * Thermal Protection protects your printer from damage and fire if a
394
- * thermistor falls out or temperature sensors fail in any way.
415
+ * Thermal Protection provides additional protection to your printer from damage
416
+ * and fire. Marlin always includes safe min and max temperature ranges which
417
+ * protect against a broken or disconnected thermistor wire.
395 418
  *
396
- * The issue: If a thermistor falls out or a temperature sensor fails,
397
- * Marlin can no longer sense the actual temperature. Since a disconnected
398
- * thermistor reads as a low temperature, the firmware will keep the heater on.
419
+ * The issue: If a thermistor falls out, it will report the much lower
420
+ * temperature of the air in the room, and the the firmware will keep
421
+ * the heater on.
399 422
  *
400 423
  * If you get "Thermal Runaway" or "Heating failed" errors the
401 424
  * details can be tuned in Configuration_adv.h
@@ -536,7 +559,7 @@
536 559
 // @section probes
537 560
 
538 561
 //
539
-// See http://marlinfw.org/configuration/probes.html
562
+// See http://marlinfw.org/docs/configuration/probes.html
540 563
 //
541 564
 
542 565
 /**
@@ -602,14 +625,15 @@
602 625
 #endif
603 626
 
604 627
 /**
605
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
606
- * options selected below - will be disabled during probing so as to minimize
607
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
608
- * in current flowing through the wires).  This is likely most useful to users of the
609
- * BLTouch probe, but may also help those with inductive or other probe types.
628
+ * Enable one or more of the following if probing seems unreliable.
629
+ * Heaters and/or fans can be disabled during probing to minimize electrical
630
+ * noise. A delay can also be added to allow noise and vibration to settle.
631
+ * These options are most useful for the BLTouch probe, but may also improve
632
+ * readings with inductive probes and piezo sensors.
610 633
  */
611 634
 //#define PROBING_HEATERS_OFF       // Turn heaters off when probing
612 635
 //#define PROBING_FANS_OFF          // Turn fans off when probing
636
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
613 637
 
614 638
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
615 639
 //#define SOLENOID_PROBE
@@ -648,14 +672,16 @@
648 672
 // X and Y axis travel speed (mm/m) between probes
649 673
 #define XY_PROBE_SPEED 8000
650 674
 
651
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
675
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
652 676
 #define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
653 677
 
654 678
 // Speed for the "accurate" probe of each point
655 679
 #define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
656 680
 
657
-// Use double touch for probing
658
-//#define PROBE_DOUBLE_TOUCH
681
+// The number of probes to perform at each point.
682
+//   Set to 2 for a fast/slow probe, using the second probe result.
683
+//   Set to 3 or more for slow probes, averaging the results.
684
+//#define MULTIPLE_PROBING 2
659 685
 
660 686
 /**
661 687
  * Z probes require clearance when deploying, stowing, and moving between
@@ -722,29 +748,55 @@
722 748
 
723 749
 // @section homing
724 750
 
751
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
752
+
725 753
 //#define Z_HOMING_HEIGHT 4  // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
726 754
                              // Be sure you have this distance over your Z_MAX_POS in case.
727 755
 
728 756
 // Direction of endstops when homing; 1=MAX, -1=MIN
729
-// :[-1, 1]
757
+// :[-1,1]
730 758
 #define X_HOME_DIR -1
731 759
 #define Y_HOME_DIR -1
732 760
 #define Z_HOME_DIR -1
733 761
 
734 762
 // @section machine
735 763
 
736
-// Travel limits after homing (units are in mm)
764
+// The size of the print bed
765
+#define X_BED_SIZE 255
766
+#define Y_BED_SIZE 205
767
+
768
+// Travel limits (mm) after homing, corresponding to endstop positions.
737 769
 #define X_MIN_POS 0
738 770
 #define Y_MIN_POS 0
739 771
 #define Z_MIN_POS 0
740
-#define X_MAX_POS 255
741
-#define Y_MAX_POS 205
772
+#define X_MAX_POS X_BED_SIZE
773
+#define Y_MAX_POS Y_BED_SIZE
742 774
 #define Z_MAX_POS 235
743 775
 
744
-// If enabled, axes won't move below MIN_POS in response to movement commands.
776
+/**
777
+ * Software Endstops
778
+ *
779
+ * - Prevent moves outside the set machine bounds.
780
+ * - Individual axes can be disabled, if desired.
781
+ * - X and Y only apply to Cartesian robots.
782
+ * - Use 'M211' to set software endstops on/off or report current state
783
+ */
784
+
785
+// Min software endstops curtail movement below minimum coordinate bounds
745 786
 #define MIN_SOFTWARE_ENDSTOPS
746
-// If enabled, axes won't move above MAX_POS in response to movement commands.
787
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
788
+  #define MIN_SOFTWARE_ENDSTOP_X
789
+  #define MIN_SOFTWARE_ENDSTOP_Y
790
+  #define MIN_SOFTWARE_ENDSTOP_Z
791
+#endif
792
+
793
+// Max software endstops curtail movement above maximum coordinate bounds
747 794
 #define MAX_SOFTWARE_ENDSTOPS
795
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
796
+  #define MAX_SOFTWARE_ENDSTOP_X
797
+  #define MAX_SOFTWARE_ENDSTOP_Y
798
+  #define MAX_SOFTWARE_ENDSTOP_Z
799
+#endif
748 800
 
749 801
 /**
750 802
  * Filament Runout Sensor
@@ -764,7 +816,7 @@
764 816
 //===========================================================================
765 817
 //=============================== Bed Leveling ==============================
766 818
 //===========================================================================
767
-// @section bedlevel
819
+// @section calibrate
768 820
 
769 821
 /**
770 822
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -790,12 +842,7 @@
790 842
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
791 843
  *   A comprehensive bed leveling system combining the features and benefits
792 844
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
793
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
794
- *   for Cartesian Printers. That said, it was primarily designed to correct
795
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
796
- *   please post an issue if something doesn't work correctly. Initially,
797
- *   you will need to set a reduced bed size so you have a rectangular area
798
- *   to test on.
845
+ *   Validation and Mesh Editing systems.
799 846
  *
800 847
  * - MESH_BED_LEVELING
801 848
  *   Probe a grid manually
@@ -822,6 +869,24 @@
822 869
   // at which point movement will be level to the machine's XY plane.
823 870
   // The height can be set with M420 Z<height>
824 871
   #define ENABLE_LEVELING_FADE_HEIGHT
872
+
873
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
874
+  // split up moves into short segments like a Delta. This follows the
875
+  // contours of the bed more closely than edge-to-edge straight moves.
876
+  #define SEGMENT_LEVELED_MOVES
877
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
878
+
879
+  /**
880
+   * Enable the G26 Mesh Validation Pattern tool.
881
+   */
882
+  //#define G26_MESH_VALIDATION   // Enable G26 mesh validation
883
+  #if ENABLED(G26_MESH_VALIDATION)
884
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
885
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
886
+    #define MESH_TEST_HOTEND_TEMP   205.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
887
+    #define MESH_TEST_BED_TEMP       60.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
888
+  #endif
889
+
825 890
 #endif
826 891
 
827 892
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -877,7 +942,9 @@
877 942
   //========================= Unified Bed Leveling ============================
878 943
   //===========================================================================
879 944
 
880
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
945
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
946
+
947
+  #define MESH_INSET 1              // Mesh inset margin on print area
881 948
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
882 949
   #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
883 950
 
@@ -888,8 +955,8 @@
888 955
   #define UBL_PROBE_PT_3_X 180
889 956
   #define UBL_PROBE_PT_3_Y 20
890 957
 
891
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
892 958
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
959
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
893 960
 
894 961
 #elif ENABLED(MESH_BED_LEVELING)
895 962
 
@@ -916,6 +983,9 @@
916 983
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
917 984
 #endif
918 985
 
986
+// Add a menu item to move between bed corners for manual bed adjustment
987
+//#define LEVEL_BED_CORNERS
988
+
919 989
 /**
920 990
  * Commands to execute at the end of G29 probing.
921 991
  * Useful to retract or move the Z probe out of the way.
@@ -946,14 +1016,71 @@
946 1016
 //#define Z_SAFE_HOMING
947 1017
 
948 1018
 #if ENABLED(Z_SAFE_HOMING)
949
-  #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
950
-  #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
1019
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1020
+  #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2)    // Y point for Z homing when homing all axes (G28).
951 1021
 #endif
952 1022
 
953 1023
 // Homing speeds (mm/m)
954 1024
 #define HOMING_FEEDRATE_XY (50*60)
955 1025
 #define HOMING_FEEDRATE_Z  (4*60)
956 1026
 
1027
+// @section calibrate
1028
+
1029
+/**
1030
+ * Bed Skew Compensation
1031
+ *
1032
+ * This feature corrects for misalignment in the XYZ axes.
1033
+ *
1034
+ * Take the following steps to get the bed skew in the XY plane:
1035
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1036
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1037
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1038
+ *  4. For XY_SIDE_AD measure the edge A to D
1039
+ *
1040
+ * Marlin automatically computes skew factors from these measurements.
1041
+ * Skew factors may also be computed and set manually:
1042
+ *
1043
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1044
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1045
+ *
1046
+ * If desired, follow the same procedure for XZ and YZ.
1047
+ * Use these diagrams for reference:
1048
+ *
1049
+ *    Y                     Z                     Z
1050
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1051
+ *    |    /       /        |    /       /        |    /       /
1052
+ *    |   /       /         |   /       /         |   /       /
1053
+ *    |  A-------D          |  A-------D          |  A-------D
1054
+ *    +-------------->X     +-------------->X     +-------------->Y
1055
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1056
+ */
1057
+//#define SKEW_CORRECTION
1058
+
1059
+#if ENABLED(SKEW_CORRECTION)
1060
+  // Input all length measurements here:
1061
+  #define XY_DIAG_AC 282.8427124746
1062
+  #define XY_DIAG_BD 282.8427124746
1063
+  #define XY_SIDE_AD 200
1064
+
1065
+  // Or, set the default skew factors directly here
1066
+  // to override the above measurements:
1067
+  #define XY_SKEW_FACTOR 0.0
1068
+
1069
+  //#define SKEW_CORRECTION_FOR_Z
1070
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1071
+    #define XZ_DIAG_AC 282.8427124746
1072
+    #define XZ_DIAG_BD 282.8427124746
1073
+    #define YZ_DIAG_AC 282.8427124746
1074
+    #define YZ_DIAG_BD 282.8427124746
1075
+    #define YZ_SIDE_AD 200
1076
+    #define XZ_SKEW_FACTOR 0.0
1077
+    #define YZ_SKEW_FACTOR 0.0
1078
+  #endif
1079
+
1080
+  // Enable this option for M852 to set skew at runtime
1081
+  //#define SKEW_CORRECTION_GCODE
1082
+#endif
1083
+
957 1084
 //=============================================================================
958 1085
 //============================= Additional Features ===========================
959 1086
 //=============================================================================
@@ -980,11 +1107,12 @@
980 1107
 //
981 1108
 #define HOST_KEEPALIVE_FEATURE        // Disable this if your host doesn't like keepalive messages
982 1109
 #define DEFAULT_KEEPALIVE_INTERVAL 2  // Number of seconds between "busy" messages. Set with M113.
1110
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
983 1111
 
984 1112
 //
985 1113
 // M100 Free Memory Watcher
986 1114
 //
987
-//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1115
+//#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
988 1116
 
989 1117
 //
990 1118
 // G20/G21 Inch mode support
@@ -1129,13 +1257,13 @@
1129 1257
  *
1130 1258
  * Select the language to display on the LCD. These languages are available:
1131 1259
  *
1132
- *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
1133
- *    it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
1134
- *    zh_CN, zh_TW, test
1260
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1261
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1262
+ *    tr, uk, zh_CN, zh_TW, test
1135 1263
  *
1136
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1264
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1137 1265
  */
1138
-//#define LCD_LANGUAGE en
1266
+#define LCD_LANGUAGE en
1139 1267
 
1140 1268
 /**
1141 1269
  * LCD Character Set
@@ -1155,7 +1283,7 @@
1155 1283
  *  - Click the controller to view the LCD menu
1156 1284
  *  - The LCD will display Japanese, Western, or Cyrillic text
1157 1285
  *
1158
- * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1286
+ * See http://marlinfw.org/docs/development/lcd_language.html
1159 1287
  *
1160 1288
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1161 1289
  */
@@ -1261,8 +1389,8 @@
1261 1389
 // Note: Test audio output with the G-Code:
1262 1390
 //  M300 S<frequency Hz> P<duration ms>
1263 1391
 //
1264
-//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
1265
-//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
1392
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
1393
+//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
1266 1394
 
1267 1395
 //
1268 1396
 // CONTROLLER TYPE: Standard
@@ -1370,11 +1498,13 @@
1370 1498
 //#define CARTESIO_UI
1371 1499
 
1372 1500
 //
1373
-// ANET_10 Controller supported displays.
1501
+// ANET and Tronxy Controller supported displays.
1374 1502
 //
1375
-//#define ANET_KEYPAD_LCD         // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1503
+//#define ZONESTAR_LCD            // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1376 1504
                                   // This LCD is known to be susceptible to electrical interference
1377 1505
                                   // which scrambles the display.  Pressing any button clears it up.
1506
+                                  // This is a LCD2004 display with 5 analog buttons.
1507
+
1378 1508
 //#define ANET_FULL_GRAPHICS_LCD  // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1379 1509
                                   // A clone of the RepRapDiscount full graphics display but with
1380 1510
                                   // different pins/wiring (see pins_ANET_10.h).
@@ -1434,11 +1564,6 @@
1434 1564
 //#define U8GLIB_SSD1306
1435 1565
 
1436 1566
 //
1437
-// TinyBoy2 128x64 OLED / Encoder Panel
1438
-//
1439
-//#define OLED_PANEL_TINYBOY2
1440
-
1441
-//
1442 1567
 // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules
1443 1568
 //
1444 1569
 //#define SAV_3DGLCD
@@ -1455,6 +1580,45 @@
1455 1580
 //
1456 1581
 //#define SAV_3DLCD
1457 1582
 
1583
+//
1584
+// TinyBoy2 128x64 OLED / Encoder Panel
1585
+//
1586
+//#define OLED_PANEL_TINYBOY2
1587
+
1588
+//
1589
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1590
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1591
+//
1592
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1593
+
1594
+//
1595
+// MKS MINI12864 with graphic controller and SD support
1596
+// http://reprap.org/wiki/MKS_MINI_12864
1597
+//
1598
+//#define MKS_MINI_12864
1599
+
1600
+//
1601
+// Factory display for Creality CR-10
1602
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1603
+//
1604
+// This is RAMPS-compatible using a single 10-pin connector.
1605
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1606
+//
1607
+//#define CR10_STOCKDISPLAY
1608
+
1609
+//
1610
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1611
+// http://reprap.org/wiki/MKS_12864OLED
1612
+//
1613
+// Tiny, but very sharp OLED display
1614
+//
1615
+//#define MKS_12864OLED
1616
+
1617
+// Silvergate GLCD controller
1618
+// http://github.com/android444/Silvergate
1619
+//
1620
+//#define SILVER_GATE_GLCD_CONTROLLER
1621
+
1458 1622
 //=============================================================================
1459 1623
 //=============================== Extra Features ==============================
1460 1624
 //=============================================================================
@@ -1511,16 +1675,22 @@
1511 1675
  * Adds the M150 command to set the LED (or LED strip) color.
1512 1676
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1513 1677
  * luminance values can be set from 0 to 255.
1678
+ * For Neopixel LED an overall brightness parameter is also available.
1514 1679
  *
1515 1680
  * *** CAUTION ***
1516 1681
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1517 1682
  *  as the Arduino cannot handle the current the LEDs will require.
1518 1683
  *  Failure to follow this precaution can destroy your Arduino!
1684
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1685
+ *  more current than the Arduino 5V linear regulator can produce.
1519 1686
  * *** CAUTION ***
1520 1687
  *
1688
+ * LED Type. Enable only one of the following two options.
1689
+ *
1521 1690
  */
1522 1691
 //#define RGB_LED
1523 1692
 //#define RGBW_LED
1693
+
1524 1694
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1525 1695
   #define RGB_LED_R_PIN 34
1526 1696
   #define RGB_LED_G_PIN 43
@@ -1528,6 +1698,17 @@
1528 1698
   #define RGB_LED_W_PIN -1
1529 1699
 #endif
1530 1700
 
1701
+// Support for Adafruit Neopixel LED driver
1702
+//#define NEOPIXEL_LED
1703
+#if ENABLED(NEOPIXEL_LED)
1704
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1705
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1706
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1707
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1708
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1709
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1710
+#endif
1711
+
1531 1712
 /**
1532 1713
  * Printer Event LEDs
1533 1714
  *
@@ -1539,68 +1720,32 @@
1539 1720
  *  - Change to green once print has finished
1540 1721
  *  - Turn off after the print has finished and the user has pushed a button
1541 1722
  */
1542
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)
1723
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1543 1724
   #define PRINTER_EVENT_LEDS
1544 1725
 #endif
1545 1726
 
1546
-/*********************************************************************\
1547
-* R/C SERVO support
1548
-* Sponsored by TrinityLabs, Reworked by codexmas
1549
-**********************************************************************/
1727
+/**
1728
+ * R/C SERVO support
1729
+ * Sponsored by TrinityLabs, Reworked by codexmas
1730
+ */
1550 1731
 
1551
-// Number of servos
1552
-//
1553
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1554
-// set it manually if you have more servos than extruders and wish to manually control some
1555
-// leaving it undefined or defining as 0 will disable the servo subsystem
1556
-// If unsure, leave commented / disabled
1557
-//
1732
+/**
1733
+ * Number of servos
1734
+ *
1735
+ * For some servo-related options NUM_SERVOS will be set automatically.
1736
+ * Set this manually if there are extra servos needing manual control.
1737
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1738
+ */
1558 1739
 //#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
1559 1740
 
1560 1741
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1561 1742
 // 300ms is a good value but you can try less delay.
1562 1743
 // If the servo can't reach the requested position, increase it.
1563
-#define SERVO_DELAY 300
1744
+#define SERVO_DELAY { 300 }
1564 1745
 
1565 1746
 // Servo deactivation
1566 1747
 //
1567 1748
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1568 1749
 //#define DEACTIVATE_SERVOS_AFTER_MOVE
1569 1750
 
1570
-/**
1571
- * Filament Width Sensor
1572
- *
1573
- * Measures the filament width in real-time and adjusts
1574
- * flow rate to compensate for any irregularities.
1575
- *
1576
- * Also allows the measured filament diameter to set the
1577
- * extrusion rate, so the slicer only has to specify the
1578
- * volume.
1579
- *
1580
- * Only a single extruder is supported at this time.
1581
- *
1582
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1583
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1584
- * 301 RAMBO       : Analog input 3
1585
- *
1586
- * Note: May require analog pins to be defined for other boards.
1587
- */
1588
-//#define FILAMENT_WIDTH_SENSOR
1589
-
1590
-#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00   // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
1591
-
1592
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1593
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1594
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1595
-
1596
-  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1597
-  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1598
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1599
-
1600
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1601
-
1602
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1603
-  //#define FILAMENT_LCD_DISPLAY
1604
-#endif
1605
-
1606 1751
 #endif // CONFIGURATION_H

+ 370
- 157
Marlin/example_configurations/Felix/Configuration_adv.h 파일 보기

@@ -32,7 +32,7 @@
32 32
  */
33 33
 #ifndef CONFIGURATION_ADV_H
34 34
 #define CONFIGURATION_ADV_H
35
-#define CONFIGURATION_ADV_H_VERSION 010100
35
+#define CONFIGURATION_ADV_H_VERSION 010107
36 36
 
37 37
 // @section temperature
38 38
 
@@ -48,31 +48,36 @@
48 48
 #endif
49 49
 
50 50
 /**
51
- * Thermal Protection protects your printer from damage and fire if a
52
- * thermistor falls out or temperature sensors fail in any way.
51
+ * Thermal Protection provides additional protection to your printer from damage
52
+ * and fire. Marlin always includes safe min and max temperature ranges which
53
+ * protect against a broken or disconnected thermistor wire.
53 54
  *
54
- * The issue: If a thermistor falls out or a temperature sensor fails,
55
- * Marlin can no longer sense the actual temperature. Since a disconnected
56
- * thermistor reads as a low temperature, the firmware will keep the heater on.
55
+ * The issue: If a thermistor falls out, it will report the much lower
56
+ * temperature of the air in the room, and the the firmware will keep
57
+ * the heater on.
57 58
  *
58 59
  * The solution: Once the temperature reaches the target, start observing.
59
- * If the temperature stays too far below the target (hysteresis) for too long (period),
60
- * the firmware will halt the machine as a safety precaution.
60
+ * If the temperature stays too far below the target (hysteresis) for too
61
+ * long (period), the firmware will halt the machine as a safety precaution.
61 62
  *
62
- * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63
+ * If you get false positives for "Thermal Runaway", increase
64
+ * THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63 65
  */
64 66
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
65 67
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
66 68
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
67 69
 
68 70
   /**
69
-   * Whenever an M104 or M109 increases the target temperature the firmware will wait for the
70
-   * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
71
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
72
-   * but only if the current temperature is far enough below the target for a reliable test.
71
+   * Whenever an M104, M109, or M303 increases the target temperature, the
72
+   * firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
73
+   * hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
74
+   * requires a hard reset. This test restarts with any M104/M109/M303, but only
75
+   * if the current temperature is far enough below the target for a reliable
76
+   * test.
73 77
    *
74
-   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
75
-   * WATCH_TEMP_INCREASE should not be below 2.
78
+   * If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
79
+   * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
80
+   * below 2.
76 81
    */
77 82
   #define WATCH_TEMP_PERIOD 20                // Seconds
78 83
   #define WATCH_TEMP_INCREASE 2               // Degrees Celsius
@@ -86,13 +91,7 @@
86 91
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
87 92
 
88 93
   /**
89
-   * Whenever an M140 or M190 increases the target temperature the firmware will wait for the
90
-   * WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
91
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
92
-   * but only if the current temperature is far enough below the target for a reliable test.
93
-   *
94
-   * If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
95
-   * WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
94
+   * As described above, except for the bed (M140/M190/M303).
96 95
    */
97 96
   #define WATCH_BED_TEMP_PERIOD 60                // Seconds
98 97
   #define WATCH_BED_TEMP_INCREASE 2               // Degrees Celsius
@@ -123,6 +122,9 @@
123 122
   #define AUTOTEMP_OLDWEIGHT 0.98
124 123
 #endif
125 124
 
125
+// Show extra position information in M114
126
+//#define M114_DETAIL
127
+
126 128
 // Show Temperature ADC value
127 129
 // Enable for M105 to include ADC values read from temperature sensors.
128 130
 //#define SHOW_TEMP_ADC_VALUES
@@ -221,6 +223,17 @@
221 223
 #define EXTRUDER_AUTO_FAN_SPEED   255  // == full speed
222 224
 
223 225
 /**
226
+ * Part-Cooling Fan Multiplexer
227
+ *
228
+ * This feature allows you to digitally multiplex the fan output.
229
+ * The multiplexer is automatically switched at tool-change.
230
+ * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans.
231
+ */
232
+#define FANMUX0_PIN -1
233
+#define FANMUX1_PIN -1
234
+#define FANMUX2_PIN -1
235
+
236
+/**
224 237
  * M355 Case Light on-off / brightness
225 238
  */
226 239
 //#define CASE_LIGHT_ENABLE
@@ -246,48 +259,49 @@
246 259
 
247 260
 //#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
248 261
 
249
-// Dual X Steppers
250
-// Uncomment this option to drive two X axis motors.
251
-// The next unused E driver will be assigned to the second X stepper.
262
+/**
263
+ * Dual Steppers / Dual Endstops
264
+ *
265
+ * This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
266
+ *
267
+ * For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
268
+ * spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
269
+ * set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
270
+ * that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
271
+ *
272
+ * Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
273
+ * this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
274
+ * in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
275
+ */
276
+
252 277
 //#define X_DUAL_STEPPER_DRIVERS
253 278
 #if ENABLED(X_DUAL_STEPPER_DRIVERS)
254
-  // Set true if the two X motors need to rotate in opposite directions
255
-  #define INVERT_X2_VS_X_DIR true
279
+  #define INVERT_X2_VS_X_DIR true   // Set 'true' if X motors should rotate in opposite directions
280
+  //#define X_DUAL_ENDSTOPS
281
+  #if ENABLED(X_DUAL_ENDSTOPS)
282
+    #define X2_USE_ENDSTOP _XMAX_
283
+    #define X_DUAL_ENDSTOPS_ADJUSTMENT  0
284
+  #endif
256 285
 #endif
257 286
 
258
-// Dual Y Steppers
259
-// Uncomment this option to drive two Y axis motors.
260
-// The next unused E driver will be assigned to the second Y stepper.
261 287
 //#define Y_DUAL_STEPPER_DRIVERS
262 288
 #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
263
-  // Set true if the two Y motors need to rotate in opposite directions
264
-  #define INVERT_Y2_VS_Y_DIR true
289
+  #define INVERT_Y2_VS_Y_DIR true   // Set 'true' if Y motors should rotate in opposite directions
290
+  //#define Y_DUAL_ENDSTOPS
291
+  #if ENABLED(Y_DUAL_ENDSTOPS)
292
+    #define Y2_USE_ENDSTOP _YMAX_
293
+    #define Y_DUAL_ENDSTOPS_ADJUSTMENT  0
294
+  #endif
265 295
 #endif
266 296
 
267
-// A single Z stepper driver is usually used to drive 2 stepper motors.
268
-// Uncomment this option to use a separate stepper driver for each Z axis motor.
269
-// The next unused E driver will be assigned to the second Z stepper.
270 297
 //#define Z_DUAL_STEPPER_DRIVERS
271
-
272 298
 #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
273
-
274
-  // Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper.
275
-  // That way the machine is capable to align the bed during home, since both Z steppers are homed.
276
-  // There is also an implementation of M666 (software endstops adjustment) to this feature.
277
-  // After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
278
-  // One just need to home the Z axis and measure the distance difference between both Z axis and apply the math: Z adjust = Z - Z2.
279
-  // If the Z stepper axis is closer to the bed, the measure Z > Z2 (yes, it is.. think about it) and the Z adjust would be positive.
280
-  // Play a little bit with small adjustments (0.5mm) and check the behaviour.
281
-  // The M119 (endstops report) will start reporting the Z2 Endstop as well.
282
-
283 299
   //#define Z_DUAL_ENDSTOPS
284
-
285 300
   #if ENABLED(Z_DUAL_ENDSTOPS)
286 301
     #define Z2_USE_ENDSTOP _XMAX_
287
-    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0  // use M666 command to determine this value
302
+    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0
288 303
   #endif
289
-
290
-#endif // Z_DUAL_STEPPER_DRIVERS
304
+#endif
291 305
 
292 306
 // Enable this for dual x-carriage printers.
293 307
 // A dual x-carriage design has the advantage that the inactive extruder can be parked which
@@ -334,12 +348,12 @@
334 348
 
335 349
 // @section homing
336 350
 
337
-//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
351
+// Homing hits each endstop, retracts by these distances, then does a slower bump.
338 352
 #define X_HOME_BUMP_MM 5
339 353
 #define Y_HOME_BUMP_MM 5
340 354
 #define Z_HOME_BUMP_MM 3
341
-#define HOMING_BUMP_DIVISOR {2, 2, 4}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
342
-//#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
355
+#define HOMING_BUMP_DIVISOR { 2, 2, 4 }  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
356
+//#define QUICK_HOME                     // If homing includes X and Y, do a diagonal move initially
343 357
 
344 358
 // When G28 is called, this option will make Y home before X
345 359
 //#define HOME_Y_BEFORE_X
@@ -394,7 +408,7 @@
394 408
 // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
395 409
 // of the buffer and all stops. This should not be much greater than zero and should only be changed
396 410
 // if unwanted behavior is observed on a user's machine when running at very slow speeds.
397
-#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
411
+#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
398 412
 
399 413
 // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
400 414
 #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
@@ -423,8 +437,21 @@
423 437
 //#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 }   // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
424 438
 //#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 }    // Default drive percent - X, Y, Z, E axis
425 439
 
426
-// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
440
+// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
427 441
 //#define DIGIPOT_I2C
442
+#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
443
+  /**
444
+   * Common slave addresses:
445
+   *
446
+   *                    A   (A shifted)   B   (B shifted)  IC
447
+   * Smoothie          0x2C (0x58)       0x2D (0x5A)       MCP4451
448
+   * AZTEEG_X3_PRO     0x2C (0x58)       0x2E (0x5C)       MCP4451
449
+   * MIGHTYBOARD_REVE  0x2F (0x5E)                         MCP4018
450
+   */
451
+  #define DIGIPOT_I2C_ADDRESS_A 0x2C  // unshifted slave address for first DIGIPOT
452
+  #define DIGIPOT_I2C_ADDRESS_B 0x2D  // unshifted slave address for second DIGIPOT
453
+#endif
454
+
428 455
 //#define DIGIPOT_MCP4018          // Requires library from https://github.com/stawel/SlowSoftI2CMaster
429 456
 #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4     AZTEEG_X3_PRO: 8
430 457
 // Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
@@ -452,6 +479,26 @@
452 479
 // On the Info Screen, display XY with one decimal place when possible
453 480
 //#define LCD_DECIMAL_SMALL_XY
454 481
 
482
+// The timeout (in ms) to return to the status screen from sub-menus
483
+//#define LCD_TIMEOUT_TO_STATUS 15000
484
+
485
+/**
486
+ * LED Control Menu
487
+ * Enable this feature to add LED Control to the LCD menu
488
+ */
489
+//#define LED_CONTROL_MENU
490
+#if ENABLED(LED_CONTROL_MENU)
491
+  #define LED_COLOR_PRESETS                 // Enable the Preset Color menu option
492
+  #if ENABLED(LED_COLOR_PRESETS)
493
+    #define LED_USER_PRESET_RED        255  // User defined RED value
494
+    #define LED_USER_PRESET_GREEN      128  // User defined GREEN value
495
+    #define LED_USER_PRESET_BLUE         0  // User defined BLUE value
496
+    #define LED_USER_PRESET_WHITE      255  // User defined WHITE value
497
+    #define LED_USER_PRESET_BRIGHTNESS 255  // User defined intensity
498
+    //#define LED_USER_PRESET_STARTUP       // Have the printer display the user preset color on startup
499
+  #endif
500
+#endif // LED_CONTROL_MENU
501
+
455 502
 #if ENABLED(SDSUPPORT)
456 503
 
457 504
   // Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -461,12 +508,14 @@
461 508
   // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
462 509
   #define SD_DETECT_INVERTED
463 510
 
464
-  #define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
511
+  #define SD_FINISHED_STEPPERRELEASE true          // Disable steppers when SD Print is finished
465 512
   #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
466 513
 
467
-  #define SDCARD_RATHERRECENTFIRST  //reverse file order of sd card menu display. Its sorted practically after the file system block order.
468
-  // if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that.
469
-  // using:
514
+  // Reverse SD sort to show "more recent" files first, according to the card's FAT.
515
+  // Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
516
+  #define SDCARD_RATHERRECENTFIRST
517
+
518
+  // Add an option in the menu to run all auto#.g files
470 519
   //#define MENU_ADDAUTOSTART
471 520
 
472 521
   /**
@@ -496,13 +545,15 @@
496 545
 
497 546
   // SD Card Sorting options
498 547
   #if ENABLED(SDCARD_SORT_ALPHA)
499
-    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256).
548
+    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256). Costs 27 bytes each.
500 549
     #define FOLDER_SORTING     -1     // -1=above  0=none  1=below
501 550
     #define SDSORT_GCODE       false  // Allow turning sorting on/off with LCD and M34 g-code.
502 551
     #define SDSORT_USES_RAM    false  // Pre-allocate a static array for faster pre-sorting.
503 552
     #define SDSORT_USES_STACK  false  // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
504 553
     #define SDSORT_CACHE_NAMES false  // Keep sorted items in RAM longer for speedy performance. Most expensive option.
505 554
     #define SDSORT_DYNAMIC_RAM false  // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
555
+    #define SDSORT_CACHE_VFATS 2      // Maximum number of 13-byte VFAT entries to use for sorting.
556
+                                      // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
506 557
   #endif
507 558
 
508 559
   // Show a progress bar on HD44780 LCDs for SD printing
@@ -521,14 +572,29 @@
521 572
     //#define LCD_PROGRESS_BAR_TEST
522 573
   #endif
523 574
 
575
+  // Add an 'M73' G-code to set the current percentage
576
+  //#define LCD_SET_PROGRESS_MANUALLY
577
+
524 578
   // This allows hosts to request long names for files and folders with M33
525 579
   //#define LONG_FILENAME_HOST_SUPPORT
526 580
 
527
-  // This option allows you to abort SD printing when any endstop is triggered.
528
-  // This feature must be enabled with "M540 S1" or from the LCD menu.
529
-  // To have any effect, endstops must be enabled during SD printing.
581
+  // Enable this option to scroll long filenames in the SD card menu
582
+  //#define SCROLL_LONG_FILENAMES
583
+
584
+  /**
585
+   * This option allows you to abort SD printing when any endstop is triggered.
586
+   * This feature must be enabled with "M540 S1" or from the LCD menu.
587
+   * To have any effect, endstops must be enabled during SD printing.
588
+   */
530 589
   //#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
531 590
 
591
+  /**
592
+   * This option makes it easier to print the same SD Card file again.
593
+   * On print completion the LCD Menu will open with the file selected.
594
+   * You can just click to start the print, or navigate elsewhere.
595
+   */
596
+  //#define SD_REPRINT_LAST_SELECTED_FILE
597
+
532 598
 #endif // SDSUPPORT
533 599
 
534 600
 /**
@@ -561,6 +627,10 @@
561 627
   // Enable this option and reduce the value to optimize screen updates.
562 628
   // The normal delay is 10µs. Use the lowest value that still gives a reliable display.
563 629
   //#define DOGM_SPI_DELAY_US 5
630
+
631
+  // Swap the CW/CCW indicators in the graphics overlay
632
+  //#define OVERLAY_GFX_REVERSE
633
+
564 634
 #endif // DOGLCD
565 635
 
566 636
 // @section safety
@@ -587,31 +657,18 @@
587 657
  */
588 658
 //#define BABYSTEPPING
589 659
 #if ENABLED(BABYSTEPPING)
590
-  #define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
591
-  #define BABYSTEP_INVERT_Z false  // Change if Z babysteps should go the other way
592
-  #define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
593
-  //#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
660
+  //#define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
661
+  #define BABYSTEP_INVERT_Z false    // Change if Z babysteps should go the other way
662
+  #define BABYSTEP_MULTIPLICATOR 1   // Babysteps are very small. Increase for faster motion.
663
+  //#define BABYSTEP_ZPROBE_OFFSET   // Enable to combine M851 and Babystepping
594 664
   //#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
595 665
   #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
596 666
                                         // Note: Extra time may be added to mitigate controller latency.
667
+  //#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
597 668
 #endif
598 669
 
599 670
 // @section extruder
600 671
 
601
-// extruder advance constant (s2/mm3)
602
-//
603
-// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
604
-//
605
-// Hooke's law says:    force = k * distance
606
-// Bernoulli's principle says:  v ^ 2 / 2 + g . h + pressure / density = constant
607
-// so: v ^ 2 is proportional to number of steps we advance the extruder
608
-//#define ADVANCE
609
-
610
-#if ENABLED(ADVANCE)
611
-  #define EXTRUDER_ADVANCE_K .0
612
-  #define D_FILAMENT 2.85
613
-#endif
614
-
615 672
 /**
616 673
  * Implementation of linear pressure control
617 674
  *
@@ -645,7 +702,7 @@
645 702
    *
646 703
    * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
647 704
    *
648
-   * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode.
705
+   * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
649 706
    * Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
650 707
    */
651 708
   #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
@@ -654,19 +711,18 @@
654 711
 
655 712
 // @section leveling
656 713
 
657
-// Default mesh area is an area with an inset margin on the print area.
658
-// Below are the macros that are used to define the borders for the mesh area,
659
-// made available here for specialized needs, ie dual extruder setup.
660
-#if ENABLED(MESH_BED_LEVELING)
661
-  #define MESH_MIN_X (X_MIN_POS + MESH_INSET)
662
-  #define MESH_MAX_X (X_MAX_POS - (MESH_INSET))
663
-  #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET)
664
-  #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET))
665
-#elif ENABLED(AUTO_BED_LEVELING_UBL)
666
-  #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET)
667
-  #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET))
668
-  #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET)
669
-  #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET))
714
+#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
715
+  #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
716
+#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
717
+  #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
718
+#endif
719
+
720
+#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
721
+  // Override the mesh area if the automatic (max) area is too large
722
+  //#define MESH_MIN_X MESH_INSET
723
+  //#define MESH_MIN_Y MESH_INSET
724
+  //#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
725
+  //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
670 726
 #endif
671 727
 
672 728
 // @section extras
@@ -686,7 +742,7 @@
686 742
 //#define BEZIER_CURVE_SUPPORT
687 743
 
688 744
 // G38.2 and G38.3 Probe Target
689
-// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
745
+// Set MULTIPLE_PROBING if you want G38 to double touch
690 746
 //#define G38_PROBE_TARGET
691 747
 #if ENABLED(G38_PROBE_TARGET)
692 748
   #define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
@@ -711,7 +767,7 @@
711 767
 // @section hidden
712 768
 
713 769
 // The number of linear motions that can be in the plan at any give time.
714
-// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
770
+// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
715 771
 #if ENABLED(SDSUPPORT)
716 772
   #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
717 773
 #else
@@ -724,7 +780,7 @@
724 780
 #define MAX_CMD_SIZE 96
725 781
 #define BUFSIZE 4
726 782
 
727
-// Transfer Buffer Size
783
+// Transmission to Host Buffer Size
728 784
 // To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0.
729 785
 // To buffer a simple "ok" you need 4 bytes.
730 786
 // For ADVANCED_OK (M105) you need 32 bytes.
@@ -733,6 +789,28 @@
733 789
 // :[0, 2, 4, 8, 16, 32, 64, 128, 256]
734 790
 #define TX_BUFFER_SIZE 0
735 791
 
792
+// Host Receive Buffer Size
793
+// Without XON/XOFF flow control (see SERIAL_XON_XOFF below) 32 bytes should be enough.
794
+// To use flow control, set this buffer size to at least 1024 bytes.
795
+// :[0, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048]
796
+//#define RX_BUFFER_SIZE 1024
797
+
798
+#if RX_BUFFER_SIZE >= 1024
799
+  // Enable to have the controller send XON/XOFF control characters to
800
+  // the host to signal the RX buffer is becoming full.
801
+  //#define SERIAL_XON_XOFF
802
+#endif
803
+
804
+#if ENABLED(SDSUPPORT)
805
+  // Enable this option to collect and display the maximum
806
+  // RX queue usage after transferring a file to SD.
807
+  //#define SERIAL_STATS_MAX_RX_QUEUED
808
+
809
+  // Enable this option to collect and display the number
810
+  // of dropped bytes after a file transfer to SD.
811
+  //#define SERIAL_STATS_DROPPED_RX
812
+#endif
813
+
736 814
 // Enable an emergency-command parser to intercept certain commands as they
737 815
 // enter the serial receive buffer, so they cannot be blocked.
738 816
 // Currently handles M108, M112, M410
@@ -748,27 +826,47 @@
748 826
 // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary.
749 827
 //#define ADVANCED_OK
750 828
 
751
-// @section fwretract
752
-
753
-// Firmware based and LCD controlled retract
754
-// M207 and M208 can be used to define parameters for the retraction.
755
-// The retraction can be called by the slicer using G10 and G11
756
-// until then, intended retractions can be detected by moves that only extrude and the direction.
757
-// the moves are than replaced by the firmware controlled ones.
829
+// @section extras
758 830
 
759
-//#define FWRETRACT  //ONLY PARTIALLY TESTED
831
+/**
832
+ * Firmware-based and LCD-controlled retract
833
+ *
834
+ * Add G10 / G11 commands for automatic firmware-based retract / recover.
835
+ * Use M207 and M208 to define parameters for retract / recover.
836
+ *
837
+ * Use M209 to enable or disable auto-retract.
838
+ * With auto-retract enabled, all G1 E moves within the set range
839
+ * will be converted to firmware-based retract/recover moves.
840
+ *
841
+ * Be sure to turn off auto-retract during filament change.
842
+ *
843
+ * Note that M207 / M208 / M209 settings are saved to EEPROM.
844
+ *
845
+ */
846
+//#define FWRETRACT  // ONLY PARTIALLY TESTED
760 847
 #if ENABLED(FWRETRACT)
761
-  #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
762
-  #define RETRACT_LENGTH 3               //default retract length (positive mm)
763
-  #define RETRACT_LENGTH_SWAP 13         //default swap retract length (positive mm), for extruder change
764
-  #define RETRACT_FEEDRATE 45            //default feedrate for retracting (mm/s)
765
-  #define RETRACT_ZLIFT 0                //default retract Z-lift
766
-  #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
767
-  #define RETRACT_RECOVER_LENGTH_SWAP 0  //default additional swap recover length (mm, added to retract length when recovering from extruder change)
768
-  #define RETRACT_RECOVER_FEEDRATE 8     //default feedrate for recovering from retraction (mm/s)
848
+  #define MIN_AUTORETRACT 0.1             // When auto-retract is on, convert E moves of this length and over
849
+  #define MAX_AUTORETRACT 10.0            // Upper limit for auto-retract conversion
850
+  #define RETRACT_LENGTH 3                // Default retract length (positive mm)
851
+  #define RETRACT_LENGTH_SWAP 13          // Default swap retract length (positive mm), for extruder change
852
+  #define RETRACT_FEEDRATE 45             // Default feedrate for retracting (mm/s)
853
+  #define RETRACT_ZLIFT 0                 // Default retract Z-lift
854
+  #define RETRACT_RECOVER_LENGTH 0        // Default additional recover length (mm, added to retract length when recovering)
855
+  #define RETRACT_RECOVER_LENGTH_SWAP 0   // Default additional swap recover length (mm, added to retract length when recovering from extruder change)
856
+  #define RETRACT_RECOVER_FEEDRATE 8      // Default feedrate for recovering from retraction (mm/s)
857
+  #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
769 858
 #endif
770 859
 
771 860
 /**
861
+ * Extra Fan Speed
862
+ * Adds a secondary fan speed for each print-cooling fan.
863
+ *   'M106 P<fan> T3-255' : Set a secondary speed for <fan>
864
+ *   'M106 P<fan> T2'     : Use the set secondary speed
865
+ *   'M106 P<fan> T1'     : Restore the previous fan speed
866
+ */
867
+//#define EXTRA_FAN_SPEED
868
+
869
+/**
772 870
  * Advanced Pause
773 871
  * Experimental feature for filament change support and for parking the nozzle when paused.
774 872
  * Adds the GCode M600 for initiating filament change.
@@ -878,7 +976,7 @@
878 976
 
879 977
 #endif
880 978
 
881
-// @section TMC2130
979
+// @section TMC2130, TMC2208
882 980
 
883 981
 /**
884 982
  * Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
@@ -892,7 +990,19 @@
892 990
  */
893 991
 //#define HAVE_TMC2130
894 992
 
895
-#if ENABLED(HAVE_TMC2130)
993
+/**
994
+ * Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
995
+ * Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
996
+ * To use the reading capabilities, also connect #_SERIAL_RX_PIN
997
+ * to #_SERIAL_TX_PIN with a 1K resistor.
998
+ * The drivers can also be used with hardware serial.
999
+ *
1000
+ * You'll also need the TMC2208Stepper Arduino library
1001
+ * (https://github.com/teemuatlut/TMC2208Stepper).
1002
+ */
1003
+//#define HAVE_TMC2208
1004
+
1005
+#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
896 1006
 
897 1007
   // CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
898 1008
   //#define X_IS_TMC2130
@@ -907,46 +1017,58 @@
907 1017
   //#define E3_IS_TMC2130
908 1018
   //#define E4_IS_TMC2130
909 1019
 
1020
+  //#define X_IS_TMC2208
1021
+  //#define X2_IS_TMC2208
1022
+  //#define Y_IS_TMC2208
1023
+  //#define Y2_IS_TMC2208
1024
+  //#define Z_IS_TMC2208
1025
+  //#define Z2_IS_TMC2208
1026
+  //#define E0_IS_TMC2208
1027
+  //#define E1_IS_TMC2208
1028
+  //#define E2_IS_TMC2208
1029
+  //#define E3_IS_TMC2208
1030
+  //#define E4_IS_TMC2208
1031
+
910 1032
   /**
911 1033
    * Stepper driver settings
912 1034
    */
913 1035
 
914 1036
   #define R_SENSE           0.11  // R_sense resistor for SilentStepStick2130
915 1037
   #define HOLD_MULTIPLIER    0.5  // Scales down the holding current from run current
916
-  #define INTERPOLATE          1  // Interpolate X/Y/Z_MICROSTEPS to 256
1038
+  #define INTERPOLATE       true  // Interpolate X/Y/Z_MICROSTEPS to 256
917 1039
 
918
-  #define X_CURRENT         1000  // rms current in mA. Multiply by 1.41 for peak current.
1040
+  #define X_CURRENT          800  // rms current in mA. Multiply by 1.41 for peak current.
919 1041
   #define X_MICROSTEPS        16  // 0..256
920 1042
 
921
-  #define Y_CURRENT         1000
1043
+  #define Y_CURRENT          800
922 1044
   #define Y_MICROSTEPS        16
923 1045
 
924
-  #define Z_CURRENT         1000
1046
+  #define Z_CURRENT          800
925 1047
   #define Z_MICROSTEPS        16
926 1048
 
927
-  //#define X2_CURRENT      1000
928
-  //#define X2_MICROSTEPS     16
1049
+  #define X2_CURRENT         800
1050
+  #define X2_MICROSTEPS       16
929 1051
 
930
-  //#define Y2_CURRENT      1000
931
-  //#define Y2_MICROSTEPS     16
1052
+  #define Y2_CURRENT         800
1053
+  #define Y2_MICROSTEPS       16
932 1054
 
933
-  //#define Z2_CURRENT      1000
934
-  //#define Z2_MICROSTEPS     16
1055
+  #define Z2_CURRENT         800
1056
+  #define Z2_MICROSTEPS       16
935 1057
 
936
-  //#define E0_CURRENT      1000
937
-  //#define E0_MICROSTEPS     16
1058
+  #define E0_CURRENT         800
1059
+  #define E0_MICROSTEPS       16
938 1060
 
939
-  //#define E1_CURRENT      1000
940
-  //#define E1_MICROSTEPS     16
1061
+  #define E1_CURRENT         800
1062
+  #define E1_MICROSTEPS       16
941 1063
 
942
-  //#define E2_CURRENT      1000
943
-  //#define E2_MICROSTEPS     16
1064
+  #define E2_CURRENT         800
1065
+  #define E2_MICROSTEPS       16
944 1066
 
945
-  //#define E3_CURRENT      1000
946
-  //#define E3_MICROSTEPS     16
1067
+  #define E3_CURRENT         800
1068
+  #define E3_MICROSTEPS       16
947 1069
 
948
-  //#define E4_CURRENT      1000
949
-  //#define E4_MICROSTEPS     16
1070
+  #define E4_CURRENT         800
1071
+  #define E4_MICROSTEPS       16
950 1072
 
951 1073
   /**
952 1074
    * Use Trinamic's ultra quiet stepping mode.
@@ -955,24 +1077,22 @@
955 1077
   #define STEALTHCHOP
956 1078
 
957 1079
   /**
958
-   * Let Marlin automatically control stepper current.
959
-   * This is still an experimental feature.
960
-   * Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
961
-   * then decrease current by CURRENT_STEP until temperature prewarn is cleared.
962
-   * Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
1080
+   * Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
1081
+   * like overtemperature and short to ground. TMC2208 requires hardware serial.
1082
+   * In the case of overtemperature Marlin can decrease the driver current until error condition clears.
1083
+   * Other detected conditions can be used to stop the current print.
963 1084
    * Relevant g-codes:
964 1085
    * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
965
-   * M906 S1 - Start adjusting current
966
-   * M906 S0 - Stop adjusting current
967 1086
    * M911 - Report stepper driver overtemperature pre-warn condition.
968 1087
    * M912 - Clear stepper driver overtemperature pre-warn condition flag.
1088
+   * M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
969 1089
    */
970
-  //#define AUTOMATIC_CURRENT_CONTROL
1090
+  //#define MONITOR_DRIVER_STATUS
971 1091
 
972
-  #if ENABLED(AUTOMATIC_CURRENT_CONTROL)
973
-    #define CURRENT_STEP          50  // [mA]
974
-    #define AUTO_ADJUST_MAX     1300  // [mA], 1300mA_rms = 1840mA_peak
1092
+  #if ENABLED(MONITOR_DRIVER_STATUS)
1093
+    #define CURRENT_STEP_DOWN     50  // [mA]
975 1094
     #define REPORT_CURRENT_CHANGE
1095
+    #define STOP_ON_ERROR
976 1096
   #endif
977 1097
 
978 1098
   /**
@@ -987,8 +1107,8 @@
987 1107
   #define X2_HYBRID_THRESHOLD    100
988 1108
   #define Y_HYBRID_THRESHOLD     100
989 1109
   #define Y2_HYBRID_THRESHOLD    100
990
-  #define Z_HYBRID_THRESHOLD       4
991
-  #define Z2_HYBRID_THRESHOLD      4
1110
+  #define Z_HYBRID_THRESHOLD       3
1111
+  #define Z2_HYBRID_THRESHOLD      3
992 1112
   #define E0_HYBRID_THRESHOLD     30
993 1113
   #define E1_HYBRID_THRESHOLD     30
994 1114
   #define E2_HYBRID_THRESHOLD     30
@@ -998,7 +1118,7 @@
998 1118
   /**
999 1119
    * Use stallGuard2 to sense an obstacle and trigger an endstop.
1000 1120
    * You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
1001
-   * If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
1121
+   * X and Y homing will always be done in spreadCycle mode.
1002 1122
    *
1003 1123
    * X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
1004 1124
    * Higher values make the system LESS sensitive.
@@ -1007,27 +1127,34 @@
1007 1127
    * It is advised to set X/Y_HOME_BUMP_MM to 0.
1008 1128
    * M914 X/Y to live tune the setting
1009 1129
    */
1010
-  //#define SENSORLESS_HOMING
1130
+  //#define SENSORLESS_HOMING // TMC2130 only
1011 1131
 
1012 1132
   #if ENABLED(SENSORLESS_HOMING)
1013
-    #define X_HOMING_SENSITIVITY  19
1014
-    #define Y_HOMING_SENSITIVITY  19
1133
+    #define X_HOMING_SENSITIVITY  8
1134
+    #define Y_HOMING_SENSITIVITY  8
1015 1135
   #endif
1016 1136
 
1017 1137
   /**
1138
+   * Enable M122 debugging command for TMC stepper drivers.
1139
+   * M122 S0/1 will enable continous reporting.
1140
+   */
1141
+  //#define TMC_DEBUG
1142
+
1143
+  /**
1018 1144
    * You can set your own advanced settings by filling in predefined functions.
1019 1145
    * A list of available functions can be found on the library github page
1020 1146
    * https://github.com/teemuatlut/TMC2130Stepper
1147
+   * https://github.com/teemuatlut/TMC2208Stepper
1021 1148
    *
1022 1149
    * Example:
1023
-   * #define TMC2130_ADV() { \
1150
+   * #define TMC_ADV() { \
1024 1151
    *   stepperX.diag0_temp_prewarn(1); \
1025
-   *   stepperX.interpolate(0); \
1152
+   *   stepperY.interpolate(0); \
1026 1153
    * }
1027 1154
    */
1028
-  #define  TMC2130_ADV() {  }
1155
+  #define  TMC_ADV() {  }
1029 1156
 
1030
-#endif // HAVE_TMC2130
1157
+#endif // TMC2130 || TMC2208
1031 1158
 
1032 1159
 // @section L6470
1033 1160
 
@@ -1192,6 +1319,48 @@
1192 1319
 #endif
1193 1320
 
1194 1321
 /**
1322
+ * Filament Width Sensor
1323
+ *
1324
+ * Measures the filament width in real-time and adjusts
1325
+ * flow rate to compensate for any irregularities.
1326
+ *
1327
+ * Also allows the measured filament diameter to set the
1328
+ * extrusion rate, so the slicer only has to specify the
1329
+ * volume.
1330
+ *
1331
+ * Only a single extruder is supported at this time.
1332
+ *
1333
+ *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1334
+ *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1335
+ * 301 RAMBO       : Analog input 3
1336
+ *
1337
+ * Note: May require analog pins to be defined for other boards.
1338
+ */
1339
+//#define FILAMENT_WIDTH_SENSOR
1340
+
1341
+#if ENABLED(FILAMENT_WIDTH_SENSOR)
1342
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
1343
+  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1344
+
1345
+  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1346
+  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1347
+  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1348
+
1349
+  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1350
+
1351
+  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1352
+  //#define FILAMENT_LCD_DISPLAY
1353
+#endif
1354
+
1355
+/**
1356
+ * CNC Coordinate Systems
1357
+ *
1358
+ * Enables G53 and G54-G59.3 commands to select coordinate systems
1359
+ * and G92.1 to reset the workspace to native machine space.
1360
+ */
1361
+//#define CNC_COORDINATE_SYSTEMS
1362
+
1363
+/**
1195 1364
  * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
1196 1365
  */
1197 1366
 //#define PINS_DEBUGGING
@@ -1244,6 +1413,8 @@
1244 1413
 //#define CUSTOM_USER_MENUS
1245 1414
 #if ENABLED(CUSTOM_USER_MENUS)
1246 1415
   #define USER_SCRIPT_DONE "M117 User Script Done"
1416
+  #define USER_SCRIPT_AUDIBLE_FEEDBACK
1417
+  //#define USER_SCRIPT_RETURN  // Return to status screen after a script
1247 1418
 
1248 1419
   #define USER_DESC_1 "Home & UBL Info"
1249 1420
   #define USER_GCODE_1 "G28\nG29 W"
@@ -1271,6 +1442,7 @@
1271 1442
 //===========================================================================
1272 1443
 //====================== I2C Position Encoder Settings ======================
1273 1444
 //===========================================================================
1445
+
1274 1446
 /**
1275 1447
  *  I2C position encoders for closed loop control.
1276 1448
  *  Developed by Chris Barr at Aus3D.
@@ -1351,4 +1523,45 @@
1351 1523
 
1352 1524
 #endif // I2C_POSITION_ENCODERS
1353 1525
 
1526
+/**
1527
+ * MAX7219 Debug Matrix
1528
+ *
1529
+ * Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
1530
+ * display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
1531
+ *
1532
+ * Fully assembled MAX7219 boards can be found on the internet for under $2(US).
1533
+ * For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
1534
+ */
1535
+//#define MAX7219_DEBUG
1536
+#if ENABLED(MAX7219_DEBUG)
1537
+  #define MAX7219_CLK_PIN   64  // 77 on Re-ARM       // Configuration of the 3 pins to control the display
1538
+  #define MAX7219_DIN_PIN   57  // 78 on Re-ARM
1539
+  #define MAX7219_LOAD_PIN  44  // 79 on Re-ARM
1540
+
1541
+  /**
1542
+   * Sample debug features
1543
+   * If you add more debug displays, be careful to avoid conflicts!
1544
+   */
1545
+  #define MAX7219_DEBUG_PRINTER_ALIVE    // Blink corner LED of 8x8 matrix to show that the firmware is functioning
1546
+  #define MAX7219_DEBUG_STEPPER_HEAD  3  // Show the stepper queue head position on this and the next LED matrix row
1547
+  #define MAX7219_DEBUG_STEPPER_TAIL  5  // Show the stepper queue tail position on this and the next LED matrix row
1548
+
1549
+  #define MAX7219_DEBUG_STEPPER_QUEUE 0  // Show the current stepper queue depth on this and the next LED matrix row
1550
+                                         // If you experience stuttering, reboots, etc. this option can reveal how
1551
+                                         // tweaks made to the configuration are affecting the printer in real-time.
1552
+#endif
1553
+
1554
+/**
1555
+ * NanoDLP Sync support
1556
+ *
1557
+ * Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
1558
+ * string to enable synchronization with DLP projector exposure. This change will allow to use
1559
+ * [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
1560
+ */
1561
+//#define NANODLP_Z_SYNC
1562
+#if ENABLED(NANODLP_Z_SYNC)
1563
+  //#define NANODLP_ALL_AXIS  // Enables "Z_move_comp" output on any axis move.
1564
+                              // Default behaviour is limited to Z axis only.
1565
+#endif
1566
+
1354 1567
 #endif // CONFIGURATION_ADV_H

+ 247
- 102
Marlin/example_configurations/Felix/DUAL/Configuration.h 파일 보기

@@ -37,7 +37,7 @@
37 37
  */
38 38
 #ifndef CONFIGURATION_H
39 39
 #define CONFIGURATION_H
40
-#define CONFIGURATION_H_VERSION 010100
40
+#define CONFIGURATION_H_VERSION 010107
41 41
 
42 42
 //===========================================================================
43 43
 //============================= Getting Started =============================
@@ -74,7 +74,7 @@
74 74
 // User-specified version info of this build to display in [Pronterface, etc] terminal window during
75 75
 // startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
76 76
 // build by the user have been successfully uploaded into firmware.
77
-#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
77
+#define STRING_CONFIG_H_AUTHOR "(none, Felix/DUAL)" // Who made the changes.
78 78
 #define SHOW_BOOTSCREEN
79 79
 #define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
80 80
 #define STRING_SPLASH_LINE2 WEBSITE_URL         // will be shown during bootup in line 2
@@ -107,8 +107,9 @@
107 107
  *
108 108
  * 250000 works in most cases, but you might try a lower speed if
109 109
  * you commonly experience drop-outs during host printing.
110
+ * You may try up to 1000000 to speed up SD file transfer.
110 111
  *
111
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
112
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
112 113
  */
113 114
 #define BAUDRATE 250000
114 115
 
@@ -135,6 +136,9 @@
135 136
 // :[1, 2, 3, 4, 5]
136 137
 #define EXTRUDERS 2
137 138
 
139
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
140
+#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
141
+
138 142
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
139 143
 //#define SINGLENOZZLE
140 144
 
@@ -161,7 +165,10 @@
161 165
 //#define SWITCHING_EXTRUDER
162 166
 #if ENABLED(SWITCHING_EXTRUDER)
163 167
   #define SWITCHING_EXTRUDER_SERVO_NR 0
164
-  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1
168
+  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3]
169
+  #if EXTRUDERS > 3
170
+    #define SWITCHING_EXTRUDER_E23_SERVO_NR 1
171
+  #endif
165 172
 #endif
166 173
 
167 174
 // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles
@@ -173,6 +180,21 @@
173 180
 #endif
174 181
 
175 182
 /**
183
+ * Two separate X-carriages with extruders that connect to a moving part
184
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
185
+ */
186
+//#define PARKING_EXTRUDER
187
+#if ENABLED(PARKING_EXTRUDER)
188
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
189
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
190
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
191
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
192
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
193
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
194
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
195
+#endif
196
+
197
+/**
176 198
  * "Mixing Extruder"
177 199
  *   - Adds a new code, M165, to set the current mix factors.
178 200
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -317,8 +339,9 @@
317 339
 
318 340
 // Comment the following line to disable PID and enable bang-bang.
319 341
 #define PIDTEMP
320
-#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
321
-#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
342
+#define BANG_MAX 255     // Limits current to nozzle while in bang-bang mode; 255=full current
343
+#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
344
+#define PID_K1 0.95      // Smoothing factor within the PID
322 345
 #if ENABLED(PIDTEMP)
323 346
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
324 347
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -328,7 +351,6 @@
328 351
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
329 352
   #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
330 353
                                   // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
331
-  #define K1 0.95 //smoothing factor within the PID
332 354
 
333 355
   // Felix 2.0+ electronics with v4 Hotend
334 356
   #define DEFAULT_Kp 12
@@ -390,12 +412,13 @@
390 412
 //===========================================================================
391 413
 
392 414
 /**
393
- * Thermal Protection protects your printer from damage and fire if a
394
- * thermistor falls out or temperature sensors fail in any way.
415
+ * Thermal Protection provides additional protection to your printer from damage
416
+ * and fire. Marlin always includes safe min and max temperature ranges which
417
+ * protect against a broken or disconnected thermistor wire.
395 418
  *
396
- * The issue: If a thermistor falls out or a temperature sensor fails,
397
- * Marlin can no longer sense the actual temperature. Since a disconnected
398
- * thermistor reads as a low temperature, the firmware will keep the heater on.
419
+ * The issue: If a thermistor falls out, it will report the much lower
420
+ * temperature of the air in the room, and the the firmware will keep
421
+ * the heater on.
399 422
  *
400 423
  * If you get "Thermal Runaway" or "Heating failed" errors the
401 424
  * details can be tuned in Configuration_adv.h
@@ -536,7 +559,7 @@
536 559
 // @section probes
537 560
 
538 561
 //
539
-// See http://marlinfw.org/configuration/probes.html
562
+// See http://marlinfw.org/docs/configuration/probes.html
540 563
 //
541 564
 
542 565
 /**
@@ -602,14 +625,15 @@
602 625
 #endif
603 626
 
604 627
 /**
605
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
606
- * options selected below - will be disabled during probing so as to minimize
607
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
608
- * in current flowing through the wires).  This is likely most useful to users of the
609
- * BLTouch probe, but may also help those with inductive or other probe types.
628
+ * Enable one or more of the following if probing seems unreliable.
629
+ * Heaters and/or fans can be disabled during probing to minimize electrical
630
+ * noise. A delay can also be added to allow noise and vibration to settle.
631
+ * These options are most useful for the BLTouch probe, but may also improve
632
+ * readings with inductive probes and piezo sensors.
610 633
  */
611 634
 //#define PROBING_HEATERS_OFF       // Turn heaters off when probing
612 635
 //#define PROBING_FANS_OFF          // Turn fans off when probing
636
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
613 637
 
614 638
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
615 639
 //#define SOLENOID_PROBE
@@ -648,14 +672,16 @@
648 672
 // X and Y axis travel speed (mm/m) between probes
649 673
 #define XY_PROBE_SPEED 8000
650 674
 
651
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
675
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
652 676
 #define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
653 677
 
654 678
 // Speed for the "accurate" probe of each point
655 679
 #define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
656 680
 
657
-// Use double touch for probing
658
-//#define PROBE_DOUBLE_TOUCH
681
+// The number of probes to perform at each point.
682
+//   Set to 2 for a fast/slow probe, using the second probe result.
683
+//   Set to 3 or more for slow probes, averaging the results.
684
+//#define MULTIPLE_PROBING 2
659 685
 
660 686
 /**
661 687
  * Z probes require clearance when deploying, stowing, and moving between
@@ -722,6 +748,8 @@
722 748
 
723 749
 // @section homing
724 750
 
751
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
752
+
725 753
 //#define Z_HOMING_HEIGHT 4  // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
726 754
                              // Be sure you have this distance over your Z_MAX_POS in case.
727 755
 
@@ -733,18 +761,42 @@
733 761
 
734 762
 // @section machine
735 763
 
736
-// Travel limits after homing (units are in mm)
764
+// The size of the print bed
765
+#define X_BED_SIZE 255
766
+#define Y_BED_SIZE 205
767
+
768
+// Travel limits (mm) after homing, corresponding to endstop positions.
737 769
 #define X_MIN_POS 0
738 770
 #define Y_MIN_POS 0
739 771
 #define Z_MIN_POS 0
740
-#define X_MAX_POS 255
741
-#define Y_MAX_POS 205
772
+#define X_MAX_POS X_BED_SIZE
773
+#define Y_MAX_POS Y_BED_SIZE
742 774
 #define Z_MAX_POS 235
743 775
 
744
-// If enabled, axes won't move below MIN_POS in response to movement commands.
776
+/**
777
+ * Software Endstops
778
+ *
779
+ * - Prevent moves outside the set machine bounds.
780
+ * - Individual axes can be disabled, if desired.
781
+ * - X and Y only apply to Cartesian robots.
782
+ * - Use 'M211' to set software endstops on/off or report current state
783
+ */
784
+
785
+// Min software endstops curtail movement below minimum coordinate bounds
745 786
 #define MIN_SOFTWARE_ENDSTOPS
746
-// If enabled, axes won't move above MAX_POS in response to movement commands.
787
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
788
+  #define MIN_SOFTWARE_ENDSTOP_X
789
+  #define MIN_SOFTWARE_ENDSTOP_Y
790
+  #define MIN_SOFTWARE_ENDSTOP_Z
791
+#endif
792
+
793
+// Max software endstops curtail movement above maximum coordinate bounds
747 794
 #define MAX_SOFTWARE_ENDSTOPS
795
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
796
+  #define MAX_SOFTWARE_ENDSTOP_X
797
+  #define MAX_SOFTWARE_ENDSTOP_Y
798
+  #define MAX_SOFTWARE_ENDSTOP_Z
799
+#endif
748 800
 
749 801
 /**
750 802
  * Filament Runout Sensor
@@ -764,7 +816,7 @@
764 816
 //===========================================================================
765 817
 //=============================== Bed Leveling ==============================
766 818
 //===========================================================================
767
-// @section bedlevel
819
+// @section calibrate
768 820
 
769 821
 /**
770 822
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -790,12 +842,7 @@
790 842
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
791 843
  *   A comprehensive bed leveling system combining the features and benefits
792 844
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
793
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
794
- *   for Cartesian Printers. That said, it was primarily designed to correct
795
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
796
- *   please post an issue if something doesn't work correctly. Initially,
797
- *   you will need to set a reduced bed size so you have a rectangular area
798
- *   to test on.
845
+ *   Validation and Mesh Editing systems.
799 846
  *
800 847
  * - MESH_BED_LEVELING
801 848
  *   Probe a grid manually
@@ -822,6 +869,24 @@
822 869
   // at which point movement will be level to the machine's XY plane.
823 870
   // The height can be set with M420 Z<height>
824 871
   #define ENABLE_LEVELING_FADE_HEIGHT
872
+
873
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
874
+  // split up moves into short segments like a Delta. This follows the
875
+  // contours of the bed more closely than edge-to-edge straight moves.
876
+  #define SEGMENT_LEVELED_MOVES
877
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
878
+
879
+  /**
880
+   * Enable the G26 Mesh Validation Pattern tool.
881
+   */
882
+  //#define G26_MESH_VALIDATION   // Enable G26 mesh validation
883
+  #if ENABLED(G26_MESH_VALIDATION)
884
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
885
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
886
+    #define MESH_TEST_HOTEND_TEMP   205.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
887
+    #define MESH_TEST_BED_TEMP       60.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
888
+  #endif
889
+
825 890
 #endif
826 891
 
827 892
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -877,7 +942,9 @@
877 942
   //========================= Unified Bed Leveling ============================
878 943
   //===========================================================================
879 944
 
880
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
945
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
946
+
947
+  #define MESH_INSET 1              // Mesh inset margin on print area
881 948
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
882 949
   #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
883 950
 
@@ -888,8 +955,8 @@
888 955
   #define UBL_PROBE_PT_3_X 180
889 956
   #define UBL_PROBE_PT_3_Y 20
890 957
 
891
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
892 958
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
959
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
893 960
 
894 961
 #elif ENABLED(MESH_BED_LEVELING)
895 962
 
@@ -916,6 +983,9 @@
916 983
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
917 984
 #endif
918 985
 
986
+// Add a menu item to move between bed corners for manual bed adjustment
987
+//#define LEVEL_BED_CORNERS
988
+
919 989
 /**
920 990
  * Commands to execute at the end of G29 probing.
921 991
  * Useful to retract or move the Z probe out of the way.
@@ -946,14 +1016,71 @@
946 1016
 //#define Z_SAFE_HOMING
947 1017
 
948 1018
 #if ENABLED(Z_SAFE_HOMING)
949
-  #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
950
-  #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
1019
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1020
+  #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2)    // Y point for Z homing when homing all axes (G28).
951 1021
 #endif
952 1022
 
953 1023
 // Homing speeds (mm/m)
954 1024
 #define HOMING_FEEDRATE_XY (50*60)
955 1025
 #define HOMING_FEEDRATE_Z  (4*60)
956 1026
 
1027
+// @section calibrate
1028
+
1029
+/**
1030
+ * Bed Skew Compensation
1031
+ *
1032
+ * This feature corrects for misalignment in the XYZ axes.
1033
+ *
1034
+ * Take the following steps to get the bed skew in the XY plane:
1035
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1036
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1037
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1038
+ *  4. For XY_SIDE_AD measure the edge A to D
1039
+ *
1040
+ * Marlin automatically computes skew factors from these measurements.
1041
+ * Skew factors may also be computed and set manually:
1042
+ *
1043
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1044
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1045
+ *
1046
+ * If desired, follow the same procedure for XZ and YZ.
1047
+ * Use these diagrams for reference:
1048
+ *
1049
+ *    Y                     Z                     Z
1050
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1051
+ *    |    /       /        |    /       /        |    /       /
1052
+ *    |   /       /         |   /       /         |   /       /
1053
+ *    |  A-------D          |  A-------D          |  A-------D
1054
+ *    +-------------->X     +-------------->X     +-------------->Y
1055
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1056
+ */
1057
+//#define SKEW_CORRECTION
1058
+
1059
+#if ENABLED(SKEW_CORRECTION)
1060
+  // Input all length measurements here:
1061
+  #define XY_DIAG_AC 282.8427124746
1062
+  #define XY_DIAG_BD 282.8427124746
1063
+  #define XY_SIDE_AD 200
1064
+
1065
+  // Or, set the default skew factors directly here
1066
+  // to override the above measurements:
1067
+  #define XY_SKEW_FACTOR 0.0
1068
+
1069
+  //#define SKEW_CORRECTION_FOR_Z
1070
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1071
+    #define XZ_DIAG_AC 282.8427124746
1072
+    #define XZ_DIAG_BD 282.8427124746
1073
+    #define YZ_DIAG_AC 282.8427124746
1074
+    #define YZ_DIAG_BD 282.8427124746
1075
+    #define YZ_SIDE_AD 200
1076
+    #define XZ_SKEW_FACTOR 0.0
1077
+    #define YZ_SKEW_FACTOR 0.0
1078
+  #endif
1079
+
1080
+  // Enable this option for M852 to set skew at runtime
1081
+  //#define SKEW_CORRECTION_GCODE
1082
+#endif
1083
+
957 1084
 //=============================================================================
958 1085
 //============================= Additional Features ===========================
959 1086
 //=============================================================================
@@ -980,11 +1107,12 @@
980 1107
 //
981 1108
 #define HOST_KEEPALIVE_FEATURE        // Disable this if your host doesn't like keepalive messages
982 1109
 #define DEFAULT_KEEPALIVE_INTERVAL 2  // Number of seconds between "busy" messages. Set with M113.
1110
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
983 1111
 
984 1112
 //
985 1113
 // M100 Free Memory Watcher
986 1114
 //
987
-//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1115
+//#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
988 1116
 
989 1117
 //
990 1118
 // G20/G21 Inch mode support
@@ -1129,13 +1257,13 @@
1129 1257
  *
1130 1258
  * Select the language to display on the LCD. These languages are available:
1131 1259
  *
1132
- *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
1133
- *    it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
1134
- *    zh_CN, zh_TW, test
1260
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1261
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1262
+ *    tr, uk, zh_CN, zh_TW, test
1135 1263
  *
1136
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1264
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1137 1265
  */
1138
-//#define LCD_LANGUAGE en
1266
+#define LCD_LANGUAGE en
1139 1267
 
1140 1268
 /**
1141 1269
  * LCD Character Set
@@ -1155,7 +1283,7 @@
1155 1283
  *  - Click the controller to view the LCD menu
1156 1284
  *  - The LCD will display Japanese, Western, or Cyrillic text
1157 1285
  *
1158
- * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1286
+ * See http://marlinfw.org/docs/development/lcd_language.html
1159 1287
  *
1160 1288
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1161 1289
  */
@@ -1261,8 +1389,8 @@
1261 1389
 // Note: Test audio output with the G-Code:
1262 1390
 //  M300 S<frequency Hz> P<duration ms>
1263 1391
 //
1264
-//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
1265
-//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
1392
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
1393
+//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
1266 1394
 
1267 1395
 //
1268 1396
 // CONTROLLER TYPE: Standard
@@ -1370,11 +1498,13 @@
1370 1498
 //#define CARTESIO_UI
1371 1499
 
1372 1500
 //
1373
-// ANET_10 Controller supported displays.
1501
+// ANET and Tronxy Controller supported displays.
1374 1502
 //
1375
-//#define ANET_KEYPAD_LCD         // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1503
+//#define ZONESTAR_LCD            // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1376 1504
                                   // This LCD is known to be susceptible to electrical interference
1377 1505
                                   // which scrambles the display.  Pressing any button clears it up.
1506
+                                  // This is a LCD2004 display with 5 analog buttons.
1507
+
1378 1508
 //#define ANET_FULL_GRAPHICS_LCD  // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1379 1509
                                   // A clone of the RepRapDiscount full graphics display but with
1380 1510
                                   // different pins/wiring (see pins_ANET_10.h).
@@ -1434,11 +1564,6 @@
1434 1564
 //#define U8GLIB_SSD1306
1435 1565
 
1436 1566
 //
1437
-// TinyBoy2 128x64 OLED / Encoder Panel
1438
-//
1439
-//#define OLED_PANEL_TINYBOY2
1440
-
1441
-//
1442 1567
 // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules
1443 1568
 //
1444 1569
 //#define SAV_3DGLCD
@@ -1455,6 +1580,45 @@
1455 1580
 //
1456 1581
 //#define SAV_3DLCD
1457 1582
 
1583
+//
1584
+// TinyBoy2 128x64 OLED / Encoder Panel
1585
+//
1586
+//#define OLED_PANEL_TINYBOY2
1587
+
1588
+//
1589
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1590
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1591
+//
1592
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1593
+
1594
+//
1595
+// MKS MINI12864 with graphic controller and SD support
1596
+// http://reprap.org/wiki/MKS_MINI_12864
1597
+//
1598
+//#define MKS_MINI_12864
1599
+
1600
+//
1601
+// Factory display for Creality CR-10
1602
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1603
+//
1604
+// This is RAMPS-compatible using a single 10-pin connector.
1605
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1606
+//
1607
+//#define CR10_STOCKDISPLAY
1608
+
1609
+//
1610
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1611
+// http://reprap.org/wiki/MKS_12864OLED
1612
+//
1613
+// Tiny, but very sharp OLED display
1614
+//
1615
+//#define MKS_12864OLED
1616
+
1617
+// Silvergate GLCD controller
1618
+// http://github.com/android444/Silvergate
1619
+//
1620
+//#define SILVER_GATE_GLCD_CONTROLLER
1621
+
1458 1622
 //=============================================================================
1459 1623
 //=============================== Extra Features ==============================
1460 1624
 //=============================================================================
@@ -1511,16 +1675,22 @@
1511 1675
  * Adds the M150 command to set the LED (or LED strip) color.
1512 1676
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1513 1677
  * luminance values can be set from 0 to 255.
1678
+ * For Neopixel LED an overall brightness parameter is also available.
1514 1679
  *
1515 1680
  * *** CAUTION ***
1516 1681
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1517 1682
  *  as the Arduino cannot handle the current the LEDs will require.
1518 1683
  *  Failure to follow this precaution can destroy your Arduino!
1684
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1685
+ *  more current than the Arduino 5V linear regulator can produce.
1519 1686
  * *** CAUTION ***
1520 1687
  *
1688
+ * LED Type. Enable only one of the following two options.
1689
+ *
1521 1690
  */
1522 1691
 //#define RGB_LED
1523 1692
 //#define RGBW_LED
1693
+
1524 1694
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1525 1695
   #define RGB_LED_R_PIN 34
1526 1696
   #define RGB_LED_G_PIN 43
@@ -1528,6 +1698,17 @@
1528 1698
   #define RGB_LED_W_PIN -1
1529 1699
 #endif
1530 1700
 
1701
+// Support for Adafruit Neopixel LED driver
1702
+//#define NEOPIXEL_LED
1703
+#if ENABLED(NEOPIXEL_LED)
1704
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1705
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1706
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1707
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1708
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1709
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1710
+#endif
1711
+
1531 1712
 /**
1532 1713
  * Printer Event LEDs
1533 1714
  *
@@ -1539,68 +1720,32 @@
1539 1720
  *  - Change to green once print has finished
1540 1721
  *  - Turn off after the print has finished and the user has pushed a button
1541 1722
  */
1542
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)
1723
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1543 1724
   #define PRINTER_EVENT_LEDS
1544 1725
 #endif
1545 1726
 
1546
-/*********************************************************************\
1547
-* R/C SERVO support
1548
-* Sponsored by TrinityLabs, Reworked by codexmas
1549
-**********************************************************************/
1727
+/**
1728
+ * R/C SERVO support
1729
+ * Sponsored by TrinityLabs, Reworked by codexmas
1730
+ */
1550 1731
 
1551
-// Number of servos
1552
-//
1553
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1554
-// set it manually if you have more servos than extruders and wish to manually control some
1555
-// leaving it undefined or defining as 0 will disable the servo subsystem
1556
-// If unsure, leave commented / disabled
1557
-//
1732
+/**
1733
+ * Number of servos
1734
+ *
1735
+ * For some servo-related options NUM_SERVOS will be set automatically.
1736
+ * Set this manually if there are extra servos needing manual control.
1737
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1738
+ */
1558 1739
 //#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
1559 1740
 
1560 1741
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1561 1742
 // 300ms is a good value but you can try less delay.
1562 1743
 // If the servo can't reach the requested position, increase it.
1563
-#define SERVO_DELAY 300
1744
+#define SERVO_DELAY { 300 }
1564 1745
 
1565 1746
 // Servo deactivation
1566 1747
 //
1567 1748
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1568 1749
 //#define DEACTIVATE_SERVOS_AFTER_MOVE
1569 1750
 
1570
-/**
1571
- * Filament Width Sensor
1572
- *
1573
- * Measures the filament width in real-time and adjusts
1574
- * flow rate to compensate for any irregularities.
1575
- *
1576
- * Also allows the measured filament diameter to set the
1577
- * extrusion rate, so the slicer only has to specify the
1578
- * volume.
1579
- *
1580
- * Only a single extruder is supported at this time.
1581
- *
1582
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1583
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1584
- * 301 RAMBO       : Analog input 3
1585
- *
1586
- * Note: May require analog pins to be defined for other boards.
1587
- */
1588
-//#define FILAMENT_WIDTH_SENSOR
1589
-
1590
-#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00   // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
1591
-
1592
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1593
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1594
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1595
-
1596
-  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1597
-  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1598
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1599
-
1600
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1601
-
1602
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1603
-  //#define FILAMENT_LCD_DISPLAY
1604
-#endif
1605
-
1606 1751
 #endif // CONFIGURATION_H

Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h → Marlin/example_configurations/FolgerTech/i3-2020/Configuration.h 파일 보기

@@ -37,7 +37,7 @@
37 37
  */
38 38
 #ifndef CONFIGURATION_H
39 39
 #define CONFIGURATION_H
40
-#define CONFIGURATION_H_VERSION 010100
40
+#define CONFIGURATION_H_VERSION 010107
41 41
 
42 42
 //===========================================================================
43 43
 //============================= Getting Started =============================
@@ -107,8 +107,9 @@
107 107
  *
108 108
  * 250000 works in most cases, but you might try a lower speed if
109 109
  * you commonly experience drop-outs during host printing.
110
+ * You may try up to 1000000 to speed up SD file transfer.
110 111
  *
111
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
112
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
112 113
  */
113 114
 #define BAUDRATE 250000
114 115
 
@@ -135,6 +136,9 @@
135 136
 // :[1, 2, 3, 4, 5]
136 137
 #define EXTRUDERS 1
137 138
 
139
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
140
+#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75
141
+
138 142
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
139 143
 //#define SINGLENOZZLE
140 144
 
@@ -161,7 +165,10 @@
161 165
 //#define SWITCHING_EXTRUDER
162 166
 #if ENABLED(SWITCHING_EXTRUDER)
163 167
   #define SWITCHING_EXTRUDER_SERVO_NR 0
164
-  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1
168
+  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3]
169
+  #if EXTRUDERS > 3
170
+    #define SWITCHING_EXTRUDER_E23_SERVO_NR 1
171
+  #endif
165 172
 #endif
166 173
 
167 174
 // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles
@@ -173,6 +180,21 @@
173 180
 #endif
174 181
 
175 182
 /**
183
+ * Two separate X-carriages with extruders that connect to a moving part
184
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
185
+ */
186
+//#define PARKING_EXTRUDER
187
+#if ENABLED(PARKING_EXTRUDER)
188
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
189
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
190
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
191
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
192
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
193
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
194
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
195
+#endif
196
+
197
+/**
176 198
  * "Mixing Extruder"
177 199
  *   - Adds a new code, M165, to set the current mix factors.
178 200
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -317,8 +339,9 @@
317 339
 
318 340
 // Comment the following line to disable PID and enable bang-bang.
319 341
 #define PIDTEMP
320
-#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
321
-#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
342
+#define BANG_MAX 255     // Limits current to nozzle while in bang-bang mode; 255=full current
343
+#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
344
+#define PID_K1 0.95      // Smoothing factor within the PID
322 345
 #if ENABLED(PIDTEMP)
323 346
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
324 347
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -328,7 +351,6 @@
328 351
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
329 352
   #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
330 353
                                   // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
331
-  #define K1 0.95 //smoothing factor within the PID
332 354
 
333 355
   // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
334 356
 
@@ -414,12 +436,13 @@
414 436
 //===========================================================================
415 437
 
416 438
 /**
417
- * Thermal Protection protects your printer from damage and fire if a
418
- * thermistor falls out or temperature sensors fail in any way.
439
+ * Thermal Protection provides additional protection to your printer from damage
440
+ * and fire. Marlin always includes safe min and max temperature ranges which
441
+ * protect against a broken or disconnected thermistor wire.
419 442
  *
420
- * The issue: If a thermistor falls out or a temperature sensor fails,
421
- * Marlin can no longer sense the actual temperature. Since a disconnected
422
- * thermistor reads as a low temperature, the firmware will keep the heater on.
443
+ * The issue: If a thermistor falls out, it will report the much lower
444
+ * temperature of the air in the room, and the the firmware will keep
445
+ * the heater on.
423 446
  *
424 447
  * If you get "Thermal Runaway" or "Heating failed" errors the
425 448
  * details can be tuned in Configuration_adv.h
@@ -553,14 +576,13 @@
553 576
 #define DEFAULT_ZJERK                  0.4
554 577
 #define DEFAULT_EJERK                  4.0
555 578
 
556
-
557 579
 //===========================================================================
558 580
 //============================= Z Probe Options =============================
559 581
 //===========================================================================
560 582
 // @section probes
561 583
 
562 584
 //
563
-// See http://marlinfw.org/configuration/probes.html
585
+// See http://marlinfw.org/docs/configuration/probes.html
564 586
 //
565 587
 
566 588
 /**
@@ -626,14 +648,15 @@
626 648
 #endif
627 649
 
628 650
 /**
629
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
630
- * options selected below - will be disabled during probing so as to minimize
631
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
632
- * in current flowing through the wires).  This is likely most useful to users of the
633
- * BLTouch probe, but may also help those with inductive or other probe types.
651
+ * Enable one or more of the following if probing seems unreliable.
652
+ * Heaters and/or fans can be disabled during probing to minimize electrical
653
+ * noise. A delay can also be added to allow noise and vibration to settle.
654
+ * These options are most useful for the BLTouch probe, but may also improve
655
+ * readings with inductive probes and piezo sensors.
634 656
  */
635 657
 //#define PROBING_HEATERS_OFF       // Turn heaters off when probing
636 658
 //#define PROBING_FANS_OFF          // Turn fans off when probing
659
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
637 660
 
638 661
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
639 662
 //#define SOLENOID_PROBE
@@ -671,14 +694,16 @@
671 694
 
672 695
 // X and Y axis travel speed (mm/m) between probes
673 696
 #define XY_PROBE_SPEED 7500
674
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
697
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
675 698
 #define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
676 699
 
677 700
 // Speed for the "accurate" probe of each point
678 701
 #define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
679 702
 
680
-// Use double touch for probing
681
-//#define PROBE_DOUBLE_TOUCH
703
+// The number of probes to perform at each point.
704
+//   Set to 2 for a fast/slow probe, using the second probe result.
705
+//   Set to 3 or more for slow probes, averaging the results.
706
+//#define MULTIPLE_PROBING 2
682 707
 
683 708
 /**
684 709
  * Z probes require clearance when deploying, stowing, and moving between
@@ -697,7 +722,8 @@
697 722
 #define Z_CLEARANCE_DEPLOY_PROBE    3 // Z Clearance for Deploy/Stow
698 723
 #define Z_CLEARANCE_BETWEEN_PROBES  3 // Z Clearance between probe points
699 724
 
700
-// For M851 give a range for adjusting the Z probe offset#define Z_PROBE_OFFSET_RANGE_MIN -20
725
+// For M851 give a range for adjusting the Z probe offset
726
+#define Z_PROBE_OFFSET_RANGE_MIN -20
701 727
 #define Z_PROBE_OFFSET_RANGE_MAX 20
702 728
 
703 729
 // Enable the M48 repeatability test to test probe accuracy
@@ -743,6 +769,8 @@
743 769
 
744 770
 // @section homing
745 771
 
772
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
773
+
746 774
 #define Z_HOMING_HEIGHT 2    // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
747 775
                              // Be sure you have this distance over your Z_MAX_POS in case.
748 776
 
@@ -754,17 +782,42 @@
754 782
 
755 783
 // @section machine
756 784
 
757
-// Travel limits after homing (units are in mm)
785
+// The size of the print bed
786
+#define X_BED_SIZE 207
787
+#define Y_BED_SIZE 182
788
+
789
+// Travel limits (mm) after homing, corresponding to endstop positions.
758 790
 #define X_MIN_POS 6
759 791
 #define Y_MIN_POS 3
760 792
 #define Z_MIN_POS 0
761
-#define X_MAX_POS 207
762
-#define Y_MAX_POS 182
793
+#define X_MAX_POS X_BED_SIZE
794
+#define Y_MAX_POS Y_BED_SIZE
763 795
 #define Z_MAX_POS 175
764
-// If enabled, axes won't move below MIN_POS in response to movement commands.
796
+
797
+/**
798
+ * Software Endstops
799
+ *
800
+ * - Prevent moves outside the set machine bounds.
801
+ * - Individual axes can be disabled, if desired.
802
+ * - X and Y only apply to Cartesian robots.
803
+ * - Use 'M211' to set software endstops on/off or report current state
804
+ */
805
+
806
+// Min software endstops curtail movement below minimum coordinate bounds
765 807
 //#define MIN_SOFTWARE_ENDSTOPS
766
-// If enabled, axes won't move above MAX_POS in response to movement commands.
808
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
809
+  #define MIN_SOFTWARE_ENDSTOP_X
810
+  #define MIN_SOFTWARE_ENDSTOP_Y
811
+  #define MIN_SOFTWARE_ENDSTOP_Z
812
+#endif
813
+
814
+// Max software endstops curtail movement above maximum coordinate bounds
767 815
 #define MAX_SOFTWARE_ENDSTOPS
816
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
817
+  #define MAX_SOFTWARE_ENDSTOP_X
818
+  #define MAX_SOFTWARE_ENDSTOP_Y
819
+  #define MAX_SOFTWARE_ENDSTOP_Z
820
+#endif
768 821
 
769 822
 /**
770 823
  * Filament Runout Sensor
@@ -784,7 +837,7 @@
784 837
 //===========================================================================
785 838
 //=============================== Bed Leveling ==============================
786 839
 //===========================================================================
787
-// @section bedlevel
840
+// @section calibrate
788 841
 
789 842
 /**
790 843
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -810,12 +863,7 @@
810 863
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
811 864
  *   A comprehensive bed leveling system combining the features and benefits
812 865
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
813
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
814
- *   for Cartesian Printers. That said, it was primarily designed to correct
815
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
816
- *   please post an issue if something doesn't work correctly. Initially,
817
- *   you will need to set a reduced bed size so you have a rectangular area
818
- *   to test on.
866
+ *   Validation and Mesh Editing systems.
819 867
  *
820 868
  * - MESH_BED_LEVELING
821 869
  *   Probe a grid manually
@@ -842,6 +890,24 @@
842 890
   // at which point movement will be level to the machine's XY plane.
843 891
   // The height can be set with M420 Z<height>
844 892
   #define ENABLE_LEVELING_FADE_HEIGHT
893
+
894
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
895
+  // split up moves into short segments like a Delta. This follows the
896
+  // contours of the bed more closely than edge-to-edge straight moves.
897
+  #define SEGMENT_LEVELED_MOVES
898
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
899
+
900
+  /**
901
+   * Enable the G26 Mesh Validation Pattern tool.
902
+   */
903
+  //#define G26_MESH_VALIDATION   // Enable G26 mesh validation
904
+  #if ENABLED(G26_MESH_VALIDATION)
905
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
906
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
907
+    #define MESH_TEST_HOTEND_TEMP   205.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
908
+    #define MESH_TEST_BED_TEMP       60.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
909
+  #endif
910
+
845 911
 #endif
846 912
 
847 913
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -899,7 +965,9 @@
899 965
   //========================= Unified Bed Leveling ============================
900 966
   //===========================================================================
901 967
 
902
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
968
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
969
+
970
+  #define MESH_INSET 1              // Mesh inset margin on print area
903 971
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
904 972
   #define GRID_MAX_POINTS_Y 10
905 973
 
@@ -910,8 +978,8 @@
910 978
   #define UBL_PROBE_PT_3_X 180
911 979
   #define UBL_PROBE_PT_3_Y 25
912 980
 
913
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
914 981
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
982
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
915 983
 
916 984
 #elif ENABLED(MESH_BED_LEVELING)
917 985
 
@@ -938,6 +1006,9 @@
938 1006
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
939 1007
 #endif
940 1008
 
1009
+// Add a menu item to move between bed corners for manual bed adjustment
1010
+//#define LEVEL_BED_CORNERS
1011
+
941 1012
 /**
942 1013
  * Commands to execute at the end of G29 probing.
943 1014
  * Useful to retract or move the Z probe out of the way.
@@ -968,14 +1039,71 @@
968 1039
 #define Z_SAFE_HOMING
969 1040
 
970 1041
 #if ENABLED(Z_SAFE_HOMING)
971
-  #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
972
-  #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
1042
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1043
+  #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2)    // Y point for Z homing when homing all axes (G28).
973 1044
 #endif
974 1045
 
975 1046
 // Homing speeds (mm/m)
976 1047
 #define HOMING_FEEDRATE_XY (40*60)
977 1048
 #define HOMING_FEEDRATE_Z  (55)
978 1049
 
1050
+// @section calibrate
1051
+
1052
+/**
1053
+ * Bed Skew Compensation
1054
+ *
1055
+ * This feature corrects for misalignment in the XYZ axes.
1056
+ *
1057
+ * Take the following steps to get the bed skew in the XY plane:
1058
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1059
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1060
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1061
+ *  4. For XY_SIDE_AD measure the edge A to D
1062
+ *
1063
+ * Marlin automatically computes skew factors from these measurements.
1064
+ * Skew factors may also be computed and set manually:
1065
+ *
1066
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1067
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1068
+ *
1069
+ * If desired, follow the same procedure for XZ and YZ.
1070
+ * Use these diagrams for reference:
1071
+ *
1072
+ *    Y                     Z                     Z
1073
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1074
+ *    |    /       /        |    /       /        |    /       /
1075
+ *    |   /       /         |   /       /         |   /       /
1076
+ *    |  A-------D          |  A-------D          |  A-------D
1077
+ *    +-------------->X     +-------------->X     +-------------->Y
1078
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1079
+ */
1080
+//#define SKEW_CORRECTION
1081
+
1082
+#if ENABLED(SKEW_CORRECTION)
1083
+  // Input all length measurements here:
1084
+  #define XY_DIAG_AC 282.8427124746
1085
+  #define XY_DIAG_BD 282.8427124746
1086
+  #define XY_SIDE_AD 200
1087
+
1088
+  // Or, set the default skew factors directly here
1089
+  // to override the above measurements:
1090
+  #define XY_SKEW_FACTOR 0.0
1091
+
1092
+  //#define SKEW_CORRECTION_FOR_Z
1093
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1094
+    #define XZ_DIAG_AC 282.8427124746
1095
+    #define XZ_DIAG_BD 282.8427124746
1096
+    #define YZ_DIAG_AC 282.8427124746
1097
+    #define YZ_DIAG_BD 282.8427124746
1098
+    #define YZ_SIDE_AD 200
1099
+    #define XZ_SKEW_FACTOR 0.0
1100
+    #define YZ_SKEW_FACTOR 0.0
1101
+  #endif
1102
+
1103
+  // Enable this option for M852 to set skew at runtime
1104
+  //#define SKEW_CORRECTION_GCODE
1105
+#endif
1106
+
979 1107
 //=============================================================================
980 1108
 //============================= Additional Features ===========================
981 1109
 //=============================================================================
@@ -1002,11 +1130,12 @@
1002 1130
 //
1003 1131
 //#define HOST_KEEPALIVE_FEATURE        // Disable this if your host doesn't like keepalive messages
1004 1132
 #define DEFAULT_KEEPALIVE_INTERVAL 2  // Number of seconds between "busy" messages. Set with M113.
1133
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
1005 1134
 
1006 1135
 //
1007 1136
 // M100 Free Memory Watcher
1008 1137
 //
1009
-#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1138
+#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
1010 1139
 
1011 1140
 //
1012 1141
 // G20/G21 Inch mode support
@@ -1151,11 +1280,11 @@
1151 1280
  *
1152 1281
  * Select the language to display on the LCD. These languages are available:
1153 1282
  *
1154
- *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
1155
- *    it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
1156
- *    zh_CN, zh_TW, test
1283
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1284
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1285
+ *    tr, uk, zh_CN, zh_TW, test
1157 1286
  *
1158
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1287
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1159 1288
  */
1160 1289
 #define LCD_LANGUAGE en
1161 1290
 
@@ -1177,7 +1306,7 @@
1177 1306
  *  - Click the controller to view the LCD menu
1178 1307
  *  - The LCD will display Japanese, Western, or Cyrillic text
1179 1308
  *
1180
- * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1309
+ * See http://marlinfw.org/docs/development/lcd_language.html
1181 1310
  *
1182 1311
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1183 1312
  */
@@ -1283,8 +1412,8 @@
1283 1412
 // Note: Test audio output with the G-Code:
1284 1413
 //  M300 S<frequency Hz> P<duration ms>
1285 1414
 //
1286
-//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
1287
-//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
1415
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
1416
+//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
1288 1417
 
1289 1418
 //
1290 1419
 // CONTROLLER TYPE: Standard
@@ -1392,11 +1521,13 @@
1392 1521
 //#define CARTESIO_UI
1393 1522
 
1394 1523
 //
1395
-// ANET_10 Controller supported displays.
1524
+// ANET and Tronxy Controller supported displays.
1396 1525
 //
1397
-//#define ANET_KEYPAD_LCD         // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1526
+//#define ZONESTAR_LCD            // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1398 1527
                                   // This LCD is known to be susceptible to electrical interference
1399 1528
                                   // which scrambles the display.  Pressing any button clears it up.
1529
+                                  // This is a LCD2004 display with 5 analog buttons.
1530
+
1400 1531
 //#define ANET_FULL_GRAPHICS_LCD  // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1401 1532
                                   // A clone of the RepRapDiscount full graphics display but with
1402 1533
                                   // different pins/wiring (see pins_ANET_10.h).
@@ -1456,11 +1587,6 @@
1456 1587
 //#define U8GLIB_SSD1306
1457 1588
 
1458 1589
 //
1459
-// TinyBoy2 128x64 OLED / Encoder Panel
1460
-//
1461
-//#define OLED_PANEL_TINYBOY2
1462
-
1463
-//
1464 1590
 // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules
1465 1591
 //
1466 1592
 //#define SAV_3DGLCD
@@ -1477,6 +1603,45 @@
1477 1603
 //
1478 1604
 //#define SAV_3DLCD
1479 1605
 
1606
+//
1607
+// TinyBoy2 128x64 OLED / Encoder Panel
1608
+//
1609
+//#define OLED_PANEL_TINYBOY2
1610
+
1611
+//
1612
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1613
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1614
+//
1615
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1616
+
1617
+//
1618
+// MKS MINI12864 with graphic controller and SD support
1619
+// http://reprap.org/wiki/MKS_MINI_12864
1620
+//
1621
+//#define MKS_MINI_12864
1622
+
1623
+//
1624
+// Factory display for Creality CR-10
1625
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1626
+//
1627
+// This is RAMPS-compatible using a single 10-pin connector.
1628
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1629
+//
1630
+//#define CR10_STOCKDISPLAY
1631
+
1632
+//
1633
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1634
+// http://reprap.org/wiki/MKS_12864OLED
1635
+//
1636
+// Tiny, but very sharp OLED display
1637
+//
1638
+//#define MKS_12864OLED
1639
+
1640
+// Silvergate GLCD controller
1641
+// http://github.com/android444/Silvergate
1642
+//
1643
+//#define SILVER_GATE_GLCD_CONTROLLER
1644
+
1480 1645
 //=============================================================================
1481 1646
 //=============================== Extra Features ==============================
1482 1647
 //=============================================================================
@@ -1533,16 +1698,22 @@
1533 1698
  * Adds the M150 command to set the LED (or LED strip) color.
1534 1699
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1535 1700
  * luminance values can be set from 0 to 255.
1701
+ * For Neopixel LED an overall brightness parameter is also available.
1536 1702
  *
1537 1703
  * *** CAUTION ***
1538 1704
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1539 1705
  *  as the Arduino cannot handle the current the LEDs will require.
1540 1706
  *  Failure to follow this precaution can destroy your Arduino!
1707
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1708
+ *  more current than the Arduino 5V linear regulator can produce.
1541 1709
  * *** CAUTION ***
1542 1710
  *
1711
+ * LED Type. Enable only one of the following two options.
1712
+ *
1543 1713
  */
1544 1714
 //#define RGB_LED
1545 1715
 //#define RGBW_LED
1716
+
1546 1717
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1547 1718
   #define RGB_LED_R_PIN 34
1548 1719
   #define RGB_LED_G_PIN 43
@@ -1550,6 +1721,17 @@
1550 1721
   #define RGB_LED_W_PIN -1
1551 1722
 #endif
1552 1723
 
1724
+// Support for Adafruit Neopixel LED driver
1725
+//#define NEOPIXEL_LED
1726
+#if ENABLED(NEOPIXEL_LED)
1727
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1728
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1729
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1730
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1731
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1732
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1733
+#endif
1734
+
1553 1735
 /**
1554 1736
  * Printer Event LEDs
1555 1737
  *
@@ -1561,68 +1743,32 @@
1561 1743
  *  - Change to green once print has finished
1562 1744
  *  - Turn off after the print has finished and the user has pushed a button
1563 1745
  */
1564
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)
1746
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1565 1747
   #define PRINTER_EVENT_LEDS
1566 1748
 #endif
1567 1749
 
1568
-/*********************************************************************\
1569
-* R/C SERVO support
1570
-* Sponsored by TrinityLabs, Reworked by codexmas
1571
-**********************************************************************/
1750
+/**
1751
+ * R/C SERVO support
1752
+ * Sponsored by TrinityLabs, Reworked by codexmas
1753
+ */
1572 1754
 
1573
-// Number of servos
1574
-//
1575
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1576
-// set it manually if you have more servos than extruders and wish to manually control some
1577
-// leaving it undefined or defining as 0 will disable the servo subsystem
1578
-// If unsure, leave commented / disabled
1579
-//
1755
+/**
1756
+ * Number of servos
1757
+ *
1758
+ * For some servo-related options NUM_SERVOS will be set automatically.
1759
+ * Set this manually if there are extra servos needing manual control.
1760
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1761
+ */
1580 1762
 #define NUM_SERVOS 2 // Servo index starts with 0 for M280 command
1581 1763
 
1582 1764
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1583 1765
 // 300ms is a good value but you can try less delay.
1584 1766
 // If the servo can't reach the requested position, increase it.
1585
-#define SERVO_DELAY 500
1767
+#define SERVO_DELAY { 500, 500 }
1586 1768
 
1587 1769
 // Servo deactivation
1588 1770
 //
1589 1771
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1590 1772
 #define DEACTIVATE_SERVOS_AFTER_MOVE
1591 1773
 
1592
-/**
1593
- * Filament Width Sensor
1594
- *
1595
- * Measures the filament width in real-time and adjusts
1596
- * flow rate to compensate for any irregularities.
1597
- *
1598
- * Also allows the measured filament diameter to set the
1599
- * extrusion rate, so the slicer only has to specify the
1600
- * volume.
1601
- *
1602
- * Only a single extruder is supported at this time.
1603
- *
1604
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1605
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1606
- * 301 RAMBO       : Analog input 3
1607
- *
1608
- * Note: May require analog pins to be defined for other boards.
1609
- */
1610
-//#define FILAMENT_WIDTH_SENSOR
1611
-
1612
-#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75   // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
1613
-
1614
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1615
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1616
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1617
-
1618
-  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1619
-  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1620
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1621
-
1622
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1623
-
1624
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1625
-  //#define FILAMENT_LCD_DISPLAY
1626
-#endif
1627
-
1628 1774
 #endif // CONFIGURATION_H

Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h → Marlin/example_configurations/FolgerTech/i3-2020/Configuration_adv.h 파일 보기

@@ -32,7 +32,7 @@
32 32
  */
33 33
 #ifndef CONFIGURATION_ADV_H
34 34
 #define CONFIGURATION_ADV_H
35
-#define CONFIGURATION_ADV_H_VERSION 010100
35
+#define CONFIGURATION_ADV_H_VERSION 010107
36 36
 
37 37
 // @section temperature
38 38
 
@@ -48,31 +48,36 @@
48 48
 #endif
49 49
 
50 50
 /**
51
- * Thermal Protection protects your printer from damage and fire if a
52
- * thermistor falls out or temperature sensors fail in any way.
51
+ * Thermal Protection provides additional protection to your printer from damage
52
+ * and fire. Marlin always includes safe min and max temperature ranges which
53
+ * protect against a broken or disconnected thermistor wire.
53 54
  *
54
- * The issue: If a thermistor falls out or a temperature sensor fails,
55
- * Marlin can no longer sense the actual temperature. Since a disconnected
56
- * thermistor reads as a low temperature, the firmware will keep the heater on.
55
+ * The issue: If a thermistor falls out, it will report the much lower
56
+ * temperature of the air in the room, and the the firmware will keep
57
+ * the heater on.
57 58
  *
58 59
  * The solution: Once the temperature reaches the target, start observing.
59
- * If the temperature stays too far below the target (hysteresis) for too long (period),
60
- * the firmware will halt the machine as a safety precaution.
60
+ * If the temperature stays too far below the target (hysteresis) for too
61
+ * long (period), the firmware will halt the machine as a safety precaution.
61 62
  *
62
- * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63
+ * If you get false positives for "Thermal Runaway", increase
64
+ * THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63 65
  */
64 66
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
65 67
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
66 68
   #define THERMAL_PROTECTION_HYSTERESIS 2     // Degrees Celsius
67 69
 
68 70
   /**
69
-   * Whenever an M104 or M109 increases the target temperature the firmware will wait for the
70
-   * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
71
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
72
-   * but only if the current temperature is far enough below the target for a reliable test.
71
+   * Whenever an M104, M109, or M303 increases the target temperature, the
72
+   * firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
73
+   * hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
74
+   * requires a hard reset. This test restarts with any M104/M109/M303, but only
75
+   * if the current temperature is far enough below the target for a reliable
76
+   * test.
73 77
    *
74
-   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
75
-   * WATCH_TEMP_INCREASE should not be below 2.
78
+   * If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
79
+   * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
80
+   * below 2.
76 81
    */
77 82
   #define WATCH_TEMP_PERIOD 40                // Seconds
78 83
   #define WATCH_TEMP_INCREASE 2               // Degrees Celsius
@@ -86,13 +91,7 @@
86 91
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
87 92
 
88 93
   /**
89
-   * Whenever an M140 or M190 increases the target temperature the firmware will wait for the
90
-   * WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
91
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
92
-   * but only if the current temperature is far enough below the target for a reliable test.
93
-   *
94
-   * If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
95
-   * WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
94
+   * As described above, except for the bed (M140/M190/M303).
96 95
    */
97 96
   #define WATCH_BED_TEMP_PERIOD 60                // Seconds
98 97
   #define WATCH_BED_TEMP_INCREASE 2               // Degrees Celsius
@@ -123,6 +122,9 @@
123 122
   #define AUTOTEMP_OLDWEIGHT 0.98
124 123
 #endif
125 124
 
125
+// Show extra position information in M114
126
+//#define M114_DETAIL
127
+
126 128
 // Show Temperature ADC value
127 129
 // Enable for M105 to include ADC values read from temperature sensors.
128 130
 //#define SHOW_TEMP_ADC_VALUES
@@ -221,6 +223,17 @@
221 223
 #define EXTRUDER_AUTO_FAN_SPEED   255  // == full speed
222 224
 
223 225
 /**
226
+ * Part-Cooling Fan Multiplexer
227
+ *
228
+ * This feature allows you to digitally multiplex the fan output.
229
+ * The multiplexer is automatically switched at tool-change.
230
+ * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans.
231
+ */
232
+#define FANMUX0_PIN -1
233
+#define FANMUX1_PIN -1
234
+#define FANMUX2_PIN -1
235
+
236
+/**
224 237
  * M355 Case Light on-off / brightness
225 238
  */
226 239
 //#define CASE_LIGHT_ENABLE
@@ -246,48 +259,49 @@
246 259
 
247 260
 //#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
248 261
 
249
-// Dual X Steppers
250
-// Uncomment this option to drive two X axis motors.
251
-// The next unused E driver will be assigned to the second X stepper.
262
+/**
263
+ * Dual Steppers / Dual Endstops
264
+ *
265
+ * This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
266
+ *
267
+ * For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
268
+ * spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
269
+ * set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
270
+ * that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
271
+ *
272
+ * Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
273
+ * this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
274
+ * in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
275
+ */
276
+
252 277
 //#define X_DUAL_STEPPER_DRIVERS
253 278
 #if ENABLED(X_DUAL_STEPPER_DRIVERS)
254
-  // Set true if the two X motors need to rotate in opposite directions
255
-  #define INVERT_X2_VS_X_DIR true
279
+  #define INVERT_X2_VS_X_DIR true   // Set 'true' if X motors should rotate in opposite directions
280
+  //#define X_DUAL_ENDSTOPS
281
+  #if ENABLED(X_DUAL_ENDSTOPS)
282
+    #define X2_USE_ENDSTOP _XMAX_
283
+    #define X_DUAL_ENDSTOPS_ADJUSTMENT  0
284
+  #endif
256 285
 #endif
257 286
 
258
-// Dual Y Steppers
259
-// Uncomment this option to drive two Y axis motors.
260
-// The next unused E driver will be assigned to the second Y stepper.
261 287
 //#define Y_DUAL_STEPPER_DRIVERS
262 288
 #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
263
-  // Set true if the two Y motors need to rotate in opposite directions
264
-  #define INVERT_Y2_VS_Y_DIR true
289
+  #define INVERT_Y2_VS_Y_DIR true   // Set 'true' if Y motors should rotate in opposite directions
290
+  //#define Y_DUAL_ENDSTOPS
291
+  #if ENABLED(Y_DUAL_ENDSTOPS)
292
+    #define Y2_USE_ENDSTOP _YMAX_
293
+    #define Y_DUAL_ENDSTOPS_ADJUSTMENT  0
294
+  #endif
265 295
 #endif
266 296
 
267
-// A single Z stepper driver is usually used to drive 2 stepper motors.
268
-// Uncomment this option to use a separate stepper driver for each Z axis motor.
269
-// The next unused E driver will be assigned to the second Z stepper.
270 297
 //#define Z_DUAL_STEPPER_DRIVERS
271
-
272 298
 #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
273
-
274
-  // Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper.
275
-  // That way the machine is capable to align the bed during home, since both Z steppers are homed.
276
-  // There is also an implementation of M666 (software endstops adjustment) to this feature.
277
-  // After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
278
-  // One just need to home the Z axis and measure the distance difference between both Z axis and apply the math: Z adjust = Z - Z2.
279
-  // If the Z stepper axis is closer to the bed, the measure Z > Z2 (yes, it is.. think about it) and the Z adjust would be positive.
280
-  // Play a little bit with small adjustments (0.5mm) and check the behaviour.
281
-  // The M119 (endstops report) will start reporting the Z2 Endstop as well.
282
-
283 299
   //#define Z_DUAL_ENDSTOPS
284
-
285 300
   #if ENABLED(Z_DUAL_ENDSTOPS)
286 301
     #define Z2_USE_ENDSTOP _XMAX_
287
-    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0  // use M666 command to determine/test this value
302
+    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0
288 303
   #endif
289
-
290
-#endif // Z_DUAL_STEPPER_DRIVERS
304
+#endif
291 305
 
292 306
 // Enable this for dual x-carriage printers.
293 307
 // A dual x-carriage design has the advantage that the inactive extruder can be parked which
@@ -334,12 +348,12 @@
334 348
 
335 349
 // @section homing
336 350
 
337
-//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
351
+// Homing hits each endstop, retracts by these distances, then does a slower bump.
338 352
 #define X_HOME_BUMP_MM 5
339 353
 #define Y_HOME_BUMP_MM 5
340 354
 #define Z_HOME_BUMP_MM 2
341
-#define HOMING_BUMP_DIVISOR {2, 2, 4}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
342
-//#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
355
+#define HOMING_BUMP_DIVISOR { 2, 2, 4 }  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
356
+//#define QUICK_HOME                     // If homing includes X and Y, do a diagonal move initially
343 357
 
344 358
 // When G28 is called, this option will make Y home before X
345 359
 //#define HOME_Y_BEFORE_X
@@ -394,7 +408,7 @@
394 408
 // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
395 409
 // of the buffer and all stops. This should not be much greater than zero and should only be changed
396 410
 // if unwanted behavior is observed on a user's machine when running at very slow speeds.
397
-#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
411
+#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
398 412
 
399 413
 // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
400 414
 #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
@@ -423,8 +437,21 @@
423 437
 //#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 }   // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
424 438
 //#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 }    // Default drive percent - X, Y, Z, E axis
425 439
 
426
-// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
440
+// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
427 441
 //#define DIGIPOT_I2C
442
+#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
443
+  /**
444
+   * Common slave addresses:
445
+   *
446
+   *                    A   (A shifted)   B   (B shifted)  IC
447
+   * Smoothie          0x2C (0x58)       0x2D (0x5A)       MCP4451
448
+   * AZTEEG_X3_PRO     0x2C (0x58)       0x2E (0x5C)       MCP4451
449
+   * MIGHTYBOARD_REVE  0x2F (0x5E)                         MCP4018
450
+   */
451
+  #define DIGIPOT_I2C_ADDRESS_A 0x2C  // unshifted slave address for first DIGIPOT
452
+  #define DIGIPOT_I2C_ADDRESS_B 0x2D  // unshifted slave address for second DIGIPOT
453
+#endif
454
+
428 455
 //#define DIGIPOT_MCP4018          // Requires library from https://github.com/stawel/SlowSoftI2CMaster
429 456
 #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4     AZTEEG_X3_PRO: 8
430 457
 // Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
@@ -455,6 +482,23 @@
455 482
 // The timeout (in ms) to return to the status screen from sub-menus
456 483
 //#define LCD_TIMEOUT_TO_STATUS 15000
457 484
 
485
+/**
486
+ * LED Control Menu
487
+ * Enable this feature to add LED Control to the LCD menu
488
+ */
489
+//#define LED_CONTROL_MENU
490
+#if ENABLED(LED_CONTROL_MENU)
491
+  #define LED_COLOR_PRESETS                 // Enable the Preset Color menu option
492
+  #if ENABLED(LED_COLOR_PRESETS)
493
+    #define LED_USER_PRESET_RED        255  // User defined RED value
494
+    #define LED_USER_PRESET_GREEN      128  // User defined GREEN value
495
+    #define LED_USER_PRESET_BLUE         0  // User defined BLUE value
496
+    #define LED_USER_PRESET_WHITE      255  // User defined WHITE value
497
+    #define LED_USER_PRESET_BRIGHTNESS 255  // User defined intensity
498
+    //#define LED_USER_PRESET_STARTUP       // Have the printer display the user preset color on startup
499
+  #endif
500
+#endif // LED_CONTROL_MENU
501
+
458 502
 #if ENABLED(SDSUPPORT)
459 503
 
460 504
   // Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -464,12 +508,14 @@
464 508
   // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
465 509
   #define SD_DETECT_INVERTED
466 510
 
467
-  #define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
511
+  #define SD_FINISHED_STEPPERRELEASE true          // Disable steppers when SD Print is finished
468 512
   #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
469 513
 
470
-  #define SDCARD_RATHERRECENTFIRST  //reverse file order of sd card menu display. Its sorted practically after the file system block order.
471
-  // if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that.
472
-  // using:
514
+  // Reverse SD sort to show "more recent" files first, according to the card's FAT.
515
+  // Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
516
+  #define SDCARD_RATHERRECENTFIRST
517
+
518
+  // Add an option in the menu to run all auto#.g files
473 519
   //#define MENU_ADDAUTOSTART
474 520
 
475 521
   /**
@@ -499,13 +545,15 @@
499 545
 
500 546
   // SD Card Sorting options
501 547
   #if ENABLED(SDCARD_SORT_ALPHA)
502
-    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256).
548
+    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256). Costs 27 bytes each.
503 549
     #define FOLDER_SORTING     -1     // -1=above  0=none  1=below
504 550
     #define SDSORT_GCODE       false  // Allow turning sorting on/off with LCD and M34 g-code.
505 551
     #define SDSORT_USES_RAM    false  // Pre-allocate a static array for faster pre-sorting.
506 552
     #define SDSORT_USES_STACK  false  // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
507 553
     #define SDSORT_CACHE_NAMES false  // Keep sorted items in RAM longer for speedy performance. Most expensive option.
508 554
     #define SDSORT_DYNAMIC_RAM false  // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
555
+    #define SDSORT_CACHE_VFATS 2      // Maximum number of 13-byte VFAT entries to use for sorting.
556
+                                      // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
509 557
   #endif
510 558
 
511 559
   // Show a progress bar on HD44780 LCDs for SD printing
@@ -524,14 +572,29 @@
524 572
     //#define LCD_PROGRESS_BAR_TEST
525 573
   #endif
526 574
 
575
+  // Add an 'M73' G-code to set the current percentage
576
+  //#define LCD_SET_PROGRESS_MANUALLY
577
+
527 578
   // This allows hosts to request long names for files and folders with M33
528 579
   //#define LONG_FILENAME_HOST_SUPPORT
529 580
 
530
-  // This option allows you to abort SD printing when any endstop is triggered.
531
-  // This feature must be enabled with "M540 S1" or from the LCD menu.
532
-  // To have any effect, endstops must be enabled during SD printing.
581
+  // Enable this option to scroll long filenames in the SD card menu
582
+  //#define SCROLL_LONG_FILENAMES
583
+
584
+  /**
585
+   * This option allows you to abort SD printing when any endstop is triggered.
586
+   * This feature must be enabled with "M540 S1" or from the LCD menu.
587
+   * To have any effect, endstops must be enabled during SD printing.
588
+   */
533 589
   //#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
534 590
 
591
+  /**
592
+   * This option makes it easier to print the same SD Card file again.
593
+   * On print completion the LCD Menu will open with the file selected.
594
+   * You can just click to start the print, or navigate elsewhere.
595
+   */
596
+  //#define SD_REPRINT_LAST_SELECTED_FILE
597
+
535 598
 #endif // SDSUPPORT
536 599
 
537 600
 /**
@@ -564,6 +627,10 @@
564 627
   // Enable this option and reduce the value to optimize screen updates.
565 628
   // The normal delay is 10µs. Use the lowest value that still gives a reliable display.
566 629
   //#define DOGM_SPI_DELAY_US 5
630
+
631
+  // Swap the CW/CCW indicators in the graphics overlay
632
+  //#define OVERLAY_GFX_REVERSE
633
+
567 634
 #endif // DOGLCD
568 635
 
569 636
 // @section safety
@@ -590,31 +657,18 @@
590 657
  */
591 658
 #define BABYSTEPPING
592 659
 #if ENABLED(BABYSTEPPING)
593
-  #define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
594
-  #define BABYSTEP_INVERT_Z false  // Change if Z babysteps should go the other way
595
-  #define BABYSTEP_MULTIPLICATOR 2 // Babysteps are very small. Increase for faster motion.
596
-  //#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
660
+  //#define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
661
+  #define BABYSTEP_INVERT_Z false    // Change if Z babysteps should go the other way
662
+  #define BABYSTEP_MULTIPLICATOR   2 // Babysteps are very small. Increase for faster motion.
663
+  //#define BABYSTEP_ZPROBE_OFFSET   // Enable to combine M851 and Babystepping
597 664
   #define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
598 665
   #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
599 666
                                         // Note: Extra time may be added to mitigate controller latency.
667
+  //#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
600 668
 #endif
601 669
 
602 670
 // @section extruder
603 671
 
604
-// extruder advance constant (s2/mm3)
605
-//
606
-// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
607
-//
608
-// Hooke's law says:    force = k * distance
609
-// Bernoulli's principle says:  v ^ 2 / 2 + g . h + pressure / density = constant
610
-// so: v ^ 2 is proportional to number of steps we advance the extruder
611
-//#define ADVANCE
612
-
613
-#if ENABLED(ADVANCE)
614
-  #define EXTRUDER_ADVANCE_K .0
615
-  #define D_FILAMENT 2.85
616
-#endif
617
-
618 672
 /**
619 673
  * Implementation of linear pressure control
620 674
  *
@@ -648,7 +702,7 @@
648 702
    *
649 703
    * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
650 704
    *
651
-   * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode.
705
+   * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
652 706
    * Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
653 707
    */
654 708
   #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
@@ -657,23 +711,18 @@
657 711
 
658 712
 // @section leveling
659 713
 
660
-// Default mesh area is an area with an inset margin on the print area.
661
-// Below are the macros that are used to define the borders for the mesh area,
662
-// made available here for specialized needs, ie dual extruder setup.
663
-#if ENABLED(MESH_BED_LEVELING)
664
-  #define MESH_MIN_X (X_MIN_POS + MESH_INSET)
665
-  #define MESH_MAX_X (X_MAX_POS - (MESH_INSET))
666
-  #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET)
667
-  #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET))
668
-#elif ENABLED(AUTO_BED_LEVELING_UBL)
669
-  #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET)
670
-  #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET))
671
-  #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET)
672
-  #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET))
673
-
674
-  // If this is defined, the currently active mesh will be saved in the
675
-  // current slot on M500.
676
-  #define UBL_SAVE_ACTIVE_ON_M500
714
+#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
715
+  #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
716
+#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
717
+  #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
718
+#endif
719
+
720
+#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
721
+  // Override the mesh area if the automatic (max) area is too large
722
+  //#define MESH_MIN_X MESH_INSET
723
+  //#define MESH_MIN_Y MESH_INSET
724
+  //#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
725
+  //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
677 726
 #endif
678 727
 
679 728
 // @section extras
@@ -693,7 +742,7 @@
693 742
 //#define BEZIER_CURVE_SUPPORT
694 743
 
695 744
 // G38.2 and G38.3 Probe Target
696
-// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
745
+// Set MULTIPLE_PROBING if you want G38 to double touch
697 746
 //#define G38_PROBE_TARGET
698 747
 #if ENABLED(G38_PROBE_TARGET)
699 748
   #define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
@@ -718,7 +767,7 @@
718 767
 // @section hidden
719 768
 
720 769
 // The number of linear motions that can be in the plan at any give time.
721
-// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
770
+// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
722 771
 #if ENABLED(SDSUPPORT)
723 772
   #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
724 773
 #else
@@ -731,7 +780,7 @@
731 780
 #define MAX_CMD_SIZE 96
732 781
 #define BUFSIZE 4
733 782
 
734
-// Transfer Buffer Size
783
+// Transmission to Host Buffer Size
735 784
 // To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0.
736 785
 // To buffer a simple "ok" you need 4 bytes.
737 786
 // For ADVANCED_OK (M105) you need 32 bytes.
@@ -740,6 +789,28 @@
740 789
 // :[0, 2, 4, 8, 16, 32, 64, 128, 256]
741 790
 #define TX_BUFFER_SIZE 0
742 791
 
792
+// Host Receive Buffer Size
793
+// Without XON/XOFF flow control (see SERIAL_XON_XOFF below) 32 bytes should be enough.
794
+// To use flow control, set this buffer size to at least 1024 bytes.
795
+// :[0, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048]
796
+//#define RX_BUFFER_SIZE 1024
797
+
798
+#if RX_BUFFER_SIZE >= 1024
799
+  // Enable to have the controller send XON/XOFF control characters to
800
+  // the host to signal the RX buffer is becoming full.
801
+  //#define SERIAL_XON_XOFF
802
+#endif
803
+
804
+#if ENABLED(SDSUPPORT)
805
+  // Enable this option to collect and display the maximum
806
+  // RX queue usage after transferring a file to SD.
807
+  //#define SERIAL_STATS_MAX_RX_QUEUED
808
+
809
+  // Enable this option to collect and display the number
810
+  // of dropped bytes after a file transfer to SD.
811
+  //#define SERIAL_STATS_DROPPED_RX
812
+#endif
813
+
743 814
 // Enable an emergency-command parser to intercept certain commands as they
744 815
 // enter the serial receive buffer, so they cannot be blocked.
745 816
 // Currently handles M108, M112, M410
@@ -755,27 +826,47 @@
755 826
 // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary.
756 827
 //#define ADVANCED_OK
757 828
 
758
-// @section fwretract
759
-
760
-// Firmware based and LCD controlled retract
761
-// M207 and M208 can be used to define parameters for the retraction.
762
-// The retraction can be called by the slicer using G10 and G11
763
-// until then, intended retractions can be detected by moves that only extrude and the direction.
764
-// the moves are than replaced by the firmware controlled ones.
829
+// @section extras
765 830
 
766
-//#define FWRETRACT  //ONLY PARTIALLY TESTED
831
+/**
832
+ * Firmware-based and LCD-controlled retract
833
+ *
834
+ * Add G10 / G11 commands for automatic firmware-based retract / recover.
835
+ * Use M207 and M208 to define parameters for retract / recover.
836
+ *
837
+ * Use M209 to enable or disable auto-retract.
838
+ * With auto-retract enabled, all G1 E moves within the set range
839
+ * will be converted to firmware-based retract/recover moves.
840
+ *
841
+ * Be sure to turn off auto-retract during filament change.
842
+ *
843
+ * Note that M207 / M208 / M209 settings are saved to EEPROM.
844
+ *
845
+ */
846
+//#define FWRETRACT  // ONLY PARTIALLY TESTED
767 847
 #if ENABLED(FWRETRACT)
768
-  #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
769
-  #define RETRACT_LENGTH 3               //default retract length (positive mm)
770
-  #define RETRACT_LENGTH_SWAP 13         //default swap retract length (positive mm), for extruder change
771
-  #define RETRACT_FEEDRATE 45            //default feedrate for retracting (mm/s)
772
-  #define RETRACT_ZLIFT 0                //default retract Z-lift
773
-  #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
774
-  #define RETRACT_RECOVER_LENGTH_SWAP 0  //default additional swap recover length (mm, added to retract length when recovering from extruder change)
775
-  #define RETRACT_RECOVER_FEEDRATE 8     //default feedrate for recovering from retraction (mm/s)
848
+  #define MIN_AUTORETRACT 0.1             // When auto-retract is on, convert E moves of this length and over
849
+  #define MAX_AUTORETRACT 10.0            // Upper limit for auto-retract conversion
850
+  #define RETRACT_LENGTH 3                // Default retract length (positive mm)
851
+  #define RETRACT_LENGTH_SWAP 13          // Default swap retract length (positive mm), for extruder change
852
+  #define RETRACT_FEEDRATE 45             // Default feedrate for retracting (mm/s)
853
+  #define RETRACT_ZLIFT 0                 // Default retract Z-lift
854
+  #define RETRACT_RECOVER_LENGTH 0        // Default additional recover length (mm, added to retract length when recovering)
855
+  #define RETRACT_RECOVER_LENGTH_SWAP 0   // Default additional swap recover length (mm, added to retract length when recovering from extruder change)
856
+  #define RETRACT_RECOVER_FEEDRATE 8      // Default feedrate for recovering from retraction (mm/s)
857
+  #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
776 858
 #endif
777 859
 
778 860
 /**
861
+ * Extra Fan Speed
862
+ * Adds a secondary fan speed for each print-cooling fan.
863
+ *   'M106 P<fan> T3-255' : Set a secondary speed for <fan>
864
+ *   'M106 P<fan> T2'     : Use the set secondary speed
865
+ *   'M106 P<fan> T1'     : Restore the previous fan speed
866
+ */
867
+//#define EXTRA_FAN_SPEED
868
+
869
+/**
779 870
  * Advanced Pause
780 871
  * Experimental feature for filament change support and for parking the nozzle when paused.
781 872
  * Adds the GCode M600 for initiating filament change.
@@ -784,7 +875,6 @@
784 875
  * Requires an LCD display.
785 876
  * This feature is required for the default FILAMENT_RUNOUT_SCRIPT.
786 877
  */
787
-
788 878
 #define ADVANCED_PAUSE_FEATURE
789 879
 #if ENABLED(ADVANCED_PAUSE_FEATURE)
790 880
   #define PAUSE_PARK_X_POS 10                 // X position of hotend
@@ -794,7 +884,6 @@
794 884
   #define PAUSE_PARK_Z_FEEDRATE 5             // Z axis feedrate in mm/s (not used for delta printers)
795 885
   #define PAUSE_PARK_RETRACT_FEEDRATE 60      // Initial retract feedrate in mm/s
796 886
   #define PAUSE_PARK_RETRACT_LENGTH 2         // Initial retract in mm
797
-
798 887
                                               // It is a short retract used immediately after print interrupt before move to filament exchange position
799 888
   #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10  // Unload filament feedrate in mm/s - filament unloading can be fast
800 889
   #define FILAMENT_CHANGE_UNLOAD_LENGTH 100   // Unload filament length from hotend in mm
@@ -887,7 +976,7 @@
887 976
 
888 977
 #endif
889 978
 
890
-// @section TMC2130
979
+// @section TMC2130, TMC2208
891 980
 
892 981
 /**
893 982
  * Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
@@ -901,7 +990,19 @@
901 990
  */
902 991
 //#define HAVE_TMC2130
903 992
 
904
-#if ENABLED(HAVE_TMC2130)
993
+/**
994
+ * Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
995
+ * Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
996
+ * To use the reading capabilities, also connect #_SERIAL_RX_PIN
997
+ * to #_SERIAL_TX_PIN with a 1K resistor.
998
+ * The drivers can also be used with hardware serial.
999
+ *
1000
+ * You'll also need the TMC2208Stepper Arduino library
1001
+ * (https://github.com/teemuatlut/TMC2208Stepper).
1002
+ */
1003
+//#define HAVE_TMC2208
1004
+
1005
+#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
905 1006
 
906 1007
   // CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
907 1008
   //#define X_IS_TMC2130
@@ -916,46 +1017,58 @@
916 1017
   //#define E3_IS_TMC2130
917 1018
   //#define E4_IS_TMC2130
918 1019
 
1020
+  //#define X_IS_TMC2208
1021
+  //#define X2_IS_TMC2208
1022
+  //#define Y_IS_TMC2208
1023
+  //#define Y2_IS_TMC2208
1024
+  //#define Z_IS_TMC2208
1025
+  //#define Z2_IS_TMC2208
1026
+  //#define E0_IS_TMC2208
1027
+  //#define E1_IS_TMC2208
1028
+  //#define E2_IS_TMC2208
1029
+  //#define E3_IS_TMC2208
1030
+  //#define E4_IS_TMC2208
1031
+
919 1032
   /**
920 1033
    * Stepper driver settings
921 1034
    */
922 1035
 
923 1036
   #define R_SENSE           0.11  // R_sense resistor for SilentStepStick2130
924 1037
   #define HOLD_MULTIPLIER    0.5  // Scales down the holding current from run current
925
-  #define INTERPOLATE          1  // Interpolate X/Y/Z_MICROSTEPS to 256
1038
+  #define INTERPOLATE       true  // Interpolate X/Y/Z_MICROSTEPS to 256
926 1039
 
927
-  #define X_CURRENT         1000  // rms current in mA. Multiply by 1.41 for peak current.
1040
+  #define X_CURRENT          800  // rms current in mA. Multiply by 1.41 for peak current.
928 1041
   #define X_MICROSTEPS        16  // 0..256
929 1042
 
930
-  #define Y_CURRENT         1000
1043
+  #define Y_CURRENT          800
931 1044
   #define Y_MICROSTEPS        16
932 1045
 
933
-  #define Z_CURRENT         1000
1046
+  #define Z_CURRENT          800
934 1047
   #define Z_MICROSTEPS        16
935 1048
 
936
-  //#define X2_CURRENT      1000
937
-  //#define X2_MICROSTEPS     16
1049
+  #define X2_CURRENT         800
1050
+  #define X2_MICROSTEPS       16
938 1051
 
939
-  //#define Y2_CURRENT      1000
940
-  //#define Y2_MICROSTEPS     16
1052
+  #define Y2_CURRENT         800
1053
+  #define Y2_MICROSTEPS       16
941 1054
 
942
-  //#define Z2_CURRENT      1000
943
-  //#define Z2_MICROSTEPS     16
1055
+  #define Z2_CURRENT         800
1056
+  #define Z2_MICROSTEPS       16
944 1057
 
945
-  //#define E0_CURRENT      1000
946
-  //#define E0_MICROSTEPS     16
1058
+  #define E0_CURRENT         800
1059
+  #define E0_MICROSTEPS       16
947 1060
 
948
-  //#define E1_CURRENT      1000
949
-  //#define E1_MICROSTEPS     16
1061
+  #define E1_CURRENT         800
1062
+  #define E1_MICROSTEPS       16
950 1063
 
951
-  //#define E2_CURRENT      1000
952
-  //#define E2_MICROSTEPS     16
1064
+  #define E2_CURRENT         800
1065
+  #define E2_MICROSTEPS       16
953 1066
 
954
-  //#define E3_CURRENT      1000
955
-  //#define E3_MICROSTEPS     16
1067
+  #define E3_CURRENT         800
1068
+  #define E3_MICROSTEPS       16
956 1069
 
957
-  //#define E4_CURRENT      1000
958
-  //#define E4_MICROSTEPS     16
1070
+  #define E4_CURRENT         800
1071
+  #define E4_MICROSTEPS       16
959 1072
 
960 1073
   /**
961 1074
    * Use Trinamic's ultra quiet stepping mode.
@@ -964,24 +1077,22 @@
964 1077
   #define STEALTHCHOP
965 1078
 
966 1079
   /**
967
-   * Let Marlin automatically control stepper current.
968
-   * This is still an experimental feature.
969
-   * Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
970
-   * then decrease current by CURRENT_STEP until temperature prewarn is cleared.
971
-   * Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
1080
+   * Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
1081
+   * like overtemperature and short to ground. TMC2208 requires hardware serial.
1082
+   * In the case of overtemperature Marlin can decrease the driver current until error condition clears.
1083
+   * Other detected conditions can be used to stop the current print.
972 1084
    * Relevant g-codes:
973 1085
    * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
974
-   * M906 S1 - Start adjusting current
975
-   * M906 S0 - Stop adjusting current
976 1086
    * M911 - Report stepper driver overtemperature pre-warn condition.
977 1087
    * M912 - Clear stepper driver overtemperature pre-warn condition flag.
1088
+   * M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
978 1089
    */
979
-  //#define AUTOMATIC_CURRENT_CONTROL
1090
+  //#define MONITOR_DRIVER_STATUS
980 1091
 
981
-  #if ENABLED(AUTOMATIC_CURRENT_CONTROL)
982
-    #define CURRENT_STEP          50  // [mA]
983
-    #define AUTO_ADJUST_MAX     1300  // [mA], 1300mA_rms = 1840mA_peak
1092
+  #if ENABLED(MONITOR_DRIVER_STATUS)
1093
+    #define CURRENT_STEP_DOWN     50  // [mA]
984 1094
     #define REPORT_CURRENT_CHANGE
1095
+    #define STOP_ON_ERROR
985 1096
   #endif
986 1097
 
987 1098
   /**
@@ -996,8 +1107,8 @@
996 1107
   #define X2_HYBRID_THRESHOLD    100
997 1108
   #define Y_HYBRID_THRESHOLD     100
998 1109
   #define Y2_HYBRID_THRESHOLD    100
999
-  #define Z_HYBRID_THRESHOLD       4
1000
-  #define Z2_HYBRID_THRESHOLD      4
1110
+  #define Z_HYBRID_THRESHOLD       3
1111
+  #define Z2_HYBRID_THRESHOLD      3
1001 1112
   #define E0_HYBRID_THRESHOLD     30
1002 1113
   #define E1_HYBRID_THRESHOLD     30
1003 1114
   #define E2_HYBRID_THRESHOLD     30
@@ -1007,7 +1118,7 @@
1007 1118
   /**
1008 1119
    * Use stallGuard2 to sense an obstacle and trigger an endstop.
1009 1120
    * You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
1010
-   * If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
1121
+   * X and Y homing will always be done in spreadCycle mode.
1011 1122
    *
1012 1123
    * X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
1013 1124
    * Higher values make the system LESS sensitive.
@@ -1016,27 +1127,34 @@
1016 1127
    * It is advised to set X/Y_HOME_BUMP_MM to 0.
1017 1128
    * M914 X/Y to live tune the setting
1018 1129
    */
1019
-  //#define SENSORLESS_HOMING
1130
+  //#define SENSORLESS_HOMING // TMC2130 only
1020 1131
 
1021 1132
   #if ENABLED(SENSORLESS_HOMING)
1022
-    #define X_HOMING_SENSITIVITY  19
1023
-    #define Y_HOMING_SENSITIVITY  19
1133
+    #define X_HOMING_SENSITIVITY  8
1134
+    #define Y_HOMING_SENSITIVITY  8
1024 1135
   #endif
1025 1136
 
1026 1137
   /**
1138
+   * Enable M122 debugging command for TMC stepper drivers.
1139
+   * M122 S0/1 will enable continous reporting.
1140
+   */
1141
+  //#define TMC_DEBUG
1142
+
1143
+  /**
1027 1144
    * You can set your own advanced settings by filling in predefined functions.
1028 1145
    * A list of available functions can be found on the library github page
1029 1146
    * https://github.com/teemuatlut/TMC2130Stepper
1147
+   * https://github.com/teemuatlut/TMC2208Stepper
1030 1148
    *
1031 1149
    * Example:
1032
-   * #define TMC2130_ADV() { \
1150
+   * #define TMC_ADV() { \
1033 1151
    *   stepperX.diag0_temp_prewarn(1); \
1034
-   *   stepperX.interpolate(0); \
1152
+   *   stepperY.interpolate(0); \
1035 1153
    * }
1036 1154
    */
1037
-  #define  TMC2130_ADV() {  }
1155
+  #define  TMC_ADV() {  }
1038 1156
 
1039
-#endif // HAVE_TMC2130
1157
+#endif // TMC2130 || TMC2208
1040 1158
 
1041 1159
 // @section L6470
1042 1160
 
@@ -1200,15 +1318,53 @@
1200 1318
   //#define SPEED_POWER_MAX      100      // 0-100%
1201 1319
 #endif
1202 1320
 
1203
-// @section debug
1321
+/**
1322
+ * Filament Width Sensor
1323
+ *
1324
+ * Measures the filament width in real-time and adjusts
1325
+ * flow rate to compensate for any irregularities.
1326
+ *
1327
+ * Also allows the measured filament diameter to set the
1328
+ * extrusion rate, so the slicer only has to specify the
1329
+ * volume.
1330
+ *
1331
+ * Only a single extruder is supported at this time.
1332
+ *
1333
+ *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1334
+ *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1335
+ * 301 RAMBO       : Analog input 3
1336
+ *
1337
+ * Note: May require analog pins to be defined for other boards.
1338
+ */
1339
+//#define FILAMENT_WIDTH_SENSOR
1340
+
1341
+#if ENABLED(FILAMENT_WIDTH_SENSOR)
1342
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
1343
+  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1344
+
1345
+  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1346
+  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1347
+  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1348
+
1349
+  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1350
+
1351
+  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1352
+  //#define FILAMENT_LCD_DISPLAY
1353
+#endif
1354
+
1355
+/**
1356
+ * CNC Coordinate Systems
1357
+ *
1358
+ * Enables G53 and G54-G59.3 commands to select coordinate systems
1359
+ * and G92.1 to reset the workspace to native machine space.
1360
+ */
1361
+//#define CNC_COORDINATE_SYSTEMS
1204 1362
 
1205 1363
 /**
1206 1364
  * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
1207 1365
  */
1208 1366
 #define PINS_DEBUGGING
1209 1367
 
1210
-// @section extras
1211
-
1212 1368
 /**
1213 1369
  * Auto-report temperatures with M155 S<seconds>
1214 1370
  */
@@ -1257,6 +1413,8 @@
1257 1413
 //#define CUSTOM_USER_MENUS
1258 1414
 #if ENABLED(CUSTOM_USER_MENUS)
1259 1415
   #define USER_SCRIPT_DONE "M117 User Script Done"
1416
+  #define USER_SCRIPT_AUDIBLE_FEEDBACK
1417
+  //#define USER_SCRIPT_RETURN  // Return to status screen after a script
1260 1418
 
1261 1419
   #define USER_DESC_1 "Home & UBL Info"
1262 1420
   #define USER_GCODE_1 "G28\nG29 W"
@@ -1284,6 +1442,7 @@
1284 1442
 //===========================================================================
1285 1443
 //====================== I2C Position Encoder Settings ======================
1286 1444
 //===========================================================================
1445
+
1287 1446
 /**
1288 1447
  *  I2C position encoders for closed loop control.
1289 1448
  *  Developed by Chris Barr at Aus3D.
@@ -1364,4 +1523,45 @@
1364 1523
 
1365 1524
 #endif // I2C_POSITION_ENCODERS
1366 1525
 
1526
+/**
1527
+ * MAX7219 Debug Matrix
1528
+ *
1529
+ * Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
1530
+ * display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
1531
+ *
1532
+ * Fully assembled MAX7219 boards can be found on the internet for under $2(US).
1533
+ * For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
1534
+ */
1535
+//#define MAX7219_DEBUG
1536
+#if ENABLED(MAX7219_DEBUG)
1537
+  #define MAX7219_CLK_PIN   64  // 77 on Re-ARM       // Configuration of the 3 pins to control the display
1538
+  #define MAX7219_DIN_PIN   57  // 78 on Re-ARM
1539
+  #define MAX7219_LOAD_PIN  44  // 79 on Re-ARM
1540
+
1541
+  /**
1542
+   * Sample debug features
1543
+   * If you add more debug displays, be careful to avoid conflicts!
1544
+   */
1545
+  #define MAX7219_DEBUG_PRINTER_ALIVE    // Blink corner LED of 8x8 matrix to show that the firmware is functioning
1546
+  #define MAX7219_DEBUG_STEPPER_HEAD  3  // Show the stepper queue head position on this and the next LED matrix row
1547
+  #define MAX7219_DEBUG_STEPPER_TAIL  5  // Show the stepper queue tail position on this and the next LED matrix row
1548
+
1549
+  #define MAX7219_DEBUG_STEPPER_QUEUE 0  // Show the current stepper queue depth on this and the next LED matrix row
1550
+                                         // If you experience stuttering, reboots, etc. this option can reveal how
1551
+                                         // tweaks made to the configuration are affecting the printer in real-time.
1552
+#endif
1553
+
1554
+/**
1555
+ * NanoDLP Sync support
1556
+ *
1557
+ * Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
1558
+ * string to enable synchronization with DLP projector exposure. This change will allow to use
1559
+ * [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
1560
+ */
1561
+//#define NANODLP_Z_SYNC
1562
+#if ENABLED(NANODLP_Z_SYNC)
1563
+  //#define NANODLP_ALL_AXIS  // Enables "Z_move_comp" output on any axis move.
1564
+                              // Default behaviour is limited to Z axis only.
1565
+#endif
1566
+
1367 1567
 #endif // CONFIGURATION_ADV_H

+ 1793
- 0
Marlin/example_configurations/Geeetech/GT2560/Configuration.h
파일 크기가 너무 크기때문에 변경 상태를 표시하지 않습니다.
파일 보기


+ 1769
- 0
Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h
파일 크기가 너무 크기때문에 변경 상태를 표시하지 않습니다.
파일 보기


+ 0
- 1260
Marlin/example_configurations/Infitary-i3-M508/Configuration_adv.h
파일 크기가 너무 크기때문에 변경 상태를 표시하지 않습니다.
파일 보기


Marlin/example_configurations/Infitary-i3-M508/Configuration.h → Marlin/example_configurations/Infitary/i3-M508/Configuration.h 파일 보기

@@ -37,7 +37,7 @@
37 37
  */
38 38
 #ifndef CONFIGURATION_H
39 39
 #define CONFIGURATION_H
40
-#define CONFIGURATION_H_VERSION 010100
40
+#define CONFIGURATION_H_VERSION 010107
41 41
 
42 42
 //===========================================================================
43 43
 //============================= Getting Started =============================
@@ -58,15 +58,15 @@
58 58
 //===========================================================================
59 59
 //============================= DELTA Printer ===============================
60 60
 //===========================================================================
61
-// For a Delta printer replace the configuration files with the files in the
62
-// example_configurations/delta directory.
61
+// For a Delta printer start with one of the configuration files in the
62
+// example_configurations/delta directory and customize for your machine.
63 63
 //
64 64
 
65 65
 //===========================================================================
66 66
 //============================= SCARA Printer ===============================
67 67
 //===========================================================================
68
-// For a Scara printer replace the configuration files with the files in the
69
-// example_configurations/SCARA directory.
68
+// For a SCARA printer start with the configuration files in
69
+// example_configurations/SCARA and customize for your machine.
70 70
 //
71 71
 
72 72
 // @section info
@@ -107,8 +107,9 @@
107 107
  *
108 108
  * 250000 works in most cases, but you might try a lower speed if
109 109
  * you commonly experience drop-outs during host printing.
110
+ * You may try up to 1000000 to speed up SD file transfer.
110 111
  *
111
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
112
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
112 113
  */
113 114
 #define BAUDRATE 250000
114 115
 
@@ -135,14 +136,39 @@
135 136
 // :[1, 2, 3, 4, 5]
136 137
 #define EXTRUDERS 1
137 138
 
139
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
140
+#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
141
+
138 142
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
139 143
 //#define SINGLENOZZLE
140 144
 
145
+/**
146
+ * Průša MK2 Single Nozzle Multi-Material Multiplexer, and variants.
147
+ *
148
+ * This device allows one stepper driver on a control board to drive
149
+ * two to eight stepper motors, one at a time, in a manner suitable
150
+ * for extruders.
151
+ *
152
+ * This option only allows the multiplexer to switch on tool-change.
153
+ * Additional options to configure custom E moves are pending.
154
+ */
155
+//#define MK2_MULTIPLEXER
156
+#if ENABLED(MK2_MULTIPLEXER)
157
+  // Override the default DIO selector pins here, if needed.
158
+  // Some pins files may provide defaults for these pins.
159
+  //#define E_MUX0_PIN 40  // Always Required
160
+  //#define E_MUX1_PIN 42  // Needed for 3 to 8 steppers
161
+  //#define E_MUX2_PIN 44  // Needed for 5 to 8 steppers
162
+#endif
163
+
141 164
 // A dual extruder that uses a single stepper motor
142 165
 //#define SWITCHING_EXTRUDER
143 166
 #if ENABLED(SWITCHING_EXTRUDER)
144 167
   #define SWITCHING_EXTRUDER_SERVO_NR 0
145
-  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1
168
+  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3]
169
+  #if EXTRUDERS > 3
170
+    #define SWITCHING_EXTRUDER_E23_SERVO_NR 1
171
+  #endif
146 172
 #endif
147 173
 
148 174
 // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles
@@ -154,6 +180,21 @@
154 180
 #endif
155 181
 
156 182
 /**
183
+ * Two separate X-carriages with extruders that connect to a moving part
184
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
185
+ */
186
+//#define PARKING_EXTRUDER
187
+#if ENABLED(PARKING_EXTRUDER)
188
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
189
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
190
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
191
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
192
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
193
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
194
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
195
+#endif
196
+
197
+/**
157 198
  * "Mixing Extruder"
158 199
  *   - Adds a new code, M165, to set the current mix factors.
159 200
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -298,8 +339,9 @@
298 339
 
299 340
 // Comment the following line to disable PID and enable bang-bang.
300 341
 #define PIDTEMP
301
-#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
302
-#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
342
+#define BANG_MAX 255     // Limits current to nozzle while in bang-bang mode; 255=full current
343
+#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
344
+#define PID_K1 0.95      // Smoothing factor within the PID
303 345
 #if ENABLED(PIDTEMP)
304 346
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
305 347
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -309,9 +351,9 @@
309 351
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
310 352
   #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
311 353
                                   // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
312
-  #define K1 0.95 //smoothing factor within the PID
313 354
 
314 355
   // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
356
+
315 357
   // Ultimaker
316 358
   //#define  DEFAULT_Kp 22.2
317 359
   //#define  DEFAULT_Ki 1.08
@@ -393,12 +435,13 @@
393 435
 //===========================================================================
394 436
 
395 437
 /**
396
- * Thermal Protection protects your printer from damage and fire if a
397
- * thermistor falls out or temperature sensors fail in any way.
438
+ * Thermal Protection provides additional protection to your printer from damage
439
+ * and fire. Marlin always includes safe min and max temperature ranges which
440
+ * protect against a broken or disconnected thermistor wire.
398 441
  *
399
- * The issue: If a thermistor falls out or a temperature sensor fails,
400
- * Marlin can no longer sense the actual temperature. Since a disconnected
401
- * thermistor reads as a low temperature, the firmware will keep the heater on.
442
+ * The issue: If a thermistor falls out, it will report the much lower
443
+ * temperature of the air in the room, and the the firmware will keep
444
+ * the heater on.
402 445
  *
403 446
  * If you get "Thermal Runaway" or "Heating failed" errors the
404 447
  * details can be tuned in Configuration_adv.h
@@ -532,14 +575,13 @@
532 575
 #define DEFAULT_ZJERK                  0.4
533 576
 #define DEFAULT_EJERK                  5.0
534 577
 
535
-
536 578
 //===========================================================================
537 579
 //============================= Z Probe Options =============================
538 580
 //===========================================================================
539 581
 // @section probes
540 582
 
541 583
 //
542
-// See http://marlinfw.org/configuration/probes.html
584
+// See http://marlinfw.org/docs/configuration/probes.html
543 585
 //
544 586
 
545 587
 /**
@@ -569,13 +611,12 @@
569 611
  *
570 612
  */
571 613
 //#define Z_MIN_PROBE_ENDSTOP
572
-//#define Z_MIN_PROBE_PIN Z_MAX_PIN
573 614
 
574 615
 /**
575 616
  * Probe Type
576 617
  *
577 618
  * Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
578
- * You must activate one of these to use Auto Bed Leveling below.
619
+ * Activate one of these to use Auto Bed Leveling below.
579 620
  */
580 621
 
581 622
 /**
@@ -606,14 +647,15 @@
606 647
 #endif
607 648
 
608 649
 /**
609
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
610
- * options selected below - will be disabled during probing so as to minimize
611
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
612
- * in current flowing through the wires).  This is likely most useful to users of the
613
- * BLTouch probe, but may also help those with inductive or other probe types.
650
+ * Enable one or more of the following if probing seems unreliable.
651
+ * Heaters and/or fans can be disabled during probing to minimize electrical
652
+ * noise. A delay can also be added to allow noise and vibration to settle.
653
+ * These options are most useful for the BLTouch probe, but may also improve
654
+ * readings with inductive probes and piezo sensors.
614 655
  */
615 656
 //#define PROBING_HEATERS_OFF       // Turn heaters off when probing
616 657
 //#define PROBING_FANS_OFF          // Turn fans off when probing
658
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
617 659
 
618 660
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
619 661
 //#define SOLENOID_PROBE
@@ -652,14 +694,16 @@
652 694
 // X and Y axis travel speed (mm/m) between probes
653 695
 #define XY_PROBE_SPEED 8000
654 696
 
655
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
697
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
656 698
 #define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
657 699
 
658 700
 // Speed for the "accurate" probe of each point
659 701
 #define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
660 702
 
661
-// Use double touch for probing
662
-//#define PROBE_DOUBLE_TOUCH
703
+// The number of probes to perform at each point.
704
+//   Set to 2 for a fast/slow probe, using the second probe result.
705
+//   Set to 3 or more for slow probes, averaging the results.
706
+//#define MULTIPLE_PROBING 2
663 707
 
664 708
 /**
665 709
  * Z probes require clearance when deploying, stowing, and moving between
@@ -726,6 +770,8 @@
726 770
 
727 771
 // @section homing
728 772
 
773
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
774
+
729 775
 //#define Z_HOMING_HEIGHT 4  // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
730 776
                              // Be sure you have this distance over your Z_MAX_POS in case.
731 777
 
@@ -737,18 +783,42 @@
737 783
 
738 784
 // @section machine
739 785
 
740
-// Travel limits after homing (units are in mm)
786
+// The size of the print bed
787
+#define X_BED_SIZE 205
788
+#define Y_BED_SIZE 205
789
+
790
+// Travel limits (mm) after homing, corresponding to endstop positions.
741 791
 #define X_MIN_POS 0
742 792
 #define Y_MIN_POS 0
743 793
 #define Z_MIN_POS 0
744
-#define X_MAX_POS 205
745
-#define Y_MAX_POS 205
794
+#define X_MAX_POS X_BED_SIZE
795
+#define Y_MAX_POS Y_BED_SIZE
746 796
 #define Z_MAX_POS 185
747 797
 
748
-// If enabled, axes won't move below MIN_POS in response to movement commands.
798
+/**
799
+ * Software Endstops
800
+ *
801
+ * - Prevent moves outside the set machine bounds.
802
+ * - Individual axes can be disabled, if desired.
803
+ * - X and Y only apply to Cartesian robots.
804
+ * - Use 'M211' to set software endstops on/off or report current state
805
+ */
806
+
807
+// Min software endstops curtail movement below minimum coordinate bounds
749 808
 #define MIN_SOFTWARE_ENDSTOPS
750
-// If enabled, axes won't move above MAX_POS in response to movement commands.
809
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
810
+  #define MIN_SOFTWARE_ENDSTOP_X
811
+  #define MIN_SOFTWARE_ENDSTOP_Y
812
+  #define MIN_SOFTWARE_ENDSTOP_Z
813
+#endif
814
+
815
+// Max software endstops curtail movement above maximum coordinate bounds
751 816
 #define MAX_SOFTWARE_ENDSTOPS
817
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
818
+  #define MAX_SOFTWARE_ENDSTOP_X
819
+  #define MAX_SOFTWARE_ENDSTOP_Y
820
+  #define MAX_SOFTWARE_ENDSTOP_Z
821
+#endif
752 822
 
753 823
 /**
754 824
  * Filament Runout Sensor
@@ -768,7 +838,7 @@
768 838
 //===========================================================================
769 839
 //=============================== Bed Leveling ==============================
770 840
 //===========================================================================
771
-// @section bedlevel
841
+// @section calibrate
772 842
 
773 843
 /**
774 844
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -794,12 +864,7 @@
794 864
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
795 865
  *   A comprehensive bed leveling system combining the features and benefits
796 866
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
797
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
798
- *   for Cartesian Printers. That said, it was primarily designed to correct
799
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
800
- *   please post an issue if something doesn't work correctly. Initially,
801
- *   you will need to set a reduced bed size so you have a rectangular area
802
- *   to test on.
867
+ *   Validation and Mesh Editing systems.
803 868
  *
804 869
  * - MESH_BED_LEVELING
805 870
  *   Probe a grid manually
@@ -826,6 +891,24 @@
826 891
   // at which point movement will be level to the machine's XY plane.
827 892
   // The height can be set with M420 Z<height>
828 893
   #define ENABLE_LEVELING_FADE_HEIGHT
894
+
895
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
896
+  // split up moves into short segments like a Delta. This follows the
897
+  // contours of the bed more closely than edge-to-edge straight moves.
898
+  #define SEGMENT_LEVELED_MOVES
899
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
900
+
901
+  /**
902
+   * Enable the G26 Mesh Validation Pattern tool.
903
+   */
904
+  //#define G26_MESH_VALIDATION   // Enable G26 mesh validation
905
+  #if ENABLED(G26_MESH_VALIDATION)
906
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
907
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
908
+    #define MESH_TEST_HOTEND_TEMP   205.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
909
+    #define MESH_TEST_BED_TEMP       60.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
910
+  #endif
911
+
829 912
 #endif
830 913
 
831 914
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -881,17 +964,21 @@
881 964
   //========================= Unified Bed Leveling ============================
882 965
   //===========================================================================
883 966
 
884
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
967
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
968
+
969
+  #define MESH_INSET 1              // Mesh inset margin on print area
885 970
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
886 971
   #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
887
-  #define UBL_PROBE_PT_1_X 39       // These set the probe locations for when UBL does a 3-Point leveling
888
-  #define UBL_PROBE_PT_1_Y 180      // of the mesh.
972
+
973
+  #define UBL_PROBE_PT_1_X 39       // Probing points for 3-Point leveling of the mesh
974
+  #define UBL_PROBE_PT_1_Y 180
889 975
   #define UBL_PROBE_PT_2_X 39
890 976
   #define UBL_PROBE_PT_2_Y 20
891 977
   #define UBL_PROBE_PT_3_X 180
892 978
   #define UBL_PROBE_PT_3_Y 20
893
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
979
+
894 980
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
981
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
895 982
 
896 983
 #elif ENABLED(MESH_BED_LEVELING)
897 984
 
@@ -918,6 +1005,9 @@
918 1005
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
919 1006
 #endif
920 1007
 
1008
+// Add a menu item to move between bed corners for manual bed adjustment
1009
+//#define LEVEL_BED_CORNERS
1010
+
921 1011
 /**
922 1012
  * Commands to execute at the end of G29 probing.
923 1013
  * Useful to retract or move the Z probe out of the way.
@@ -948,14 +1038,71 @@
948 1038
 //#define Z_SAFE_HOMING
949 1039
 
950 1040
 #if ENABLED(Z_SAFE_HOMING)
951
-  #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
952
-  #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
1041
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1042
+  #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2)    // Y point for Z homing when homing all axes (G28).
953 1043
 #endif
954 1044
 
955 1045
 // Homing speeds (mm/m)
956 1046
 #define HOMING_FEEDRATE_XY (50*60)
957 1047
 #define HOMING_FEEDRATE_Z  (4*60)
958 1048
 
1049
+// @section calibrate
1050
+
1051
+/**
1052
+ * Bed Skew Compensation
1053
+ *
1054
+ * This feature corrects for misalignment in the XYZ axes.
1055
+ *
1056
+ * Take the following steps to get the bed skew in the XY plane:
1057
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1058
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1059
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1060
+ *  4. For XY_SIDE_AD measure the edge A to D
1061
+ *
1062
+ * Marlin automatically computes skew factors from these measurements.
1063
+ * Skew factors may also be computed and set manually:
1064
+ *
1065
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1066
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1067
+ *
1068
+ * If desired, follow the same procedure for XZ and YZ.
1069
+ * Use these diagrams for reference:
1070
+ *
1071
+ *    Y                     Z                     Z
1072
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1073
+ *    |    /       /        |    /       /        |    /       /
1074
+ *    |   /       /         |   /       /         |   /       /
1075
+ *    |  A-------D          |  A-------D          |  A-------D
1076
+ *    +-------------->X     +-------------->X     +-------------->Y
1077
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1078
+ */
1079
+//#define SKEW_CORRECTION
1080
+
1081
+#if ENABLED(SKEW_CORRECTION)
1082
+  // Input all length measurements here:
1083
+  #define XY_DIAG_AC 282.8427124746
1084
+  #define XY_DIAG_BD 282.8427124746
1085
+  #define XY_SIDE_AD 200
1086
+
1087
+  // Or, set the default skew factors directly here
1088
+  // to override the above measurements:
1089
+  #define XY_SKEW_FACTOR 0.0
1090
+
1091
+  //#define SKEW_CORRECTION_FOR_Z
1092
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1093
+    #define XZ_DIAG_AC 282.8427124746
1094
+    #define XZ_DIAG_BD 282.8427124746
1095
+    #define YZ_DIAG_AC 282.8427124746
1096
+    #define YZ_DIAG_BD 282.8427124746
1097
+    #define YZ_SIDE_AD 200
1098
+    #define XZ_SKEW_FACTOR 0.0
1099
+    #define YZ_SKEW_FACTOR 0.0
1100
+  #endif
1101
+
1102
+  // Enable this option for M852 to set skew at runtime
1103
+  //#define SKEW_CORRECTION_GCODE
1104
+#endif
1105
+
959 1106
 //=============================================================================
960 1107
 //============================= Additional Features ===========================
961 1108
 //=============================================================================
@@ -971,11 +1118,8 @@
971 1118
 // M502 - reverts to the default "factory settings".  You still need to store them in EEPROM afterwards if you want to.
972 1119
 //
973 1120
 //#define EEPROM_SETTINGS // Enable for M500 and M501 commands
974
-
975
-#if ENABLED(EEPROM_SETTINGS)
976
-  // To disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
977
-  #define EEPROM_CHITCHAT // Please keep turned on if you can.
978
-#endif
1121
+//#define DISABLE_M503    // Saves ~2700 bytes of PROGMEM. Disable for release!
1122
+#define EEPROM_CHITCHAT   // Give feedback on EEPROM commands. Disable to save PROGMEM.
979 1123
 
980 1124
 //
981 1125
 // Host Keepalive
@@ -985,11 +1129,12 @@
985 1129
 //
986 1130
 #define HOST_KEEPALIVE_FEATURE        // Disable this if your host doesn't like keepalive messages
987 1131
 #define DEFAULT_KEEPALIVE_INTERVAL 2  // Number of seconds between "busy" messages. Set with M113.
1132
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
988 1133
 
989 1134
 //
990 1135
 // M100 Free Memory Watcher
991 1136
 //
992
-//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1137
+//#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
993 1138
 
994 1139
 //
995 1140
 // G20/G21 Inch mode support
@@ -1134,10 +1279,11 @@
1134 1279
  *
1135 1280
  * Select the language to display on the LCD. These languages are available:
1136 1281
  *
1137
- *    en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
1138
- *    kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
1282
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1283
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1284
+ *    tr, uk, zh_CN, zh_TW, test
1139 1285
  *
1140
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
1286
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1141 1287
  */
1142 1288
 #define LCD_LANGUAGE en
1143 1289
 
@@ -1159,7 +1305,7 @@
1159 1305
  *  - Click the controller to view the LCD menu
1160 1306
  *  - The LCD will display Japanese, Western, or Cyrillic text
1161 1307
  *
1162
- * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1308
+ * See http://marlinfw.org/docs/development/lcd_language.html
1163 1309
  *
1164 1310
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1165 1311
  */
@@ -1265,8 +1411,8 @@
1265 1411
 // Note: Test audio output with the G-Code:
1266 1412
 //  M300 S<frequency Hz> P<duration ms>
1267 1413
 //
1268
-//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
1269
-//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
1414
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
1415
+//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
1270 1416
 
1271 1417
 //
1272 1418
 // CONTROLLER TYPE: Standard
@@ -1286,12 +1432,6 @@
1286 1432
 //#define ULTIPANEL
1287 1433
 
1288 1434
 //
1289
-// Cartesio UI
1290
-// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
1291
-//
1292
-//#define CARTESIO_UI
1293
-
1294
-//
1295 1435
 // PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
1296 1436
 // http://reprap.org/wiki/PanelOne
1297 1437
 //
@@ -1374,6 +1514,24 @@
1374 1514
 //#define BQ_LCD_SMART_CONTROLLER
1375 1515
 
1376 1516
 //
1517
+// Cartesio UI
1518
+// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
1519
+//
1520
+//#define CARTESIO_UI
1521
+
1522
+//
1523
+// ANET and Tronxy Controller supported displays.
1524
+//
1525
+//#define ZONESTAR_LCD            // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1526
+                                  // This LCD is known to be susceptible to electrical interference
1527
+                                  // which scrambles the display.  Pressing any button clears it up.
1528
+                                  // This is a LCD2004 display with 5 analog buttons.
1529
+
1530
+//#define ANET_FULL_GRAPHICS_LCD  // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1531
+                                  // A clone of the RepRapDiscount full graphics display but with
1532
+                                  // different pins/wiring (see pins_ANET_10.h).
1533
+
1534
+//
1377 1535
 // LCD for Melzi Card with Graphical LCD
1378 1536
 //
1379 1537
 //#define LCD_FOR_MELZI
@@ -1394,6 +1552,9 @@
1394 1552
 //
1395 1553
 // Sainsmart YW Robot (LCM1602) LCD Display
1396 1554
 //
1555
+// Note: This controller requires F.Malpartida's LiquidCrystal_I2C library
1556
+// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home
1557
+//
1397 1558
 //#define LCD_I2C_SAINSMART_YWROBOT
1398 1559
 
1399 1560
 //
@@ -1446,6 +1607,40 @@
1446 1607
 //
1447 1608
 //#define OLED_PANEL_TINYBOY2
1448 1609
 
1610
+//
1611
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1612
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1613
+//
1614
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1615
+
1616
+//
1617
+// MKS MINI12864 with graphic controller and SD support
1618
+// http://reprap.org/wiki/MKS_MINI_12864
1619
+//
1620
+//#define MKS_MINI_12864
1621
+
1622
+//
1623
+// Factory display for Creality CR-10
1624
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1625
+//
1626
+// This is RAMPS-compatible using a single 10-pin connector.
1627
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1628
+//
1629
+//#define CR10_STOCKDISPLAY
1630
+
1631
+//
1632
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1633
+// http://reprap.org/wiki/MKS_12864OLED
1634
+//
1635
+// Tiny, but very sharp OLED display
1636
+//
1637
+//#define MKS_12864OLED
1638
+
1639
+// Silvergate GLCD controller
1640
+// http://github.com/android444/Silvergate
1641
+//
1642
+//#define SILVER_GATE_GLCD_CONTROLLER
1643
+
1449 1644
 //=============================================================================
1450 1645
 //=============================== Extra Features ==============================
1451 1646
 //=============================================================================
@@ -1484,12 +1679,15 @@
1484 1679
 // SkeinForge sends the wrong arc g-codes when using Arc Point as fillet procedure
1485 1680
 //#define SF_ARC_FIX
1486 1681
 
1487
-// Support for the BariCUDA Paste Extruder.
1682
+// Support for the BariCUDA Paste Extruder
1488 1683
 //#define BARICUDA
1489 1684
 
1490
-//define BlinkM/CyzRgb Support
1685
+// Support for BlinkM/CyzRgb
1491 1686
 //#define BLINKM
1492 1687
 
1688
+// Support for PCA9632 PWM LED driver
1689
+//#define PCA9632
1690
+
1493 1691
 /**
1494 1692
  * RGB LED / LED Strip Control
1495 1693
  *
@@ -1499,16 +1697,22 @@
1499 1697
  * Adds the M150 command to set the LED (or LED strip) color.
1500 1698
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1501 1699
  * luminance values can be set from 0 to 255.
1700
+ * For Neopixel LED an overall brightness parameter is also available.
1502 1701
  *
1503 1702
  * *** CAUTION ***
1504 1703
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1505 1704
  *  as the Arduino cannot handle the current the LEDs will require.
1506 1705
  *  Failure to follow this precaution can destroy your Arduino!
1706
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1707
+ *  more current than the Arduino 5V linear regulator can produce.
1507 1708
  * *** CAUTION ***
1508 1709
  *
1710
+ * LED Type. Enable only one of the following two options.
1711
+ *
1509 1712
  */
1510 1713
 //#define RGB_LED
1511 1714
 //#define RGBW_LED
1715
+
1512 1716
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1513 1717
   #define RGB_LED_R_PIN 34
1514 1718
   #define RGB_LED_G_PIN 43
@@ -1516,6 +1720,17 @@
1516 1720
   #define RGB_LED_W_PIN -1
1517 1721
 #endif
1518 1722
 
1723
+// Support for Adafruit Neopixel LED driver
1724
+//#define NEOPIXEL_LED
1725
+#if ENABLED(NEOPIXEL_LED)
1726
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1727
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1728
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1729
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1730
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1731
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1732
+#endif
1733
+
1519 1734
 /**
1520 1735
  * Printer Event LEDs
1521 1736
  *
@@ -1527,68 +1742,32 @@
1527 1742
  *  - Change to green once print has finished
1528 1743
  *  - Turn off after the print has finished and the user has pushed a button
1529 1744
  */
1530
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1745
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1531 1746
   #define PRINTER_EVENT_LEDS
1532 1747
 #endif
1533 1748
 
1534
-/*********************************************************************\
1535
-* R/C SERVO support
1536
-* Sponsored by TrinityLabs, Reworked by codexmas
1537
-**********************************************************************/
1749
+/**
1750
+ * R/C SERVO support
1751
+ * Sponsored by TrinityLabs, Reworked by codexmas
1752
+ */
1538 1753
 
1539
-// Number of servos
1540
-//
1541
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1542
-// set it manually if you have more servos than extruders and wish to manually control some
1543
-// leaving it undefined or defining as 0 will disable the servo subsystem
1544
-// If unsure, leave commented / disabled
1545
-//
1754
+/**
1755
+ * Number of servos
1756
+ *
1757
+ * For some servo-related options NUM_SERVOS will be set automatically.
1758
+ * Set this manually if there are extra servos needing manual control.
1759
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1760
+ */
1546 1761
 //#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
1547 1762
 
1548 1763
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1549 1764
 // 300ms is a good value but you can try less delay.
1550 1765
 // If the servo can't reach the requested position, increase it.
1551
-#define SERVO_DELAY 300
1766
+#define SERVO_DELAY { 300 }
1552 1767
 
1553 1768
 // Servo deactivation
1554 1769
 //
1555 1770
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1556 1771
 //#define DEACTIVATE_SERVOS_AFTER_MOVE
1557 1772
 
1558
-/**
1559
- * Filament Width Sensor
1560
- *
1561
- * Measures the filament width in real-time and adjusts
1562
- * flow rate to compensate for any irregularities.
1563
- *
1564
- * Also allows the measured filament diameter to set the
1565
- * extrusion rate, so the slicer only has to specify the
1566
- * volume.
1567
- *
1568
- * Only a single extruder is supported at this time.
1569
- *
1570
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1571
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1572
- * 301 RAMBO       : Analog input 3
1573
- *
1574
- * Note: May require analog pins to be defined for other boards.
1575
- */
1576
-//#define FILAMENT_WIDTH_SENSOR
1577
-
1578
-#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00   // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
1579
-
1580
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1581
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1582
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1583
-
1584
-  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1585
-  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1586
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1587
-
1588
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1589
-
1590
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1591
-  //#define FILAMENT_LCD_DISPLAY
1592
-#endif
1593
-
1594 1773
 #endif // CONFIGURATION_H

+ 1567
- 0
Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h
파일 크기가 너무 크기때문에 변경 상태를 표시하지 않습니다.
파일 보기


Marlin/example_configurations/M150/Configuration.h → Marlin/example_configurations/Malyan/M150/Configuration.h 파일 보기

@@ -42,7 +42,7 @@
42 42
  */
43 43
 #ifndef CONFIGURATION_H
44 44
 #define CONFIGURATION_H
45
-#define CONFIGURATION_H_VERSION 010100
45
+#define CONFIGURATION_H_VERSION 010107
46 46
 
47 47
 //===========================================================================
48 48
 //============================= Getting Started =============================
@@ -112,8 +112,9 @@
112 112
  *
113 113
  * 250000 works in most cases, but you might try a lower speed if
114 114
  * you commonly experience drop-outs during host printing.
115
+ * You may try up to 1000000 to speed up SD file transfer.
115 116
  *
116
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
117
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
117 118
  */
118 119
 #define BAUDRATE 115200
119 120
 
@@ -140,6 +141,9 @@
140 141
 // :[1, 2, 3, 4, 5]
141 142
 #define EXTRUDERS 1
142 143
 
144
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
145
+#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
146
+
143 147
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
144 148
 //#define SINGLENOZZLE
145 149
 
@@ -166,7 +170,10 @@
166 170
 //#define SWITCHING_EXTRUDER
167 171
 #if ENABLED(SWITCHING_EXTRUDER)
168 172
   #define SWITCHING_EXTRUDER_SERVO_NR 0
169
-  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1
173
+  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3]
174
+  #if EXTRUDERS > 3
175
+    #define SWITCHING_EXTRUDER_E23_SERVO_NR 1
176
+  #endif
170 177
 #endif
171 178
 
172 179
 // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles
@@ -178,6 +185,21 @@
178 185
 #endif
179 186
 
180 187
 /**
188
+ * Two separate X-carriages with extruders that connect to a moving part
189
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
190
+ */
191
+//#define PARKING_EXTRUDER
192
+#if ENABLED(PARKING_EXTRUDER)
193
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
194
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
195
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
196
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
197
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
198
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
199
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
200
+#endif
201
+
202
+/**
181 203
  * "Mixing Extruder"
182 204
  *   - Adds a new code, M165, to set the current mix factors.
183 205
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -305,6 +327,7 @@
305 327
 #define HEATER_1_MINTEMP 5
306 328
 #define HEATER_2_MINTEMP 5
307 329
 #define HEATER_3_MINTEMP 5
330
+#define HEATER_4_MINTEMP 5
308 331
 #define BED_MINTEMP 5
309 332
 
310 333
 // When temperature exceeds max temp, your heater will be switched off.
@@ -314,6 +337,7 @@
314 337
 #define HEATER_1_MAXTEMP 275
315 338
 #define HEATER_2_MAXTEMP 275
316 339
 #define HEATER_3_MAXTEMP 275
340
+#define HEATER_4_MAXTEMP 275
317 341
 #define BED_MAXTEMP 150
318 342
 
319 343
 //===========================================================================
@@ -323,8 +347,9 @@
323 347
 
324 348
 // Comment the following line to disable PID and enable bang-bang.
325 349
 #define PIDTEMP
326
-#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
327
-#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
350
+#define BANG_MAX 255     // Limits current to nozzle while in bang-bang mode; 255=full current
351
+#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
352
+#define PID_K1 0.95      // Smoothing factor within the PID
328 353
 #if ENABLED(PIDTEMP)
329 354
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
330 355
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -334,7 +359,6 @@
334 359
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
335 360
   #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
336 361
                                   // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
337
-  #define K1 0.95 //smoothing factor within the PID
338 362
 
339 363
   // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
340 364
 
@@ -415,12 +439,13 @@
415 439
 //===========================================================================
416 440
 
417 441
 /**
418
- * Thermal Protection protects your printer from damage and fire if a
419
- * thermistor falls out or temperature sensors fail in any way.
442
+ * Thermal Protection provides additional protection to your printer from damage
443
+ * and fire. Marlin always includes safe min and max temperature ranges which
444
+ * protect against a broken or disconnected thermistor wire.
420 445
  *
421
- * The issue: If a thermistor falls out or a temperature sensor fails,
422
- * Marlin can no longer sense the actual temperature. Since a disconnected
423
- * thermistor reads as a low temperature, the firmware will keep the heater on.
446
+ * The issue: If a thermistor falls out, it will report the much lower
447
+ * temperature of the air in the room, and the the firmware will keep
448
+ * the heater on.
424 449
  *
425 450
  * If you get "Thermal Runaway" or "Heating failed" errors the
426 451
  * details can be tuned in Configuration_adv.h
@@ -566,14 +591,13 @@
566 591
 #define DEFAULT_ZJERK                 0.40
567 592
 #define DEFAULT_EJERK                 5.0
568 593
 
569
-
570 594
 //===========================================================================
571 595
 //============================= Z Probe Options =============================
572 596
 //===========================================================================
573 597
 // @section probes
574 598
 
575 599
 //
576
-// See http://marlinfw.org/configuration/probes.html
600
+// See http://marlinfw.org/docs/configuration/probes.html
577 601
 //
578 602
 
579 603
 /**
@@ -639,14 +663,15 @@
639 663
 #endif
640 664
 
641 665
 /**
642
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
643
- * options selected below - will be disabled during probing so as to minimize
644
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
645
- * in current flowing through the wires).  This is likely most useful to users of the
646
- * BLTouch probe, but may also help those with inductive or other probe types.
666
+ * Enable one or more of the following if probing seems unreliable.
667
+ * Heaters and/or fans can be disabled during probing to minimize electrical
668
+ * noise. A delay can also be added to allow noise and vibration to settle.
669
+ * These options are most useful for the BLTouch probe, but may also improve
670
+ * readings with inductive probes and piezo sensors.
647 671
  */
648 672
 //#define PROBING_HEATERS_OFF       // Turn heaters off when probing
649 673
 //#define PROBING_FANS_OFF          // Turn fans off when probing
674
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
650 675
 
651 676
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
652 677
 //#define SOLENOID_PROBE
@@ -689,14 +714,16 @@
689 714
 // X and Y axis travel speed (mm/m) between probes
690 715
 //#define XY_PROBE_SPEED 8000
691 716
 
692
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
717
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
693 718
 //#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
694 719
 
695 720
 // Speed for the "accurate" probe of each point
696 721
 //#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
697 722
 
698
-// Use double touch for probing
699
-//#define PROBE_DOUBLE_TOUCH
723
+// The number of probes to perform at each point.
724
+//   Set to 2 for a fast/slow probe, using the second probe result.
725
+//   Set to 3 or more for slow probes, averaging the results.
726
+//#define MULTIPLE_PROBING 2
700 727
 
701 728
 /**
702 729
  * Z probes require clearance when deploying, stowing, and moving between
@@ -763,6 +790,8 @@
763 790
 
764 791
 // @section homing
765 792
 
793
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
794
+
766 795
 //#define Z_HOMING_HEIGHT 4  // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
767 796
                              // Be sure you have this distance over your Z_MAX_POS in case.
768 797
 
@@ -774,18 +803,42 @@
774 803
 
775 804
 // @section machine
776 805
 
777
-// Travel limits after homing (units are in mm)
806
+// The size of the print bed
807
+#define X_BED_SIZE 200
808
+#define Y_BED_SIZE 200
809
+
810
+// Travel limits (mm) after homing, corresponding to endstop positions.
778 811
 #define X_MIN_POS 0
779 812
 #define Y_MIN_POS 0
780 813
 #define Z_MIN_POS 0
781
-#define X_MAX_POS 200
782
-#define Y_MAX_POS 200
814
+#define X_MAX_POS X_BED_SIZE
815
+#define Y_MAX_POS Y_BED_SIZE
783 816
 #define Z_MAX_POS 180
784 817
 
785
-// If enabled, axes won't move below MIN_POS in response to movement commands.
818
+/**
819
+ * Software Endstops
820
+ *
821
+ * - Prevent moves outside the set machine bounds.
822
+ * - Individual axes can be disabled, if desired.
823
+ * - X and Y only apply to Cartesian robots.
824
+ * - Use 'M211' to set software endstops on/off or report current state
825
+ */
826
+
827
+// Min software endstops curtail movement below minimum coordinate bounds
786 828
 #define MIN_SOFTWARE_ENDSTOPS
787
-// If enabled, axes won't move above MAX_POS in response to movement commands.
829
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
830
+  #define MIN_SOFTWARE_ENDSTOP_X
831
+  #define MIN_SOFTWARE_ENDSTOP_Y
832
+  #define MIN_SOFTWARE_ENDSTOP_Z
833
+#endif
834
+
835
+// Max software endstops curtail movement above maximum coordinate bounds
788 836
 #define MAX_SOFTWARE_ENDSTOPS
837
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
838
+  #define MAX_SOFTWARE_ENDSTOP_X
839
+  #define MAX_SOFTWARE_ENDSTOP_Y
840
+  #define MAX_SOFTWARE_ENDSTOP_Z
841
+#endif
789 842
 
790 843
 /**
791 844
  * Filament Runout Sensor
@@ -805,7 +858,7 @@
805 858
 //===========================================================================
806 859
 //=============================== Bed Leveling ==============================
807 860
 //===========================================================================
808
-// @section bedlevel
861
+// @section calibrate
809 862
 
810 863
 /**
811 864
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -831,12 +884,7 @@
831 884
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
832 885
  *   A comprehensive bed leveling system combining the features and benefits
833 886
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
834
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
835
- *   for Cartesian Printers. That said, it was primarily designed to correct
836
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
837
- *   please post an issue if something doesn't work correctly. Initially,
838
- *   you will need to set a reduced bed size so you have a rectangular area
839
- *   to test on.
887
+ *   Validation and Mesh Editing systems.
840 888
  *
841 889
  * - MESH_BED_LEVELING
842 890
  *   Probe a grid manually
@@ -867,6 +915,24 @@
867 915
   // at which point movement will be level to the machine's XY plane.
868 916
   // The height can be set with M420 Z<height>
869 917
   #define ENABLE_LEVELING_FADE_HEIGHT
918
+
919
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
920
+  // split up moves into short segments like a Delta. This follows the
921
+  // contours of the bed more closely than edge-to-edge straight moves.
922
+  #define SEGMENT_LEVELED_MOVES
923
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
924
+
925
+  /**
926
+   * Enable the G26 Mesh Validation Pattern tool.
927
+   */
928
+  //#define G26_MESH_VALIDATION   // Enable G26 mesh validation
929
+  #if ENABLED(G26_MESH_VALIDATION)
930
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
931
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
932
+    #define MESH_TEST_HOTEND_TEMP   205.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
933
+    #define MESH_TEST_BED_TEMP       60.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
934
+  #endif
935
+
870 936
 #endif
871 937
 
872 938
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -922,7 +988,9 @@
922 988
   //========================= Unified Bed Leveling ============================
923 989
   //===========================================================================
924 990
 
925
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
991
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
992
+
993
+  #define MESH_INSET 1              // Mesh inset margin on print area
926 994
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
927 995
   #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
928 996
 
@@ -933,8 +1001,8 @@
933 1001
   #define UBL_PROBE_PT_3_X 180
934 1002
   #define UBL_PROBE_PT_3_Y 20
935 1003
 
936
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
937 1004
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
1005
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
938 1006
 
939 1007
 #elif ENABLED(MESH_BED_LEVELING)
940 1008
 
@@ -961,6 +1029,9 @@
961 1029
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
962 1030
 #endif
963 1031
 
1032
+// Add a menu item to move between bed corners for manual bed adjustment
1033
+//#define LEVEL_BED_CORNERS
1034
+
964 1035
 /**
965 1036
  * Commands to execute at the end of G29 probing.
966 1037
  * Useful to retract or move the Z probe out of the way.
@@ -991,14 +1062,71 @@
991 1062
 //#define Z_SAFE_HOMING
992 1063
 
993 1064
 #if ENABLED(Z_SAFE_HOMING)
994
-  #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
995
-  #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
1065
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1066
+  #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2)    // Y point for Z homing when homing all axes (G28).
996 1067
 #endif
997 1068
 
998 1069
 // Homing speeds (mm/m)
999 1070
 #define HOMING_FEEDRATE_XY (50*60)
1000 1071
 #define HOMING_FEEDRATE_Z  (4*60)
1001 1072
 
1073
+// @section calibrate
1074
+
1075
+/**
1076
+ * Bed Skew Compensation
1077
+ *
1078
+ * This feature corrects for misalignment in the XYZ axes.
1079
+ *
1080
+ * Take the following steps to get the bed skew in the XY plane:
1081
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1082
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1083
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1084
+ *  4. For XY_SIDE_AD measure the edge A to D
1085
+ *
1086
+ * Marlin automatically computes skew factors from these measurements.
1087
+ * Skew factors may also be computed and set manually:
1088
+ *
1089
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1090
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1091
+ *
1092
+ * If desired, follow the same procedure for XZ and YZ.
1093
+ * Use these diagrams for reference:
1094
+ *
1095
+ *    Y                     Z                     Z
1096
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1097
+ *    |    /       /        |    /       /        |    /       /
1098
+ *    |   /       /         |   /       /         |   /       /
1099
+ *    |  A-------D          |  A-------D          |  A-------D
1100
+ *    +-------------->X     +-------------->X     +-------------->Y
1101
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1102
+ */
1103
+//#define SKEW_CORRECTION
1104
+
1105
+#if ENABLED(SKEW_CORRECTION)
1106
+  // Input all length measurements here:
1107
+  #define XY_DIAG_AC 282.8427124746
1108
+  #define XY_DIAG_BD 282.8427124746
1109
+  #define XY_SIDE_AD 200
1110
+
1111
+  // Or, set the default skew factors directly here
1112
+  // to override the above measurements:
1113
+  #define XY_SKEW_FACTOR 0.0
1114
+
1115
+  //#define SKEW_CORRECTION_FOR_Z
1116
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1117
+    #define XZ_DIAG_AC 282.8427124746
1118
+    #define XZ_DIAG_BD 282.8427124746
1119
+    #define YZ_DIAG_AC 282.8427124746
1120
+    #define YZ_DIAG_BD 282.8427124746
1121
+    #define YZ_SIDE_AD 200
1122
+    #define XZ_SKEW_FACTOR 0.0
1123
+    #define YZ_SKEW_FACTOR 0.0
1124
+  #endif
1125
+
1126
+  // Enable this option for M852 to set skew at runtime
1127
+  //#define SKEW_CORRECTION_GCODE
1128
+#endif
1129
+
1002 1130
 //=============================================================================
1003 1131
 //============================= Additional Features ===========================
1004 1132
 //=============================================================================
@@ -1025,11 +1153,12 @@
1025 1153
 //
1026 1154
 #define HOST_KEEPALIVE_FEATURE        // Disable this if your host doesn't like keepalive messages
1027 1155
 #define DEFAULT_KEEPALIVE_INTERVAL 2  // Number of seconds between "busy" messages. Set with M113.
1156
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
1028 1157
 
1029 1158
 //
1030 1159
 // M100 Free Memory Watcher
1031 1160
 //
1032
-//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1161
+//#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
1033 1162
 
1034 1163
 //
1035 1164
 // G20/G21 Inch mode support
@@ -1174,11 +1303,11 @@
1174 1303
  *
1175 1304
  * Select the language to display on the LCD. These languages are available:
1176 1305
  *
1177
- *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
1178
- *    it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
1179
- *    zh_CN, zh_TW, test
1306
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1307
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1308
+ *    tr, uk, zh_CN, zh_TW, test
1180 1309
  *
1181
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1310
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1182 1311
  */
1183 1312
 #define LCD_LANGUAGE en
1184 1313
 
@@ -1200,7 +1329,7 @@
1200 1329
  *  - Click the controller to view the LCD menu
1201 1330
  *  - The LCD will display Japanese, Western, or Cyrillic text
1202 1331
  *
1203
- * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1332
+ * See http://marlinfw.org/docs/development/lcd_language.html
1204 1333
  *
1205 1334
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1206 1335
  */
@@ -1306,8 +1435,8 @@
1306 1435
 // Note: Test audio output with the G-Code:
1307 1436
 //  M300 S<frequency Hz> P<duration ms>
1308 1437
 //
1309
-//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
1310
-//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
1438
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
1439
+//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
1311 1440
 
1312 1441
 //
1313 1442
 // CONTROLLER TYPE: Standard
@@ -1415,11 +1544,13 @@
1415 1544
 //#define CARTESIO_UI
1416 1545
 
1417 1546
 //
1418
-// ANET_10 Controller supported displays.
1547
+// ANET and Tronxy Controller supported displays.
1419 1548
 //
1420
-//#define ANET_KEYPAD_LCD         // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1549
+//#define ZONESTAR_LCD            // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1421 1550
                                   // This LCD is known to be susceptible to electrical interference
1422 1551
                                   // which scrambles the display.  Pressing any button clears it up.
1552
+                                  // This is a LCD2004 display with 5 analog buttons.
1553
+
1423 1554
 //#define ANET_FULL_GRAPHICS_LCD  // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1424 1555
                                   // A clone of the RepRapDiscount full graphics display but with
1425 1556
                                   // different pins/wiring (see pins_ANET_10.h).
@@ -1479,11 +1610,6 @@
1479 1610
 //#define U8GLIB_SSD1306
1480 1611
 
1481 1612
 //
1482
-// TinyBoy2 128x64 OLED / Encoder Panel
1483
-//
1484
-//#define OLED_PANEL_TINYBOY2
1485
-
1486
-//
1487 1613
 // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules
1488 1614
 //
1489 1615
 //#define SAV_3DGLCD
@@ -1500,6 +1626,45 @@
1500 1626
 //
1501 1627
 //#define SAV_3DLCD
1502 1628
 
1629
+//
1630
+// TinyBoy2 128x64 OLED / Encoder Panel
1631
+//
1632
+//#define OLED_PANEL_TINYBOY2
1633
+
1634
+//
1635
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1636
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1637
+//
1638
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1639
+
1640
+//
1641
+// MKS MINI12864 with graphic controller and SD support
1642
+// http://reprap.org/wiki/MKS_MINI_12864
1643
+//
1644
+//#define MKS_MINI_12864
1645
+
1646
+//
1647
+// Factory display for Creality CR-10
1648
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1649
+//
1650
+// This is RAMPS-compatible using a single 10-pin connector.
1651
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1652
+//
1653
+//#define CR10_STOCKDISPLAY
1654
+
1655
+//
1656
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1657
+// http://reprap.org/wiki/MKS_12864OLED
1658
+//
1659
+// Tiny, but very sharp OLED display
1660
+//
1661
+//#define MKS_12864OLED
1662
+
1663
+// Silvergate GLCD controller
1664
+// http://github.com/android444/Silvergate
1665
+//
1666
+//#define SILVER_GATE_GLCD_CONTROLLER
1667
+
1503 1668
 //=============================================================================
1504 1669
 //=============================== Extra Features ==============================
1505 1670
 //=============================================================================
@@ -1556,16 +1721,22 @@
1556 1721
  * Adds the M150 command to set the LED (or LED strip) color.
1557 1722
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1558 1723
  * luminance values can be set from 0 to 255.
1724
+ * For Neopixel LED an overall brightness parameter is also available.
1559 1725
  *
1560 1726
  * *** CAUTION ***
1561 1727
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1562 1728
  *  as the Arduino cannot handle the current the LEDs will require.
1563 1729
  *  Failure to follow this precaution can destroy your Arduino!
1730
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1731
+ *  more current than the Arduino 5V linear regulator can produce.
1564 1732
  * *** CAUTION ***
1565 1733
  *
1734
+ * LED Type. Enable only one of the following two options.
1735
+ *
1566 1736
  */
1567 1737
 //#define RGB_LED
1568 1738
 //#define RGBW_LED
1739
+
1569 1740
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1570 1741
   #define RGB_LED_R_PIN 34
1571 1742
   #define RGB_LED_G_PIN 43
@@ -1573,6 +1744,17 @@
1573 1744
   #define RGB_LED_W_PIN -1
1574 1745
 #endif
1575 1746
 
1747
+// Support for Adafruit Neopixel LED driver
1748
+//#define NEOPIXEL_LED
1749
+#if ENABLED(NEOPIXEL_LED)
1750
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1751
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1752
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1753
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1754
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1755
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1756
+#endif
1757
+
1576 1758
 /**
1577 1759
  * Printer Event LEDs
1578 1760
  *
@@ -1584,68 +1766,32 @@
1584 1766
  *  - Change to green once print has finished
1585 1767
  *  - Turn off after the print has finished and the user has pushed a button
1586 1768
  */
1587
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)
1769
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1588 1770
   #define PRINTER_EVENT_LEDS
1589 1771
 #endif
1590 1772
 
1591
-/*********************************************************************\
1592
-* R/C SERVO support
1593
-* Sponsored by TrinityLabs, Reworked by codexmas
1594
-**********************************************************************/
1773
+/**
1774
+ * R/C SERVO support
1775
+ * Sponsored by TrinityLabs, Reworked by codexmas
1776
+ */
1595 1777
 
1596
-// Number of servos
1597
-//
1598
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1599
-// set it manually if you have more servos than extruders and wish to manually control some
1600
-// leaving it undefined or defining as 0 will disable the servo subsystem
1601
-// If unsure, leave commented / disabled
1602
-//
1778
+/**
1779
+ * Number of servos
1780
+ *
1781
+ * For some servo-related options NUM_SERVOS will be set automatically.
1782
+ * Set this manually if there are extra servos needing manual control.
1783
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1784
+ */
1603 1785
 //#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
1604 1786
 
1605 1787
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1606 1788
 // 300ms is a good value but you can try less delay.
1607 1789
 // If the servo can't reach the requested position, increase it.
1608
-#define SERVO_DELAY 300
1790
+#define SERVO_DELAY { 300 }
1609 1791
 
1610 1792
 // Servo deactivation
1611 1793
 //
1612 1794
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1613 1795
 //#define DEACTIVATE_SERVOS_AFTER_MOVE
1614 1796
 
1615
-/**
1616
- * Filament Width Sensor
1617
- *
1618
- * Measures the filament width in real-time and adjusts
1619
- * flow rate to compensate for any irregularities.
1620
- *
1621
- * Also allows the measured filament diameter to set the
1622
- * extrusion rate, so the slicer only has to specify the
1623
- * volume.
1624
- *
1625
- * Only a single extruder is supported at this time.
1626
- *
1627
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1628
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1629
- * 301 RAMBO       : Analog input 3
1630
- *
1631
- * Note: May require analog pins to be defined for other boards.
1632
- */
1633
-//#define FILAMENT_WIDTH_SENSOR
1634
-
1635
-#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00   // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
1636
-
1637
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1638
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1639
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1640
-
1641
-  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1642
-  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1643
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1644
-
1645
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1646
-
1647
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1648
-  //#define FILAMENT_LCD_DISPLAY
1649
-#endif
1650
-
1651 1797
 #endif // CONFIGURATION_H

+ 1567
- 0
Marlin/example_configurations/Malyan/M150/Configuration_adv.h
파일 크기가 너무 크기때문에 변경 상태를 표시하지 않습니다.
파일 보기


Marlin/example_configurations/M150/README.md → Marlin/example_configurations/Malyan/M150/README.md 파일 보기


Marlin/example_configurations/M150/_Bootscreen.h → Marlin/example_configurations/Malyan/M150/_Bootscreen.h 파일 보기


+ 15
- 0
Marlin/example_configurations/Micromake/C1/README.md 파일 보기

@@ -0,0 +1,15 @@
1
+# Micromake C1
2
+
3
+### In the folder "basic"
4
+Configuration files for Micromake C1 without mods
5
+  - English LCD 2X16 Characters
6
+  - Motors 16 STEPS
7
+  - No heated bed
8
+  - No probe, etc.
9
+  - Like a standard C1 as shipped by Micromake.
10
+
11
+### In the folder "enhanced"
12
+Configuration files for Micromake C1 with…
13
+  - 128 STEPS configured with jumper on the motherboard (all open for 128 Steps).
14
+  - Capacitive Probe (Adjust offsets at your convenience)
15
+  - French language with no accents for Japanese LCD.

+ 1773
- 0
Marlin/example_configurations/Micromake/C1/basic/Configuration.h
파일 크기가 너무 크기때문에 변경 상태를 표시하지 않습니다.
파일 보기


+ 1773
- 0
Marlin/example_configurations/Micromake/C1/enhanced/Configuration.h
파일 크기가 너무 크기때문에 변경 상태를 표시하지 않습니다.
파일 보기


+ 1568
- 0
Marlin/example_configurations/Micromake/C1/enhanced/Configuration_adv.h
파일 크기가 너무 크기때문에 변경 상태를 표시하지 않습니다.
파일 보기


+ 245
- 100
Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h 파일 보기

@@ -37,7 +37,7 @@
37 37
  */
38 38
 #ifndef CONFIGURATION_H
39 39
 #define CONFIGURATION_H
40
-#define CONFIGURATION_H_VERSION 010100
40
+#define CONFIGURATION_H_VERSION 010107
41 41
 
42 42
 //===========================================================================
43 43
 //============================= Getting Started =============================
@@ -107,8 +107,9 @@
107 107
  *
108 108
  * 250000 works in most cases, but you might try a lower speed if
109 109
  * you commonly experience drop-outs during host printing.
110
+ * You may try up to 1000000 to speed up SD file transfer.
110 111
  *
111
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
112
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
112 113
  */
113 114
 #define BAUDRATE 250000
114 115
 
@@ -135,6 +136,9 @@
135 136
 // :[1, 2, 3, 4, 5]
136 137
 #define EXTRUDERS 1
137 138
 
139
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
140
+#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
141
+
138 142
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
139 143
 //#define SINGLENOZZLE
140 144
 
@@ -161,7 +165,10 @@
161 165
 //#define SWITCHING_EXTRUDER
162 166
 #if ENABLED(SWITCHING_EXTRUDER)
163 167
   #define SWITCHING_EXTRUDER_SERVO_NR 0
164
-  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1
168
+  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3]
169
+  #if EXTRUDERS > 3
170
+    #define SWITCHING_EXTRUDER_E23_SERVO_NR 1
171
+  #endif
165 172
 #endif
166 173
 
167 174
 // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles
@@ -173,6 +180,21 @@
173 180
 #endif
174 181
 
175 182
 /**
183
+ * Two separate X-carriages with extruders that connect to a moving part
184
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
185
+ */
186
+//#define PARKING_EXTRUDER
187
+#if ENABLED(PARKING_EXTRUDER)
188
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
189
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
190
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
191
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
192
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
193
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
194
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
195
+#endif
196
+
197
+/**
176 198
  * "Mixing Extruder"
177 199
  *   - Adds a new code, M165, to set the current mix factors.
178 200
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -317,8 +339,9 @@
317 339
 
318 340
 // Comment the following line to disable PID and enable bang-bang.
319 341
 #define PIDTEMP
320
-#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
321
-#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
342
+#define BANG_MAX 255     // Limits current to nozzle while in bang-bang mode; 255=full current
343
+#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
344
+#define PID_K1 0.95      // Smoothing factor within the PID
322 345
 #if ENABLED(PIDTEMP)
323 346
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
324 347
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -328,7 +351,6 @@
328 351
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
329 352
   #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
330 353
                                   // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
331
-  #define K1 0.95 //smoothing factor within the PID
332 354
 
333 355
   // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
334 356
 
@@ -409,12 +431,13 @@
409 431
 //===========================================================================
410 432
 
411 433
 /**
412
- * Thermal Protection protects your printer from damage and fire if a
413
- * thermistor falls out or temperature sensors fail in any way.
434
+ * Thermal Protection provides additional protection to your printer from damage
435
+ * and fire. Marlin always includes safe min and max temperature ranges which
436
+ * protect against a broken or disconnected thermistor wire.
414 437
  *
415
- * The issue: If a thermistor falls out or a temperature sensor fails,
416
- * Marlin can no longer sense the actual temperature. Since a disconnected
417
- * thermistor reads as a low temperature, the firmware will keep the heater on.
438
+ * The issue: If a thermistor falls out, it will report the much lower
439
+ * temperature of the air in the room, and the the firmware will keep
440
+ * the heater on.
418 441
  *
419 442
  * If you get "Thermal Runaway" or "Heating failed" errors the
420 443
  * details can be tuned in Configuration_adv.h
@@ -554,7 +577,7 @@
554 577
 // @section probes
555 578
 
556 579
 //
557
-// See http://marlinfw.org/configuration/probes.html
580
+// See http://marlinfw.org/docs/configuration/probes.html
558 581
 //
559 582
 
560 583
 /**
@@ -620,14 +643,15 @@
620 643
 #endif
621 644
 
622 645
 /**
623
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
624
- * options selected below - will be disabled during probing so as to minimize
625
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
626
- * in current flowing through the wires).  This is likely most useful to users of the
627
- * BLTouch probe, but may also help those with inductive or other probe types.
646
+ * Enable one or more of the following if probing seems unreliable.
647
+ * Heaters and/or fans can be disabled during probing to minimize electrical
648
+ * noise. A delay can also be added to allow noise and vibration to settle.
649
+ * These options are most useful for the BLTouch probe, but may also improve
650
+ * readings with inductive probes and piezo sensors.
628 651
  */
629 652
 //#define PROBING_HEATERS_OFF       // Turn heaters off when probing
630 653
 //#define PROBING_FANS_OFF          // Turn fans off when probing
654
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
631 655
 
632 656
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
633 657
 //#define SOLENOID_PROBE
@@ -666,14 +690,16 @@
666 690
 // X and Y axis travel speed (mm/m) between probes
667 691
 #define XY_PROBE_SPEED 8000
668 692
 
669
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
693
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
670 694
 #define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
671 695
 
672 696
 // Speed for the "accurate" probe of each point
673 697
 #define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
674 698
 
675
-// Use double touch for probing
676
-//#define PROBE_DOUBLE_TOUCH
699
+// The number of probes to perform at each point.
700
+//   Set to 2 for a fast/slow probe, using the second probe result.
701
+//   Set to 3 or more for slow probes, averaging the results.
702
+//#define MULTIPLE_PROBING 2
677 703
 
678 704
 /**
679 705
  * Z probes require clearance when deploying, stowing, and moving between
@@ -740,6 +766,8 @@
740 766
 
741 767
 // @section homing
742 768
 
769
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
770
+
743 771
 //#define Z_HOMING_HEIGHT 4  // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
744 772
                              // Be sure you have this distance over your Z_MAX_POS in case.
745 773
 
@@ -751,18 +779,42 @@
751 779
 
752 780
 // @section machine
753 781
 
754
-// Travel limits after homing (units are in mm)
782
+// The size of the print bed
783
+#define X_BED_SIZE 200
784
+#define Y_BED_SIZE 200
785
+
786
+// Travel limits (mm) after homing, corresponding to endstop positions.
755 787
 #define X_MIN_POS 0
756 788
 #define Y_MIN_POS 0
757 789
 #define Z_MIN_POS 0
758
-#define X_MAX_POS 200
759
-#define Y_MAX_POS 200
790
+#define X_MAX_POS X_BED_SIZE
791
+#define Y_MAX_POS Y_BED_SIZE
760 792
 #define Z_MAX_POS 200
761 793
 
762
-// If enabled, axes won't move below MIN_POS in response to movement commands.
794
+/**
795
+ * Software Endstops
796
+ *
797
+ * - Prevent moves outside the set machine bounds.
798
+ * - Individual axes can be disabled, if desired.
799
+ * - X and Y only apply to Cartesian robots.
800
+ * - Use 'M211' to set software endstops on/off or report current state
801
+ */
802
+
803
+// Min software endstops curtail movement below minimum coordinate bounds
763 804
 #define MIN_SOFTWARE_ENDSTOPS
764
-// If enabled, axes won't move above MAX_POS in response to movement commands.
805
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
806
+  #define MIN_SOFTWARE_ENDSTOP_X
807
+  #define MIN_SOFTWARE_ENDSTOP_Y
808
+  #define MIN_SOFTWARE_ENDSTOP_Z
809
+#endif
810
+
811
+// Max software endstops curtail movement above maximum coordinate bounds
765 812
 #define MAX_SOFTWARE_ENDSTOPS
813
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
814
+  #define MAX_SOFTWARE_ENDSTOP_X
815
+  #define MAX_SOFTWARE_ENDSTOP_Y
816
+  #define MAX_SOFTWARE_ENDSTOP_Z
817
+#endif
766 818
 
767 819
 /**
768 820
  * Filament Runout Sensor
@@ -782,7 +834,7 @@
782 834
 //===========================================================================
783 835
 //=============================== Bed Leveling ==============================
784 836
 //===========================================================================
785
-// @section bedlevel
837
+// @section calibrate
786 838
 
787 839
 /**
788 840
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -808,12 +860,7 @@
808 860
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
809 861
  *   A comprehensive bed leveling system combining the features and benefits
810 862
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
811
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
812
- *   for Cartesian Printers. That said, it was primarily designed to correct
813
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
814
- *   please post an issue if something doesn't work correctly. Initially,
815
- *   you will need to set a reduced bed size so you have a rectangular area
816
- *   to test on.
863
+ *   Validation and Mesh Editing systems.
817 864
  *
818 865
  * - MESH_BED_LEVELING
819 866
  *   Probe a grid manually
@@ -840,6 +887,24 @@
840 887
   // at which point movement will be level to the machine's XY plane.
841 888
   // The height can be set with M420 Z<height>
842 889
   #define ENABLE_LEVELING_FADE_HEIGHT
890
+
891
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
892
+  // split up moves into short segments like a Delta. This follows the
893
+  // contours of the bed more closely than edge-to-edge straight moves.
894
+  #define SEGMENT_LEVELED_MOVES
895
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
896
+
897
+  /**
898
+   * Enable the G26 Mesh Validation Pattern tool.
899
+   */
900
+  //#define G26_MESH_VALIDATION   // Enable G26 mesh validation
901
+  #if ENABLED(G26_MESH_VALIDATION)
902
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
903
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
904
+    #define MESH_TEST_HOTEND_TEMP   205.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
905
+    #define MESH_TEST_BED_TEMP       60.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
906
+  #endif
907
+
843 908
 #endif
844 909
 
845 910
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -895,7 +960,9 @@
895 960
   //========================= Unified Bed Leveling ============================
896 961
   //===========================================================================
897 962
 
898
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
963
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
964
+
965
+  #define MESH_INSET 1              // Mesh inset margin on print area
899 966
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
900 967
   #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
901 968
 
@@ -906,8 +973,8 @@
906 973
   #define UBL_PROBE_PT_3_X 180
907 974
   #define UBL_PROBE_PT_3_Y 20
908 975
 
909
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
910 976
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
977
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
911 978
 
912 979
 #elif ENABLED(MESH_BED_LEVELING)
913 980
 
@@ -934,6 +1001,9 @@
934 1001
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
935 1002
 #endif
936 1003
 
1004
+// Add a menu item to move between bed corners for manual bed adjustment
1005
+//#define LEVEL_BED_CORNERS
1006
+
937 1007
 /**
938 1008
  * Commands to execute at the end of G29 probing.
939 1009
  * Useful to retract or move the Z probe out of the way.
@@ -964,14 +1034,71 @@
964 1034
 //#define Z_SAFE_HOMING
965 1035
 
966 1036
 #if ENABLED(Z_SAFE_HOMING)
967
-  #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
968
-  #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
1037
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1038
+  #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2)    // Y point for Z homing when homing all axes (G28).
969 1039
 #endif
970 1040
 
971 1041
 // Homing speeds (mm/m)
972 1042
 #define HOMING_FEEDRATE_XY (50*60)
973 1043
 #define HOMING_FEEDRATE_Z  (4*60)
974 1044
 
1045
+// @section calibrate
1046
+
1047
+/**
1048
+ * Bed Skew Compensation
1049
+ *
1050
+ * This feature corrects for misalignment in the XYZ axes.
1051
+ *
1052
+ * Take the following steps to get the bed skew in the XY plane:
1053
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1054
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1055
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1056
+ *  4. For XY_SIDE_AD measure the edge A to D
1057
+ *
1058
+ * Marlin automatically computes skew factors from these measurements.
1059
+ * Skew factors may also be computed and set manually:
1060
+ *
1061
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1062
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1063
+ *
1064
+ * If desired, follow the same procedure for XZ and YZ.
1065
+ * Use these diagrams for reference:
1066
+ *
1067
+ *    Y                     Z                     Z
1068
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1069
+ *    |    /       /        |    /       /        |    /       /
1070
+ *    |   /       /         |   /       /         |   /       /
1071
+ *    |  A-------D          |  A-------D          |  A-------D
1072
+ *    +-------------->X     +-------------->X     +-------------->Y
1073
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1074
+ */
1075
+//#define SKEW_CORRECTION
1076
+
1077
+#if ENABLED(SKEW_CORRECTION)
1078
+  // Input all length measurements here:
1079
+  #define XY_DIAG_AC 282.8427124746
1080
+  #define XY_DIAG_BD 282.8427124746
1081
+  #define XY_SIDE_AD 200
1082
+
1083
+  // Or, set the default skew factors directly here
1084
+  // to override the above measurements:
1085
+  #define XY_SKEW_FACTOR 0.0
1086
+
1087
+  //#define SKEW_CORRECTION_FOR_Z
1088
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1089
+    #define XZ_DIAG_AC 282.8427124746
1090
+    #define XZ_DIAG_BD 282.8427124746
1091
+    #define YZ_DIAG_AC 282.8427124746
1092
+    #define YZ_DIAG_BD 282.8427124746
1093
+    #define YZ_SIDE_AD 200
1094
+    #define XZ_SKEW_FACTOR 0.0
1095
+    #define YZ_SKEW_FACTOR 0.0
1096
+  #endif
1097
+
1098
+  // Enable this option for M852 to set skew at runtime
1099
+  //#define SKEW_CORRECTION_GCODE
1100
+#endif
1101
+
975 1102
 //=============================================================================
976 1103
 //============================= Additional Features ===========================
977 1104
 //=============================================================================
@@ -998,11 +1125,12 @@
998 1125
 //
999 1126
 #define HOST_KEEPALIVE_FEATURE        // Disable this if your host doesn't like keepalive messages
1000 1127
 #define DEFAULT_KEEPALIVE_INTERVAL 2  // Number of seconds between "busy" messages. Set with M113.
1128
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
1001 1129
 
1002 1130
 //
1003 1131
 // M100 Free Memory Watcher
1004 1132
 //
1005
-//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1133
+//#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
1006 1134
 
1007 1135
 //
1008 1136
 // G20/G21 Inch mode support
@@ -1147,11 +1275,11 @@
1147 1275
  *
1148 1276
  * Select the language to display on the LCD. These languages are available:
1149 1277
  *
1150
- *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
1151
- *    it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
1152
- *    zh_CN, zh_TW, test
1278
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1279
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1280
+ *    tr, uk, zh_CN, zh_TW, test
1153 1281
  *
1154
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1282
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1155 1283
  */
1156 1284
 #define LCD_LANGUAGE en
1157 1285
 
@@ -1173,7 +1301,7 @@
1173 1301
  *  - Click the controller to view the LCD menu
1174 1302
  *  - The LCD will display Japanese, Western, or Cyrillic text
1175 1303
  *
1176
- * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1304
+ * See http://marlinfw.org/docs/development/lcd_language.html
1177 1305
  *
1178 1306
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1179 1307
  */
@@ -1279,8 +1407,8 @@
1279 1407
 // Note: Test audio output with the G-Code:
1280 1408
 //  M300 S<frequency Hz> P<duration ms>
1281 1409
 //
1282
-//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
1283
-//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
1410
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
1411
+//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
1284 1412
 
1285 1413
 //
1286 1414
 // CONTROLLER TYPE: Standard
@@ -1388,11 +1516,13 @@
1388 1516
 //#define CARTESIO_UI
1389 1517
 
1390 1518
 //
1391
-// ANET_10 Controller supported displays.
1519
+// ANET and Tronxy Controller supported displays.
1392 1520
 //
1393
-//#define ANET_KEYPAD_LCD         // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1521
+//#define ZONESTAR_LCD            // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1394 1522
                                   // This LCD is known to be susceptible to electrical interference
1395 1523
                                   // which scrambles the display.  Pressing any button clears it up.
1524
+                                  // This is a LCD2004 display with 5 analog buttons.
1525
+
1396 1526
 //#define ANET_FULL_GRAPHICS_LCD  // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1397 1527
                                   // A clone of the RepRapDiscount full graphics display but with
1398 1528
                                   // different pins/wiring (see pins_ANET_10.h).
@@ -1452,11 +1582,6 @@
1452 1582
 //#define U8GLIB_SSD1306
1453 1583
 
1454 1584
 //
1455
-// TinyBoy2 128x64 OLED / Encoder Panel
1456
-//
1457
-//#define OLED_PANEL_TINYBOY2
1458
-
1459
-//
1460 1585
 // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules
1461 1586
 //
1462 1587
 //#define SAV_3DGLCD
@@ -1473,6 +1598,45 @@
1473 1598
 //
1474 1599
 //#define SAV_3DLCD
1475 1600
 
1601
+//
1602
+// TinyBoy2 128x64 OLED / Encoder Panel
1603
+//
1604
+//#define OLED_PANEL_TINYBOY2
1605
+
1606
+//
1607
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1608
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1609
+//
1610
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1611
+
1612
+//
1613
+// MKS MINI12864 with graphic controller and SD support
1614
+// http://reprap.org/wiki/MKS_MINI_12864
1615
+//
1616
+//#define MKS_MINI_12864
1617
+
1618
+//
1619
+// Factory display for Creality CR-10
1620
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1621
+//
1622
+// This is RAMPS-compatible using a single 10-pin connector.
1623
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1624
+//
1625
+//#define CR10_STOCKDISPLAY
1626
+
1627
+//
1628
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1629
+// http://reprap.org/wiki/MKS_12864OLED
1630
+//
1631
+// Tiny, but very sharp OLED display
1632
+//
1633
+//#define MKS_12864OLED
1634
+
1635
+// Silvergate GLCD controller
1636
+// http://github.com/android444/Silvergate
1637
+//
1638
+//#define SILVER_GATE_GLCD_CONTROLLER
1639
+
1476 1640
 //=============================================================================
1477 1641
 //=============================== Extra Features ==============================
1478 1642
 //=============================================================================
@@ -1529,16 +1693,22 @@
1529 1693
  * Adds the M150 command to set the LED (or LED strip) color.
1530 1694
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1531 1695
  * luminance values can be set from 0 to 255.
1696
+ * For Neopixel LED an overall brightness parameter is also available.
1532 1697
  *
1533 1698
  * *** CAUTION ***
1534 1699
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1535 1700
  *  as the Arduino cannot handle the current the LEDs will require.
1536 1701
  *  Failure to follow this precaution can destroy your Arduino!
1702
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1703
+ *  more current than the Arduino 5V linear regulator can produce.
1537 1704
  * *** CAUTION ***
1538 1705
  *
1706
+ * LED Type. Enable only one of the following two options.
1707
+ *
1539 1708
  */
1540 1709
 //#define RGB_LED
1541 1710
 //#define RGBW_LED
1711
+
1542 1712
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1543 1713
   #define RGB_LED_R_PIN 34
1544 1714
   #define RGB_LED_G_PIN 43
@@ -1546,6 +1716,17 @@
1546 1716
   #define RGB_LED_W_PIN -1
1547 1717
 #endif
1548 1718
 
1719
+// Support for Adafruit Neopixel LED driver
1720
+//#define NEOPIXEL_LED
1721
+#if ENABLED(NEOPIXEL_LED)
1722
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1723
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1724
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1725
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1726
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1727
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1728
+#endif
1729
+
1549 1730
 /**
1550 1731
  * Printer Event LEDs
1551 1732
  *
@@ -1557,68 +1738,32 @@
1557 1738
  *  - Change to green once print has finished
1558 1739
  *  - Turn off after the print has finished and the user has pushed a button
1559 1740
  */
1560
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)
1741
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1561 1742
   #define PRINTER_EVENT_LEDS
1562 1743
 #endif
1563 1744
 
1564
-/*********************************************************************\
1565
-* R/C SERVO support
1566
-* Sponsored by TrinityLabs, Reworked by codexmas
1567
-**********************************************************************/
1745
+/**
1746
+ * R/C SERVO support
1747
+ * Sponsored by TrinityLabs, Reworked by codexmas
1748
+ */
1568 1749
 
1569
-// Number of servos
1570
-//
1571
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1572
-// set it manually if you have more servos than extruders and wish to manually control some
1573
-// leaving it undefined or defining as 0 will disable the servo subsystem
1574
-// If unsure, leave commented / disabled
1575
-//
1750
+/**
1751
+ * Number of servos
1752
+ *
1753
+ * For some servo-related options NUM_SERVOS will be set automatically.
1754
+ * Set this manually if there are extra servos needing manual control.
1755
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1756
+ */
1576 1757
 //#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
1577 1758
 
1578 1759
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1579 1760
 // 300ms is a good value but you can try less delay.
1580 1761
 // If the servo can't reach the requested position, increase it.
1581
-#define SERVO_DELAY 300
1762
+#define SERVO_DELAY { 300 }
1582 1763
 
1583 1764
 // Servo deactivation
1584 1765
 //
1585 1766
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1586 1767
 //#define DEACTIVATE_SERVOS_AFTER_MOVE
1587 1768
 
1588
-/**
1589
- * Filament Width Sensor
1590
- *
1591
- * Measures the filament width in real-time and adjusts
1592
- * flow rate to compensate for any irregularities.
1593
- *
1594
- * Also allows the measured filament diameter to set the
1595
- * extrusion rate, so the slicer only has to specify the
1596
- * volume.
1597
- *
1598
- * Only a single extruder is supported at this time.
1599
- *
1600
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1601
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1602
- * 301 RAMBO       : Analog input 3
1603
- *
1604
- * Note: May require analog pins to be defined for other boards.
1605
- */
1606
-//#define FILAMENT_WIDTH_SENSOR
1607
-
1608
-#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00   // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
1609
-
1610
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1611
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1612
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1613
-
1614
-  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1615
-  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1616
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1617
-
1618
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1619
-
1620
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1621
-  //#define FILAMENT_LCD_DISPLAY
1622
-#endif
1623
-
1624 1769
 #endif // CONFIGURATION_H

+ 246
- 101
Marlin/example_configurations/RigidBot/Configuration.h 파일 보기

@@ -37,7 +37,7 @@
37 37
  */
38 38
 #ifndef CONFIGURATION_H
39 39
 #define CONFIGURATION_H
40
-#define CONFIGURATION_H_VERSION 010100
40
+#define CONFIGURATION_H_VERSION 010107
41 41
 
42 42
 //===========================================================================
43 43
 //============================= Getting Started =============================
@@ -74,7 +74,7 @@
74 74
 // User-specified version info of this build to display in [Pronterface, etc] terminal window during
75 75
 // startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
76 76
 // build by the user have been successfully uploaded into firmware.
77
-#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
77
+#define STRING_CONFIG_H_AUTHOR "(none, RigidBot)" // Who made the changes.
78 78
 #define SHOW_BOOTSCREEN
79 79
 #define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
80 80
 #define STRING_SPLASH_LINE2 WEBSITE_URL         // will be shown during bootup in line 2
@@ -107,8 +107,9 @@
107 107
  *
108 108
  * 250000 works in most cases, but you might try a lower speed if
109 109
  * you commonly experience drop-outs during host printing.
110
+ * You may try up to 1000000 to speed up SD file transfer.
110 111
  *
111
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
112
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
112 113
  */
113 114
 #define BAUDRATE 115200
114 115
 
@@ -138,6 +139,9 @@
138 139
 // :[1, 2, 3, 4, 5]
139 140
 #define EXTRUDERS 1  // Single extruder. Set to 2 for dual extruders
140 141
 
142
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
143
+#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
144
+
141 145
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
142 146
 //#define SINGLENOZZLE
143 147
 
@@ -164,7 +168,10 @@
164 168
 //#define SWITCHING_EXTRUDER
165 169
 #if ENABLED(SWITCHING_EXTRUDER)
166 170
   #define SWITCHING_EXTRUDER_SERVO_NR 0
167
-  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1
171
+  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3]
172
+  #if EXTRUDERS > 3
173
+    #define SWITCHING_EXTRUDER_E23_SERVO_NR 1
174
+  #endif
168 175
 #endif
169 176
 
170 177
 // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles
@@ -176,6 +183,21 @@
176 183
 #endif
177 184
 
178 185
 /**
186
+ * Two separate X-carriages with extruders that connect to a moving part
187
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
188
+ */
189
+//#define PARKING_EXTRUDER
190
+#if ENABLED(PARKING_EXTRUDER)
191
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
192
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
193
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
194
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
195
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
196
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
197
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
198
+#endif
199
+
200
+/**
179 201
  * "Mixing Extruder"
180 202
  *   - Adds a new code, M165, to set the current mix factors.
181 203
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -320,8 +342,9 @@
320 342
 
321 343
 // Comment the following line to disable PID and enable bang-bang.
322 344
 #define PIDTEMP
323
-#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
324
-#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
345
+#define BANG_MAX 255     // Limits current to nozzle while in bang-bang mode; 255=full current
346
+#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
347
+#define PID_K1 0.95      // Smoothing factor within the PID
325 348
 #if ENABLED(PIDTEMP)
326 349
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
327 350
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -331,7 +354,6 @@
331 354
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
332 355
   #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
333 356
                                   // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
334
-  #define K1 0.95 //smoothing factor within the PID
335 357
 
336 358
   // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
337 359
 
@@ -405,12 +427,13 @@
405 427
 //===========================================================================
406 428
 
407 429
 /**
408
- * Thermal Protection protects your printer from damage and fire if a
409
- * thermistor falls out or temperature sensors fail in any way.
430
+ * Thermal Protection provides additional protection to your printer from damage
431
+ * and fire. Marlin always includes safe min and max temperature ranges which
432
+ * protect against a broken or disconnected thermistor wire.
410 433
  *
411
- * The issue: If a thermistor falls out or a temperature sensor fails,
412
- * Marlin can no longer sense the actual temperature. Since a disconnected
413
- * thermistor reads as a low temperature, the firmware will keep the heater on.
434
+ * The issue: If a thermistor falls out, it will report the much lower
435
+ * temperature of the air in the room, and the the firmware will keep
436
+ * the heater on.
414 437
  *
415 438
  * If you get "Thermal Runaway" or "Heating failed" errors the
416 439
  * details can be tuned in Configuration_adv.h
@@ -552,7 +575,7 @@
552 575
 // @section probes
553 576
 
554 577
 //
555
-// See http://marlinfw.org/configuration/probes.html
578
+// See http://marlinfw.org/docs/configuration/probes.html
556 579
 //
557 580
 
558 581
 /**
@@ -618,14 +641,15 @@
618 641
 #endif
619 642
 
620 643
 /**
621
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
622
- * options selected below - will be disabled during probing so as to minimize
623
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
624
- * in current flowing through the wires).  This is likely most useful to users of the
625
- * BLTouch probe, but may also help those with inductive or other probe types.
644
+ * Enable one or more of the following if probing seems unreliable.
645
+ * Heaters and/or fans can be disabled during probing to minimize electrical
646
+ * noise. A delay can also be added to allow noise and vibration to settle.
647
+ * These options are most useful for the BLTouch probe, but may also improve
648
+ * readings with inductive probes and piezo sensors.
626 649
  */
627 650
 //#define PROBING_HEATERS_OFF       // Turn heaters off when probing
628 651
 //#define PROBING_FANS_OFF          // Turn fans off when probing
652
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
629 653
 
630 654
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
631 655
 //#define SOLENOID_PROBE
@@ -664,14 +688,16 @@
664 688
 // X and Y axis travel speed (mm/m) between probes
665 689
 #define XY_PROBE_SPEED 8000
666 690
 
667
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
691
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
668 692
 #define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
669 693
 
670 694
 // Speed for the "accurate" probe of each point
671 695
 #define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
672 696
 
673
-// Use double touch for probing
674
-//#define PROBE_DOUBLE_TOUCH
697
+// The number of probes to perform at each point.
698
+//   Set to 2 for a fast/slow probe, using the second probe result.
699
+//   Set to 3 or more for slow probes, averaging the results.
700
+//#define MULTIPLE_PROBING 2
675 701
 
676 702
 /**
677 703
  * Z probes require clearance when deploying, stowing, and moving between
@@ -738,6 +764,8 @@
738 764
 
739 765
 // @section homing
740 766
 
767
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
768
+
741 769
 //#define Z_HOMING_HEIGHT 4  // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
742 770
                              // Be sure you have this distance over your Z_MAX_POS in case.
743 771
 
@@ -749,18 +777,42 @@
749 777
 
750 778
 // @section machine
751 779
 
752
-// Travel limits after homing (units are in mm)
780
+// The size of the print bed
781
+#define X_BED_SIZE 254  // RigidBot regular is 254mm, RigitBot Big is 406mm
782
+#define Y_BED_SIZE 248  // RigidBot regular is 248mm, RigitBot Big is 304mm
783
+
784
+// Travel limits (mm) after homing, corresponding to endstop positions.
753 785
 #define X_MIN_POS 0
754 786
 #define Y_MIN_POS 0
755 787
 #define Z_MIN_POS 0
756
-#define X_MAX_POS 254  // RigidBot regular is 254mm, RigitBot Big is 406mm
757
-#define Y_MAX_POS 248  // RigidBot regular is 248mm, RigitBot Big is 304mm
788
+#define X_MAX_POS X_BED_SIZE
789
+#define Y_MAX_POS Y_BED_SIZE
758 790
 #define Z_MAX_POS 254  // RigidBot regular and Big are 254mm
759 791
 
760
-// If enabled, axes won't move below MIN_POS in response to movement commands.
792
+/**
793
+ * Software Endstops
794
+ *
795
+ * - Prevent moves outside the set machine bounds.
796
+ * - Individual axes can be disabled, if desired.
797
+ * - X and Y only apply to Cartesian robots.
798
+ * - Use 'M211' to set software endstops on/off or report current state
799
+ */
800
+
801
+// Min software endstops curtail movement below minimum coordinate bounds
761 802
 #define MIN_SOFTWARE_ENDSTOPS
762
-// If enabled, axes won't move above MAX_POS in response to movement commands.
803
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
804
+  #define MIN_SOFTWARE_ENDSTOP_X
805
+  #define MIN_SOFTWARE_ENDSTOP_Y
806
+  #define MIN_SOFTWARE_ENDSTOP_Z
807
+#endif
808
+
809
+// Max software endstops curtail movement above maximum coordinate bounds
763 810
 #define MAX_SOFTWARE_ENDSTOPS
811
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
812
+  #define MAX_SOFTWARE_ENDSTOP_X
813
+  #define MAX_SOFTWARE_ENDSTOP_Y
814
+  #define MAX_SOFTWARE_ENDSTOP_Z
815
+#endif
764 816
 
765 817
 /**
766 818
  * Filament Runout Sensor
@@ -780,7 +832,7 @@
780 832
 //===========================================================================
781 833
 //=============================== Bed Leveling ==============================
782 834
 //===========================================================================
783
-// @section bedlevel
835
+// @section calibrate
784 836
 
785 837
 /**
786 838
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -806,12 +858,7 @@
806 858
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
807 859
  *   A comprehensive bed leveling system combining the features and benefits
808 860
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
809
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
810
- *   for Cartesian Printers. That said, it was primarily designed to correct
811
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
812
- *   please post an issue if something doesn't work correctly. Initially,
813
- *   you will need to set a reduced bed size so you have a rectangular area
814
- *   to test on.
861
+ *   Validation and Mesh Editing systems.
815 862
  *
816 863
  * - MESH_BED_LEVELING
817 864
  *   Probe a grid manually
@@ -838,6 +885,24 @@
838 885
   // at which point movement will be level to the machine's XY plane.
839 886
   // The height can be set with M420 Z<height>
840 887
   #define ENABLE_LEVELING_FADE_HEIGHT
888
+
889
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
890
+  // split up moves into short segments like a Delta. This follows the
891
+  // contours of the bed more closely than edge-to-edge straight moves.
892
+  #define SEGMENT_LEVELED_MOVES
893
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
894
+
895
+  /**
896
+   * Enable the G26 Mesh Validation Pattern tool.
897
+   */
898
+  //#define G26_MESH_VALIDATION   // Enable G26 mesh validation
899
+  #if ENABLED(G26_MESH_VALIDATION)
900
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
901
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
902
+    #define MESH_TEST_HOTEND_TEMP   205.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
903
+    #define MESH_TEST_BED_TEMP       60.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
904
+  #endif
905
+
841 906
 #endif
842 907
 
843 908
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -893,7 +958,9 @@
893 958
   //========================= Unified Bed Leveling ============================
894 959
   //===========================================================================
895 960
 
896
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
961
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
962
+
963
+  #define MESH_INSET 1              // Mesh inset margin on print area
897 964
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
898 965
   #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
899 966
 
@@ -904,8 +971,8 @@
904 971
   #define UBL_PROBE_PT_3_X 180
905 972
   #define UBL_PROBE_PT_3_Y 20
906 973
 
907
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
908 974
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
975
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
909 976
 
910 977
 #elif ENABLED(MESH_BED_LEVELING)
911 978
 
@@ -932,6 +999,9 @@
932 999
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
933 1000
 #endif
934 1001
 
1002
+// Add a menu item to move between bed corners for manual bed adjustment
1003
+//#define LEVEL_BED_CORNERS
1004
+
935 1005
 /**
936 1006
  * Commands to execute at the end of G29 probing.
937 1007
  * Useful to retract or move the Z probe out of the way.
@@ -962,14 +1032,71 @@
962 1032
 //#define Z_SAFE_HOMING
963 1033
 
964 1034
 #if ENABLED(Z_SAFE_HOMING)
965
-  #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
966
-  #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
1035
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1036
+  #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2)    // Y point for Z homing when homing all axes (G28).
967 1037
 #endif
968 1038
 
969 1039
 // Homing speeds (mm/m)
970 1040
 #define HOMING_FEEDRATE_XY (50*60)
971 1041
 #define HOMING_FEEDRATE_Z  (15*60)
972 1042
 
1043
+// @section calibrate
1044
+
1045
+/**
1046
+ * Bed Skew Compensation
1047
+ *
1048
+ * This feature corrects for misalignment in the XYZ axes.
1049
+ *
1050
+ * Take the following steps to get the bed skew in the XY plane:
1051
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1052
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1053
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1054
+ *  4. For XY_SIDE_AD measure the edge A to D
1055
+ *
1056
+ * Marlin automatically computes skew factors from these measurements.
1057
+ * Skew factors may also be computed and set manually:
1058
+ *
1059
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1060
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1061
+ *
1062
+ * If desired, follow the same procedure for XZ and YZ.
1063
+ * Use these diagrams for reference:
1064
+ *
1065
+ *    Y                     Z                     Z
1066
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1067
+ *    |    /       /        |    /       /        |    /       /
1068
+ *    |   /       /         |   /       /         |   /       /
1069
+ *    |  A-------D          |  A-------D          |  A-------D
1070
+ *    +-------------->X     +-------------->X     +-------------->Y
1071
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1072
+ */
1073
+//#define SKEW_CORRECTION
1074
+
1075
+#if ENABLED(SKEW_CORRECTION)
1076
+  // Input all length measurements here:
1077
+  #define XY_DIAG_AC 282.8427124746
1078
+  #define XY_DIAG_BD 282.8427124746
1079
+  #define XY_SIDE_AD 200
1080
+
1081
+  // Or, set the default skew factors directly here
1082
+  // to override the above measurements:
1083
+  #define XY_SKEW_FACTOR 0.0
1084
+
1085
+  //#define SKEW_CORRECTION_FOR_Z
1086
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1087
+    #define XZ_DIAG_AC 282.8427124746
1088
+    #define XZ_DIAG_BD 282.8427124746
1089
+    #define YZ_DIAG_AC 282.8427124746
1090
+    #define YZ_DIAG_BD 282.8427124746
1091
+    #define YZ_SIDE_AD 200
1092
+    #define XZ_SKEW_FACTOR 0.0
1093
+    #define YZ_SKEW_FACTOR 0.0
1094
+  #endif
1095
+
1096
+  // Enable this option for M852 to set skew at runtime
1097
+  //#define SKEW_CORRECTION_GCODE
1098
+#endif
1099
+
973 1100
 //=============================================================================
974 1101
 //============================= Additional Features ===========================
975 1102
 //=============================================================================
@@ -996,11 +1123,12 @@
996 1123
 //
997 1124
 #define HOST_KEEPALIVE_FEATURE        // Disable this if your host doesn't like keepalive messages
998 1125
 #define DEFAULT_KEEPALIVE_INTERVAL 2  // Number of seconds between "busy" messages. Set with M113.
1126
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
999 1127
 
1000 1128
 //
1001 1129
 // M100 Free Memory Watcher
1002 1130
 //
1003
-//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1131
+//#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
1004 1132
 
1005 1133
 //
1006 1134
 // G20/G21 Inch mode support
@@ -1145,11 +1273,11 @@
1145 1273
  *
1146 1274
  * Select the language to display on the LCD. These languages are available:
1147 1275
  *
1148
- *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
1149
- *    it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
1150
- *    zh_CN, zh_TW, test
1276
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1277
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1278
+ *    tr, uk, zh_CN, zh_TW, test
1151 1279
  *
1152
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1280
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1153 1281
  */
1154 1282
 #define LCD_LANGUAGE en
1155 1283
 
@@ -1171,7 +1299,7 @@
1171 1299
  *  - Click the controller to view the LCD menu
1172 1300
  *  - The LCD will display Japanese, Western, or Cyrillic text
1173 1301
  *
1174
- * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1302
+ * See http://marlinfw.org/docs/development/lcd_language.html
1175 1303
  *
1176 1304
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1177 1305
  */
@@ -1277,8 +1405,8 @@
1277 1405
 // Note: Test audio output with the G-Code:
1278 1406
 //  M300 S<frequency Hz> P<duration ms>
1279 1407
 //
1280
-//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
1281
-//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
1408
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
1409
+//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
1282 1410
 
1283 1411
 //
1284 1412
 // CONTROLLER TYPE: Standard
@@ -1388,11 +1516,13 @@
1388 1516
 //#define CARTESIO_UI
1389 1517
 
1390 1518
 //
1391
-// ANET_10 Controller supported displays.
1519
+// ANET and Tronxy Controller supported displays.
1392 1520
 //
1393
-//#define ANET_KEYPAD_LCD         // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1521
+//#define ZONESTAR_LCD            // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1394 1522
                                   // This LCD is known to be susceptible to electrical interference
1395 1523
                                   // which scrambles the display.  Pressing any button clears it up.
1524
+                                  // This is a LCD2004 display with 5 analog buttons.
1525
+
1396 1526
 //#define ANET_FULL_GRAPHICS_LCD  // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1397 1527
                                   // A clone of the RepRapDiscount full graphics display but with
1398 1528
                                   // different pins/wiring (see pins_ANET_10.h).
@@ -1452,11 +1582,6 @@
1452 1582
 //#define U8GLIB_SSD1306
1453 1583
 
1454 1584
 //
1455
-// TinyBoy2 128x64 OLED / Encoder Panel
1456
-//
1457
-//#define OLED_PANEL_TINYBOY2
1458
-
1459
-//
1460 1585
 // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules
1461 1586
 //
1462 1587
 //#define SAV_3DGLCD
@@ -1473,6 +1598,45 @@
1473 1598
 //
1474 1599
 //#define SAV_3DLCD
1475 1600
 
1601
+//
1602
+// TinyBoy2 128x64 OLED / Encoder Panel
1603
+//
1604
+//#define OLED_PANEL_TINYBOY2
1605
+
1606
+//
1607
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1608
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1609
+//
1610
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1611
+
1612
+//
1613
+// MKS MINI12864 with graphic controller and SD support
1614
+// http://reprap.org/wiki/MKS_MINI_12864
1615
+//
1616
+//#define MKS_MINI_12864
1617
+
1618
+//
1619
+// Factory display for Creality CR-10
1620
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1621
+//
1622
+// This is RAMPS-compatible using a single 10-pin connector.
1623
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1624
+//
1625
+//#define CR10_STOCKDISPLAY
1626
+
1627
+//
1628
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1629
+// http://reprap.org/wiki/MKS_12864OLED
1630
+//
1631
+// Tiny, but very sharp OLED display
1632
+//
1633
+//#define MKS_12864OLED
1634
+
1635
+// Silvergate GLCD controller
1636
+// http://github.com/android444/Silvergate
1637
+//
1638
+//#define SILVER_GATE_GLCD_CONTROLLER
1639
+
1476 1640
 //=============================================================================
1477 1641
 //=============================== Extra Features ==============================
1478 1642
 //=============================================================================
@@ -1529,16 +1693,22 @@
1529 1693
  * Adds the M150 command to set the LED (or LED strip) color.
1530 1694
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1531 1695
  * luminance values can be set from 0 to 255.
1696
+ * For Neopixel LED an overall brightness parameter is also available.
1532 1697
  *
1533 1698
  * *** CAUTION ***
1534 1699
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1535 1700
  *  as the Arduino cannot handle the current the LEDs will require.
1536 1701
  *  Failure to follow this precaution can destroy your Arduino!
1702
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1703
+ *  more current than the Arduino 5V linear regulator can produce.
1537 1704
  * *** CAUTION ***
1538 1705
  *
1706
+ * LED Type. Enable only one of the following two options.
1707
+ *
1539 1708
  */
1540 1709
 //#define RGB_LED
1541 1710
 //#define RGBW_LED
1711
+
1542 1712
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1543 1713
   #define RGB_LED_R_PIN 34
1544 1714
   #define RGB_LED_G_PIN 43
@@ -1546,6 +1716,17 @@
1546 1716
   #define RGB_LED_W_PIN -1
1547 1717
 #endif
1548 1718
 
1719
+// Support for Adafruit Neopixel LED driver
1720
+//#define NEOPIXEL_LED
1721
+#if ENABLED(NEOPIXEL_LED)
1722
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1723
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1724
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1725
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1726
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1727
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1728
+#endif
1729
+
1549 1730
 /**
1550 1731
  * Printer Event LEDs
1551 1732
  *
@@ -1557,68 +1738,32 @@
1557 1738
  *  - Change to green once print has finished
1558 1739
  *  - Turn off after the print has finished and the user has pushed a button
1559 1740
  */
1560
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)
1741
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1561 1742
   #define PRINTER_EVENT_LEDS
1562 1743
 #endif
1563 1744
 
1564
-/*********************************************************************\
1565
-* R/C SERVO support
1566
-* Sponsored by TrinityLabs, Reworked by codexmas
1567
-**********************************************************************/
1745
+/**
1746
+ * R/C SERVO support
1747
+ * Sponsored by TrinityLabs, Reworked by codexmas
1748
+ */
1568 1749
 
1569
-// Number of servos
1570
-//
1571
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1572
-// set it manually if you have more servos than extruders and wish to manually control some
1573
-// leaving it undefined or defining as 0 will disable the servo subsystem
1574
-// If unsure, leave commented / disabled
1575
-//
1750
+/**
1751
+ * Number of servos
1752
+ *
1753
+ * For some servo-related options NUM_SERVOS will be set automatically.
1754
+ * Set this manually if there are extra servos needing manual control.
1755
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1756
+ */
1576 1757
 //#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
1577 1758
 
1578 1759
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1579 1760
 // 300ms is a good value but you can try less delay.
1580 1761
 // If the servo can't reach the requested position, increase it.
1581
-#define SERVO_DELAY 300
1762
+#define SERVO_DELAY { 300 }
1582 1763
 
1583 1764
 // Servo deactivation
1584 1765
 //
1585 1766
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1586 1767
 //#define DEACTIVATE_SERVOS_AFTER_MOVE
1587 1768
 
1588
-/**
1589
- * Filament Width Sensor
1590
- *
1591
- * Measures the filament width in real-time and adjusts
1592
- * flow rate to compensate for any irregularities.
1593
- *
1594
- * Also allows the measured filament diameter to set the
1595
- * extrusion rate, so the slicer only has to specify the
1596
- * volume.
1597
- *
1598
- * Only a single extruder is supported at this time.
1599
- *
1600
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1601
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1602
- * 301 RAMBO       : Analog input 3
1603
- *
1604
- * Note: May require analog pins to be defined for other boards.
1605
- */
1606
-//#define FILAMENT_WIDTH_SENSOR
1607
-
1608
-#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00   // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
1609
-
1610
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1611
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1612
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1613
-
1614
-  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1615
-  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1616
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1617
-
1618
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1619
-
1620
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1621
-  //#define FILAMENT_LCD_DISPLAY
1622
-#endif
1623
-
1624 1769
 #endif // CONFIGURATION_H

+ 370
- 157
Marlin/example_configurations/RigidBot/Configuration_adv.h 파일 보기

@@ -32,7 +32,7 @@
32 32
  */
33 33
 #ifndef CONFIGURATION_ADV_H
34 34
 #define CONFIGURATION_ADV_H
35
-#define CONFIGURATION_ADV_H_VERSION 010100
35
+#define CONFIGURATION_ADV_H_VERSION 010107
36 36
 
37 37
 // @section temperature
38 38
 
@@ -48,31 +48,36 @@
48 48
 #endif
49 49
 
50 50
 /**
51
- * Thermal Protection protects your printer from damage and fire if a
52
- * thermistor falls out or temperature sensors fail in any way.
51
+ * Thermal Protection provides additional protection to your printer from damage
52
+ * and fire. Marlin always includes safe min and max temperature ranges which
53
+ * protect against a broken or disconnected thermistor wire.
53 54
  *
54
- * The issue: If a thermistor falls out or a temperature sensor fails,
55
- * Marlin can no longer sense the actual temperature. Since a disconnected
56
- * thermistor reads as a low temperature, the firmware will keep the heater on.
55
+ * The issue: If a thermistor falls out, it will report the much lower
56
+ * temperature of the air in the room, and the the firmware will keep
57
+ * the heater on.
57 58
  *
58 59
  * The solution: Once the temperature reaches the target, start observing.
59
- * If the temperature stays too far below the target (hysteresis) for too long (period),
60
- * the firmware will halt the machine as a safety precaution.
60
+ * If the temperature stays too far below the target (hysteresis) for too
61
+ * long (period), the firmware will halt the machine as a safety precaution.
61 62
  *
62
- * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63
+ * If you get false positives for "Thermal Runaway", increase
64
+ * THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63 65
  */
64 66
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
65 67
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
66 68
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
67 69
 
68 70
   /**
69
-   * Whenever an M104 or M109 increases the target temperature the firmware will wait for the
70
-   * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
71
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
72
-   * but only if the current temperature is far enough below the target for a reliable test.
71
+   * Whenever an M104, M109, or M303 increases the target temperature, the
72
+   * firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
73
+   * hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
74
+   * requires a hard reset. This test restarts with any M104/M109/M303, but only
75
+   * if the current temperature is far enough below the target for a reliable
76
+   * test.
73 77
    *
74
-   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
75
-   * WATCH_TEMP_INCREASE should not be below 2.
78
+   * If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
79
+   * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
80
+   * below 2.
76 81
    */
77 82
   #define WATCH_TEMP_PERIOD 20                // Seconds
78 83
   #define WATCH_TEMP_INCREASE 2               // Degrees Celsius
@@ -86,13 +91,7 @@
86 91
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
87 92
 
88 93
   /**
89
-   * Whenever an M140 or M190 increases the target temperature the firmware will wait for the
90
-   * WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
91
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
92
-   * but only if the current temperature is far enough below the target for a reliable test.
93
-   *
94
-   * If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
95
-   * WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
94
+   * As described above, except for the bed (M140/M190/M303).
96 95
    */
97 96
   #define WATCH_BED_TEMP_PERIOD 60                // Seconds
98 97
   #define WATCH_BED_TEMP_INCREASE 2               // Degrees Celsius
@@ -123,6 +122,9 @@
123 122
   #define AUTOTEMP_OLDWEIGHT 0.98
124 123
 #endif
125 124
 
125
+// Show extra position information in M114
126
+//#define M114_DETAIL
127
+
126 128
 // Show Temperature ADC value
127 129
 // Enable for M105 to include ADC values read from temperature sensors.
128 130
 //#define SHOW_TEMP_ADC_VALUES
@@ -221,6 +223,17 @@
221 223
 #define EXTRUDER_AUTO_FAN_SPEED   255  // == full speed
222 224
 
223 225
 /**
226
+ * Part-Cooling Fan Multiplexer
227
+ *
228
+ * This feature allows you to digitally multiplex the fan output.
229
+ * The multiplexer is automatically switched at tool-change.
230
+ * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans.
231
+ */
232
+#define FANMUX0_PIN -1
233
+#define FANMUX1_PIN -1
234
+#define FANMUX2_PIN -1
235
+
236
+/**
224 237
  * M355 Case Light on-off / brightness
225 238
  */
226 239
 //#define CASE_LIGHT_ENABLE
@@ -246,48 +259,49 @@
246 259
 
247 260
 //#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
248 261
 
249
-// Dual X Steppers
250
-// Uncomment this option to drive two X axis motors.
251
-// The next unused E driver will be assigned to the second X stepper.
262
+/**
263
+ * Dual Steppers / Dual Endstops
264
+ *
265
+ * This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
266
+ *
267
+ * For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
268
+ * spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
269
+ * set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
270
+ * that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
271
+ *
272
+ * Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
273
+ * this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
274
+ * in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
275
+ */
276
+
252 277
 //#define X_DUAL_STEPPER_DRIVERS
253 278
 #if ENABLED(X_DUAL_STEPPER_DRIVERS)
254
-  // Set true if the two X motors need to rotate in opposite directions
255
-  #define INVERT_X2_VS_X_DIR true
279
+  #define INVERT_X2_VS_X_DIR true   // Set 'true' if X motors should rotate in opposite directions
280
+  //#define X_DUAL_ENDSTOPS
281
+  #if ENABLED(X_DUAL_ENDSTOPS)
282
+    #define X2_USE_ENDSTOP _XMAX_
283
+    #define X_DUAL_ENDSTOPS_ADJUSTMENT  0
284
+  #endif
256 285
 #endif
257 286
 
258
-// Dual Y Steppers
259
-// Uncomment this option to drive two Y axis motors.
260
-// The next unused E driver will be assigned to the second Y stepper.
261 287
 //#define Y_DUAL_STEPPER_DRIVERS
262 288
 #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
263
-  // Set true if the two Y motors need to rotate in opposite directions
264
-  #define INVERT_Y2_VS_Y_DIR true
289
+  #define INVERT_Y2_VS_Y_DIR true   // Set 'true' if Y motors should rotate in opposite directions
290
+  //#define Y_DUAL_ENDSTOPS
291
+  #if ENABLED(Y_DUAL_ENDSTOPS)
292
+    #define Y2_USE_ENDSTOP _YMAX_
293
+    #define Y_DUAL_ENDSTOPS_ADJUSTMENT  0
294
+  #endif
265 295
 #endif
266 296
 
267
-// A single Z stepper driver is usually used to drive 2 stepper motors.
268
-// Uncomment this option to use a separate stepper driver for each Z axis motor.
269
-// The next unused E driver will be assigned to the second Z stepper.
270 297
 //#define Z_DUAL_STEPPER_DRIVERS
271
-
272 298
 #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
273
-
274
-  // Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper.
275
-  // That way the machine is capable to align the bed during home, since both Z steppers are homed.
276
-  // There is also an implementation of M666 (software endstops adjustment) to this feature.
277
-  // After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
278
-  // One just need to home the Z axis and measure the distance difference between both Z axis and apply the math: Z adjust = Z - Z2.
279
-  // If the Z stepper axis is closer to the bed, the measure Z > Z2 (yes, it is.. think about it) and the Z adjust would be positive.
280
-  // Play a little bit with small adjustments (0.5mm) and check the behaviour.
281
-  // The M119 (endstops report) will start reporting the Z2 Endstop as well.
282
-
283 299
   //#define Z_DUAL_ENDSTOPS
284
-
285 300
   #if ENABLED(Z_DUAL_ENDSTOPS)
286 301
     #define Z2_USE_ENDSTOP _XMAX_
287
-    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0  // use M666 command to determine this value
302
+    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0
288 303
   #endif
289
-
290
-#endif // Z_DUAL_STEPPER_DRIVERS
304
+#endif
291 305
 
292 306
 // Enable this for dual x-carriage printers.
293 307
 // A dual x-carriage design has the advantage that the inactive extruder can be parked which
@@ -334,12 +348,12 @@
334 348
 
335 349
 // @section homing
336 350
 
337
-//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
351
+// Homing hits each endstop, retracts by these distances, then does a slower bump.
338 352
 #define X_HOME_BUMP_MM 5
339 353
 #define Y_HOME_BUMP_MM 5
340 354
 #define Z_HOME_BUMP_MM 2
341
-#define HOMING_BUMP_DIVISOR {2, 2, 4}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
342
-//#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
355
+#define HOMING_BUMP_DIVISOR { 2, 2, 4 }  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
356
+//#define QUICK_HOME                     // If homing includes X and Y, do a diagonal move initially
343 357
 
344 358
 // When G28 is called, this option will make Y home before X
345 359
 //#define HOME_Y_BEFORE_X
@@ -394,7 +408,7 @@
394 408
 // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
395 409
 // of the buffer and all stops. This should not be much greater than zero and should only be changed
396 410
 // if unwanted behavior is observed on a user's machine when running at very slow speeds.
397
-#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
411
+#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
398 412
 
399 413
 // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
400 414
 #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
@@ -423,8 +437,21 @@
423 437
 //#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 }   // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
424 438
 //#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 }    // Default drive percent - X, Y, Z, E axis
425 439
 
426
-// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
440
+// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
427 441
 //#define DIGIPOT_I2C
442
+#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
443
+  /**
444
+   * Common slave addresses:
445
+   *
446
+   *                    A   (A shifted)   B   (B shifted)  IC
447
+   * Smoothie          0x2C (0x58)       0x2D (0x5A)       MCP4451
448
+   * AZTEEG_X3_PRO     0x2C (0x58)       0x2E (0x5C)       MCP4451
449
+   * MIGHTYBOARD_REVE  0x2F (0x5E)                         MCP4018
450
+   */
451
+  #define DIGIPOT_I2C_ADDRESS_A 0x2C  // unshifted slave address for first DIGIPOT
452
+  #define DIGIPOT_I2C_ADDRESS_B 0x2D  // unshifted slave address for second DIGIPOT
453
+#endif
454
+
428 455
 //#define DIGIPOT_MCP4018          // Requires library from https://github.com/stawel/SlowSoftI2CMaster
429 456
 #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4     AZTEEG_X3_PRO: 8
430 457
 // Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
@@ -452,6 +479,26 @@
452 479
 // On the Info Screen, display XY with one decimal place when possible
453 480
 //#define LCD_DECIMAL_SMALL_XY
454 481
 
482
+// The timeout (in ms) to return to the status screen from sub-menus
483
+//#define LCD_TIMEOUT_TO_STATUS 15000
484
+
485
+/**
486
+ * LED Control Menu
487
+ * Enable this feature to add LED Control to the LCD menu
488
+ */
489
+//#define LED_CONTROL_MENU
490
+#if ENABLED(LED_CONTROL_MENU)
491
+  #define LED_COLOR_PRESETS                 // Enable the Preset Color menu option
492
+  #if ENABLED(LED_COLOR_PRESETS)
493
+    #define LED_USER_PRESET_RED        255  // User defined RED value
494
+    #define LED_USER_PRESET_GREEN      128  // User defined GREEN value
495
+    #define LED_USER_PRESET_BLUE         0  // User defined BLUE value
496
+    #define LED_USER_PRESET_WHITE      255  // User defined WHITE value
497
+    #define LED_USER_PRESET_BRIGHTNESS 255  // User defined intensity
498
+    //#define LED_USER_PRESET_STARTUP       // Have the printer display the user preset color on startup
499
+  #endif
500
+#endif // LED_CONTROL_MENU
501
+
455 502
 #if ENABLED(SDSUPPORT)
456 503
 
457 504
   // Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -461,12 +508,14 @@
461 508
   // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
462 509
   #define SD_DETECT_INVERTED
463 510
 
464
-  #define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
511
+  #define SD_FINISHED_STEPPERRELEASE true          // Disable steppers when SD Print is finished
465 512
   #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
466 513
 
467
-  #define SDCARD_RATHERRECENTFIRST  //reverse file order of sd card menu display. Its sorted practically after the file system block order.
468
-  // if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that.
469
-  // using:
514
+  // Reverse SD sort to show "more recent" files first, according to the card's FAT.
515
+  // Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
516
+  #define SDCARD_RATHERRECENTFIRST
517
+
518
+  // Add an option in the menu to run all auto#.g files
470 519
   //#define MENU_ADDAUTOSTART
471 520
 
472 521
   /**
@@ -496,13 +545,15 @@
496 545
 
497 546
   // SD Card Sorting options
498 547
   #if ENABLED(SDCARD_SORT_ALPHA)
499
-    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256).
548
+    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256). Costs 27 bytes each.
500 549
     #define FOLDER_SORTING     -1     // -1=above  0=none  1=below
501 550
     #define SDSORT_GCODE       false  // Allow turning sorting on/off with LCD and M34 g-code.
502 551
     #define SDSORT_USES_RAM    false  // Pre-allocate a static array for faster pre-sorting.
503 552
     #define SDSORT_USES_STACK  false  // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
504 553
     #define SDSORT_CACHE_NAMES false  // Keep sorted items in RAM longer for speedy performance. Most expensive option.
505 554
     #define SDSORT_DYNAMIC_RAM false  // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
555
+    #define SDSORT_CACHE_VFATS 2      // Maximum number of 13-byte VFAT entries to use for sorting.
556
+                                      // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
506 557
   #endif
507 558
 
508 559
   // Show a progress bar on HD44780 LCDs for SD printing
@@ -521,14 +572,29 @@
521 572
     //#define LCD_PROGRESS_BAR_TEST
522 573
   #endif
523 574
 
575
+  // Add an 'M73' G-code to set the current percentage
576
+  //#define LCD_SET_PROGRESS_MANUALLY
577
+
524 578
   // This allows hosts to request long names for files and folders with M33
525 579
   //#define LONG_FILENAME_HOST_SUPPORT
526 580
 
527
-  // This option allows you to abort SD printing when any endstop is triggered.
528
-  // This feature must be enabled with "M540 S1" or from the LCD menu.
529
-  // To have any effect, endstops must be enabled during SD printing.
581
+  // Enable this option to scroll long filenames in the SD card menu
582
+  //#define SCROLL_LONG_FILENAMES
583
+
584
+  /**
585
+   * This option allows you to abort SD printing when any endstop is triggered.
586
+   * This feature must be enabled with "M540 S1" or from the LCD menu.
587
+   * To have any effect, endstops must be enabled during SD printing.
588
+   */
530 589
   //#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
531 590
 
591
+  /**
592
+   * This option makes it easier to print the same SD Card file again.
593
+   * On print completion the LCD Menu will open with the file selected.
594
+   * You can just click to start the print, or navigate elsewhere.
595
+   */
596
+  //#define SD_REPRINT_LAST_SELECTED_FILE
597
+
532 598
 #endif // SDSUPPORT
533 599
 
534 600
 /**
@@ -561,6 +627,10 @@
561 627
   // Enable this option and reduce the value to optimize screen updates.
562 628
   // The normal delay is 10µs. Use the lowest value that still gives a reliable display.
563 629
   //#define DOGM_SPI_DELAY_US 5
630
+
631
+  // Swap the CW/CCW indicators in the graphics overlay
632
+  //#define OVERLAY_GFX_REVERSE
633
+
564 634
 #endif // DOGLCD
565 635
 
566 636
 // @section safety
@@ -587,31 +657,18 @@
587 657
  */
588 658
 //#define BABYSTEPPING
589 659
 #if ENABLED(BABYSTEPPING)
590
-  #define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
591
-  #define BABYSTEP_INVERT_Z false  // Change if Z babysteps should go the other way
592
-  #define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
593
-  //#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
660
+  //#define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
661
+  #define BABYSTEP_INVERT_Z false    // Change if Z babysteps should go the other way
662
+  #define BABYSTEP_MULTIPLICATOR 1   // Babysteps are very small. Increase for faster motion.
663
+  //#define BABYSTEP_ZPROBE_OFFSET   // Enable to combine M851 and Babystepping
594 664
   //#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
595 665
   #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
596 666
                                         // Note: Extra time may be added to mitigate controller latency.
667
+  //#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
597 668
 #endif
598 669
 
599 670
 // @section extruder
600 671
 
601
-// extruder advance constant (s2/mm3)
602
-//
603
-// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
604
-//
605
-// Hooke's law says:    force = k * distance
606
-// Bernoulli's principle says:  v ^ 2 / 2 + g . h + pressure / density = constant
607
-// so: v ^ 2 is proportional to number of steps we advance the extruder
608
-//#define ADVANCE
609
-
610
-#if ENABLED(ADVANCE)
611
-  #define EXTRUDER_ADVANCE_K .0
612
-  #define D_FILAMENT 1.75
613
-#endif
614
-
615 672
 /**
616 673
  * Implementation of linear pressure control
617 674
  *
@@ -645,7 +702,7 @@
645 702
    *
646 703
    * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
647 704
    *
648
-   * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode.
705
+   * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
649 706
    * Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
650 707
    */
651 708
   #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
@@ -654,19 +711,18 @@
654 711
 
655 712
 // @section leveling
656 713
 
657
-// Default mesh area is an area with an inset margin on the print area.
658
-// Below are the macros that are used to define the borders for the mesh area,
659
-// made available here for specialized needs, ie dual extruder setup.
660
-#if ENABLED(MESH_BED_LEVELING)
661
-  #define MESH_MIN_X (X_MIN_POS + MESH_INSET)
662
-  #define MESH_MAX_X (X_MAX_POS - (MESH_INSET))
663
-  #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET)
664
-  #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET))
665
-#elif ENABLED(AUTO_BED_LEVELING_UBL)
666
-  #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET)
667
-  #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET))
668
-  #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET)
669
-  #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET))
714
+#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
715
+  #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
716
+#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
717
+  #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
718
+#endif
719
+
720
+#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
721
+  // Override the mesh area if the automatic (max) area is too large
722
+  //#define MESH_MIN_X MESH_INSET
723
+  //#define MESH_MIN_Y MESH_INSET
724
+  //#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
725
+  //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
670 726
 #endif
671 727
 
672 728
 // @section extras
@@ -686,7 +742,7 @@
686 742
 //#define BEZIER_CURVE_SUPPORT
687 743
 
688 744
 // G38.2 and G38.3 Probe Target
689
-// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
745
+// Set MULTIPLE_PROBING if you want G38 to double touch
690 746
 //#define G38_PROBE_TARGET
691 747
 #if ENABLED(G38_PROBE_TARGET)
692 748
   #define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
@@ -711,7 +767,7 @@
711 767
 // @section hidden
712 768
 
713 769
 // The number of linear motions that can be in the plan at any give time.
714
-// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
770
+// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
715 771
 #if ENABLED(SDSUPPORT)
716 772
   #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
717 773
 #else
@@ -724,7 +780,7 @@
724 780
 #define MAX_CMD_SIZE 96
725 781
 #define BUFSIZE 8
726 782
 
727
-// Transfer Buffer Size
783
+// Transmission to Host Buffer Size
728 784
 // To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0.
729 785
 // To buffer a simple "ok" you need 4 bytes.
730 786
 // For ADVANCED_OK (M105) you need 32 bytes.
@@ -733,6 +789,28 @@
733 789
 // :[0, 2, 4, 8, 16, 32, 64, 128, 256]
734 790
 #define TX_BUFFER_SIZE 0
735 791
 
792
+// Host Receive Buffer Size
793
+// Without XON/XOFF flow control (see SERIAL_XON_XOFF below) 32 bytes should be enough.
794
+// To use flow control, set this buffer size to at least 1024 bytes.
795
+// :[0, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048]
796
+//#define RX_BUFFER_SIZE 1024
797
+
798
+#if RX_BUFFER_SIZE >= 1024
799
+  // Enable to have the controller send XON/XOFF control characters to
800
+  // the host to signal the RX buffer is becoming full.
801
+  //#define SERIAL_XON_XOFF
802
+#endif
803
+
804
+#if ENABLED(SDSUPPORT)
805
+  // Enable this option to collect and display the maximum
806
+  // RX queue usage after transferring a file to SD.
807
+  //#define SERIAL_STATS_MAX_RX_QUEUED
808
+
809
+  // Enable this option to collect and display the number
810
+  // of dropped bytes after a file transfer to SD.
811
+  //#define SERIAL_STATS_DROPPED_RX
812
+#endif
813
+
736 814
 // Enable an emergency-command parser to intercept certain commands as they
737 815
 // enter the serial receive buffer, so they cannot be blocked.
738 816
 // Currently handles M108, M112, M410
@@ -748,27 +826,47 @@
748 826
 // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary.
749 827
 //#define ADVANCED_OK
750 828
 
751
-// @section fwretract
752
-
753
-// Firmware based and LCD controlled retract
754
-// M207 and M208 can be used to define parameters for the retraction.
755
-// The retraction can be called by the slicer using G10 and G11
756
-// until then, intended retractions can be detected by moves that only extrude and the direction.
757
-// the moves are than replaced by the firmware controlled ones.
829
+// @section extras
758 830
 
759
-//#define FWRETRACT  //ONLY PARTIALLY TESTED
831
+/**
832
+ * Firmware-based and LCD-controlled retract
833
+ *
834
+ * Add G10 / G11 commands for automatic firmware-based retract / recover.
835
+ * Use M207 and M208 to define parameters for retract / recover.
836
+ *
837
+ * Use M209 to enable or disable auto-retract.
838
+ * With auto-retract enabled, all G1 E moves within the set range
839
+ * will be converted to firmware-based retract/recover moves.
840
+ *
841
+ * Be sure to turn off auto-retract during filament change.
842
+ *
843
+ * Note that M207 / M208 / M209 settings are saved to EEPROM.
844
+ *
845
+ */
846
+//#define FWRETRACT  // ONLY PARTIALLY TESTED
760 847
 #if ENABLED(FWRETRACT)
761
-  #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
762
-  #define RETRACT_LENGTH 3               //default retract length (positive mm)
763
-  #define RETRACT_LENGTH_SWAP 13         //default swap retract length (positive mm), for extruder change
764
-  #define RETRACT_FEEDRATE 45            //default feedrate for retracting (mm/s)
765
-  #define RETRACT_ZLIFT 0                //default retract Z-lift
766
-  #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
767
-  #define RETRACT_RECOVER_LENGTH_SWAP 0  //default additional swap recover length (mm, added to retract length when recovering from extruder change)
768
-  #define RETRACT_RECOVER_FEEDRATE 8     //default feedrate for recovering from retraction (mm/s)
848
+  #define MIN_AUTORETRACT 0.1             // When auto-retract is on, convert E moves of this length and over
849
+  #define MAX_AUTORETRACT 10.0            // Upper limit for auto-retract conversion
850
+  #define RETRACT_LENGTH 3                // Default retract length (positive mm)
851
+  #define RETRACT_LENGTH_SWAP 13          // Default swap retract length (positive mm), for extruder change
852
+  #define RETRACT_FEEDRATE 45             // Default feedrate for retracting (mm/s)
853
+  #define RETRACT_ZLIFT 0                 // Default retract Z-lift
854
+  #define RETRACT_RECOVER_LENGTH 0        // Default additional recover length (mm, added to retract length when recovering)
855
+  #define RETRACT_RECOVER_LENGTH_SWAP 0   // Default additional swap recover length (mm, added to retract length when recovering from extruder change)
856
+  #define RETRACT_RECOVER_FEEDRATE 8      // Default feedrate for recovering from retraction (mm/s)
857
+  #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
769 858
 #endif
770 859
 
771 860
 /**
861
+ * Extra Fan Speed
862
+ * Adds a secondary fan speed for each print-cooling fan.
863
+ *   'M106 P<fan> T3-255' : Set a secondary speed for <fan>
864
+ *   'M106 P<fan> T2'     : Use the set secondary speed
865
+ *   'M106 P<fan> T1'     : Restore the previous fan speed
866
+ */
867
+//#define EXTRA_FAN_SPEED
868
+
869
+/**
772 870
  * Advanced Pause
773 871
  * Experimental feature for filament change support and for parking the nozzle when paused.
774 872
  * Adds the GCode M600 for initiating filament change.
@@ -878,7 +976,7 @@
878 976
 
879 977
 #endif
880 978
 
881
-// @section TMC2130
979
+// @section TMC2130, TMC2208
882 980
 
883 981
 /**
884 982
  * Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
@@ -892,7 +990,19 @@
892 990
  */
893 991
 //#define HAVE_TMC2130
894 992
 
895
-#if ENABLED(HAVE_TMC2130)
993
+/**
994
+ * Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
995
+ * Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
996
+ * To use the reading capabilities, also connect #_SERIAL_RX_PIN
997
+ * to #_SERIAL_TX_PIN with a 1K resistor.
998
+ * The drivers can also be used with hardware serial.
999
+ *
1000
+ * You'll also need the TMC2208Stepper Arduino library
1001
+ * (https://github.com/teemuatlut/TMC2208Stepper).
1002
+ */
1003
+//#define HAVE_TMC2208
1004
+
1005
+#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
896 1006
 
897 1007
   // CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
898 1008
   //#define X_IS_TMC2130
@@ -907,46 +1017,58 @@
907 1017
   //#define E3_IS_TMC2130
908 1018
   //#define E4_IS_TMC2130
909 1019
 
1020
+  //#define X_IS_TMC2208
1021
+  //#define X2_IS_TMC2208
1022
+  //#define Y_IS_TMC2208
1023
+  //#define Y2_IS_TMC2208
1024
+  //#define Z_IS_TMC2208
1025
+  //#define Z2_IS_TMC2208
1026
+  //#define E0_IS_TMC2208
1027
+  //#define E1_IS_TMC2208
1028
+  //#define E2_IS_TMC2208
1029
+  //#define E3_IS_TMC2208
1030
+  //#define E4_IS_TMC2208
1031
+
910 1032
   /**
911 1033
    * Stepper driver settings
912 1034
    */
913 1035
 
914 1036
   #define R_SENSE           0.11  // R_sense resistor for SilentStepStick2130
915 1037
   #define HOLD_MULTIPLIER    0.5  // Scales down the holding current from run current
916
-  #define INTERPOLATE          1  // Interpolate X/Y/Z_MICROSTEPS to 256
1038
+  #define INTERPOLATE       true  // Interpolate X/Y/Z_MICROSTEPS to 256
917 1039
 
918
-  #define X_CURRENT         1000  // rms current in mA. Multiply by 1.41 for peak current.
1040
+  #define X_CURRENT          800  // rms current in mA. Multiply by 1.41 for peak current.
919 1041
   #define X_MICROSTEPS        16  // 0..256
920 1042
 
921
-  #define Y_CURRENT         1000
1043
+  #define Y_CURRENT          800
922 1044
   #define Y_MICROSTEPS        16
923 1045
 
924
-  #define Z_CURRENT         1000
1046
+  #define Z_CURRENT          800
925 1047
   #define Z_MICROSTEPS        16
926 1048
 
927
-  //#define X2_CURRENT      1000
928
-  //#define X2_MICROSTEPS     16
1049
+  #define X2_CURRENT         800
1050
+  #define X2_MICROSTEPS       16
929 1051
 
930
-  //#define Y2_CURRENT      1000
931
-  //#define Y2_MICROSTEPS     16
1052
+  #define Y2_CURRENT         800
1053
+  #define Y2_MICROSTEPS       16
932 1054
 
933
-  //#define Z2_CURRENT      1000
934
-  //#define Z2_MICROSTEPS     16
1055
+  #define Z2_CURRENT         800
1056
+  #define Z2_MICROSTEPS       16
935 1057
 
936
-  //#define E0_CURRENT      1000
937
-  //#define E0_MICROSTEPS     16
1058
+  #define E0_CURRENT         800
1059
+  #define E0_MICROSTEPS       16
938 1060
 
939
-  //#define E1_CURRENT      1000
940
-  //#define E1_MICROSTEPS     16
1061
+  #define E1_CURRENT         800
1062
+  #define E1_MICROSTEPS       16
941 1063
 
942
-  //#define E2_CURRENT      1000
943
-  //#define E2_MICROSTEPS     16
1064
+  #define E2_CURRENT         800
1065
+  #define E2_MICROSTEPS       16
944 1066
 
945
-  //#define E3_CURRENT      1000
946
-  //#define E3_MICROSTEPS     16
1067
+  #define E3_CURRENT         800
1068
+  #define E3_MICROSTEPS       16
947 1069
 
948
-  //#define E4_CURRENT      1000
949
-  //#define E4_MICROSTEPS     16
1070
+  #define E4_CURRENT         800
1071
+  #define E4_MICROSTEPS       16
950 1072
 
951 1073
   /**
952 1074
    * Use Trinamic's ultra quiet stepping mode.
@@ -955,24 +1077,22 @@
955 1077
   #define STEALTHCHOP
956 1078
 
957 1079
   /**
958
-   * Let Marlin automatically control stepper current.
959
-   * This is still an experimental feature.
960
-   * Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
961
-   * then decrease current by CURRENT_STEP until temperature prewarn is cleared.
962
-   * Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
1080
+   * Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
1081
+   * like overtemperature and short to ground. TMC2208 requires hardware serial.
1082
+   * In the case of overtemperature Marlin can decrease the driver current until error condition clears.
1083
+   * Other detected conditions can be used to stop the current print.
963 1084
    * Relevant g-codes:
964 1085
    * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
965
-   * M906 S1 - Start adjusting current
966
-   * M906 S0 - Stop adjusting current
967 1086
    * M911 - Report stepper driver overtemperature pre-warn condition.
968 1087
    * M912 - Clear stepper driver overtemperature pre-warn condition flag.
1088
+   * M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
969 1089
    */
970
-  //#define AUTOMATIC_CURRENT_CONTROL
1090
+  //#define MONITOR_DRIVER_STATUS
971 1091
 
972
-  #if ENABLED(AUTOMATIC_CURRENT_CONTROL)
973
-    #define CURRENT_STEP          50  // [mA]
974
-    #define AUTO_ADJUST_MAX     1300  // [mA], 1300mA_rms = 1840mA_peak
1092
+  #if ENABLED(MONITOR_DRIVER_STATUS)
1093
+    #define CURRENT_STEP_DOWN     50  // [mA]
975 1094
     #define REPORT_CURRENT_CHANGE
1095
+    #define STOP_ON_ERROR
976 1096
   #endif
977 1097
 
978 1098
   /**
@@ -987,8 +1107,8 @@
987 1107
   #define X2_HYBRID_THRESHOLD    100
988 1108
   #define Y_HYBRID_THRESHOLD     100
989 1109
   #define Y2_HYBRID_THRESHOLD    100
990
-  #define Z_HYBRID_THRESHOLD       4
991
-  #define Z2_HYBRID_THRESHOLD      4
1110
+  #define Z_HYBRID_THRESHOLD       3
1111
+  #define Z2_HYBRID_THRESHOLD      3
992 1112
   #define E0_HYBRID_THRESHOLD     30
993 1113
   #define E1_HYBRID_THRESHOLD     30
994 1114
   #define E2_HYBRID_THRESHOLD     30
@@ -998,7 +1118,7 @@
998 1118
   /**
999 1119
    * Use stallGuard2 to sense an obstacle and trigger an endstop.
1000 1120
    * You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
1001
-   * If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
1121
+   * X and Y homing will always be done in spreadCycle mode.
1002 1122
    *
1003 1123
    * X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
1004 1124
    * Higher values make the system LESS sensitive.
@@ -1007,27 +1127,34 @@
1007 1127
    * It is advised to set X/Y_HOME_BUMP_MM to 0.
1008 1128
    * M914 X/Y to live tune the setting
1009 1129
    */
1010
-  //#define SENSORLESS_HOMING
1130
+  //#define SENSORLESS_HOMING // TMC2130 only
1011 1131
 
1012 1132
   #if ENABLED(SENSORLESS_HOMING)
1013
-    #define X_HOMING_SENSITIVITY  19
1014
-    #define Y_HOMING_SENSITIVITY  19
1133
+    #define X_HOMING_SENSITIVITY  8
1134
+    #define Y_HOMING_SENSITIVITY  8
1015 1135
   #endif
1016 1136
 
1017 1137
   /**
1138
+   * Enable M122 debugging command for TMC stepper drivers.
1139
+   * M122 S0/1 will enable continous reporting.
1140
+   */
1141
+  //#define TMC_DEBUG
1142
+
1143
+  /**
1018 1144
    * You can set your own advanced settings by filling in predefined functions.
1019 1145
    * A list of available functions can be found on the library github page
1020 1146
    * https://github.com/teemuatlut/TMC2130Stepper
1147
+   * https://github.com/teemuatlut/TMC2208Stepper
1021 1148
    *
1022 1149
    * Example:
1023
-   * #define TMC2130_ADV() { \
1150
+   * #define TMC_ADV() { \
1024 1151
    *   stepperX.diag0_temp_prewarn(1); \
1025
-   *   stepperX.interpolate(0); \
1152
+   *   stepperY.interpolate(0); \
1026 1153
    * }
1027 1154
    */
1028
-  #define  TMC2130_ADV() {  }
1155
+  #define  TMC_ADV() {  }
1029 1156
 
1030
-#endif // HAVE_TMC2130
1157
+#endif // TMC2130 || TMC2208
1031 1158
 
1032 1159
 // @section L6470
1033 1160
 
@@ -1192,6 +1319,48 @@
1192 1319
 #endif
1193 1320
 
1194 1321
 /**
1322
+ * Filament Width Sensor
1323
+ *
1324
+ * Measures the filament width in real-time and adjusts
1325
+ * flow rate to compensate for any irregularities.
1326
+ *
1327
+ * Also allows the measured filament diameter to set the
1328
+ * extrusion rate, so the slicer only has to specify the
1329
+ * volume.
1330
+ *
1331
+ * Only a single extruder is supported at this time.
1332
+ *
1333
+ *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1334
+ *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1335
+ * 301 RAMBO       : Analog input 3
1336
+ *
1337
+ * Note: May require analog pins to be defined for other boards.
1338
+ */
1339
+//#define FILAMENT_WIDTH_SENSOR
1340
+
1341
+#if ENABLED(FILAMENT_WIDTH_SENSOR)
1342
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
1343
+  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1344
+
1345
+  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1346
+  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1347
+  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1348
+
1349
+  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1350
+
1351
+  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1352
+  //#define FILAMENT_LCD_DISPLAY
1353
+#endif
1354
+
1355
+/**
1356
+ * CNC Coordinate Systems
1357
+ *
1358
+ * Enables G53 and G54-G59.3 commands to select coordinate systems
1359
+ * and G92.1 to reset the workspace to native machine space.
1360
+ */
1361
+//#define CNC_COORDINATE_SYSTEMS
1362
+
1363
+/**
1195 1364
  * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
1196 1365
  */
1197 1366
 //#define PINS_DEBUGGING
@@ -1244,6 +1413,8 @@
1244 1413
 //#define CUSTOM_USER_MENUS
1245 1414
 #if ENABLED(CUSTOM_USER_MENUS)
1246 1415
   #define USER_SCRIPT_DONE "M117 User Script Done"
1416
+  #define USER_SCRIPT_AUDIBLE_FEEDBACK
1417
+  //#define USER_SCRIPT_RETURN  // Return to status screen after a script
1247 1418
 
1248 1419
   #define USER_DESC_1 "Home & UBL Info"
1249 1420
   #define USER_GCODE_1 "G28\nG29 W"
@@ -1271,6 +1442,7 @@
1271 1442
 //===========================================================================
1272 1443
 //====================== I2C Position Encoder Settings ======================
1273 1444
 //===========================================================================
1445
+
1274 1446
 /**
1275 1447
  *  I2C position encoders for closed loop control.
1276 1448
  *  Developed by Chris Barr at Aus3D.
@@ -1351,4 +1523,45 @@
1351 1523
 
1352 1524
 #endif // I2C_POSITION_ENCODERS
1353 1525
 
1526
+/**
1527
+ * MAX7219 Debug Matrix
1528
+ *
1529
+ * Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
1530
+ * display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
1531
+ *
1532
+ * Fully assembled MAX7219 boards can be found on the internet for under $2(US).
1533
+ * For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
1534
+ */
1535
+//#define MAX7219_DEBUG
1536
+#if ENABLED(MAX7219_DEBUG)
1537
+  #define MAX7219_CLK_PIN   64  // 77 on Re-ARM       // Configuration of the 3 pins to control the display
1538
+  #define MAX7219_DIN_PIN   57  // 78 on Re-ARM
1539
+  #define MAX7219_LOAD_PIN  44  // 79 on Re-ARM
1540
+
1541
+  /**
1542
+   * Sample debug features
1543
+   * If you add more debug displays, be careful to avoid conflicts!
1544
+   */
1545
+  #define MAX7219_DEBUG_PRINTER_ALIVE    // Blink corner LED of 8x8 matrix to show that the firmware is functioning
1546
+  #define MAX7219_DEBUG_STEPPER_HEAD  3  // Show the stepper queue head position on this and the next LED matrix row
1547
+  #define MAX7219_DEBUG_STEPPER_TAIL  5  // Show the stepper queue tail position on this and the next LED matrix row
1548
+
1549
+  #define MAX7219_DEBUG_STEPPER_QUEUE 0  // Show the current stepper queue depth on this and the next LED matrix row
1550
+                                         // If you experience stuttering, reboots, etc. this option can reveal how
1551
+                                         // tweaks made to the configuration are affecting the printer in real-time.
1552
+#endif
1553
+
1554
+/**
1555
+ * NanoDLP Sync support
1556
+ *
1557
+ * Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
1558
+ * string to enable synchronization with DLP projector exposure. This change will allow to use
1559
+ * [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
1560
+ */
1561
+//#define NANODLP_Z_SYNC
1562
+#if ENABLED(NANODLP_Z_SYNC)
1563
+  //#define NANODLP_ALL_AXIS  // Enables "Z_move_comp" output on any axis move.
1564
+                              // Default behaviour is limited to Z axis only.
1565
+#endif
1566
+
1354 1567
 #endif // CONFIGURATION_ADV_H

+ 246
- 101
Marlin/example_configurations/SCARA/Configuration.h 파일 보기

@@ -37,7 +37,7 @@
37 37
  */
38 38
 #ifndef CONFIGURATION_H
39 39
 #define CONFIGURATION_H
40
-#define CONFIGURATION_H_VERSION 010100
40
+#define CONFIGURATION_H_VERSION 010107
41 41
 
42 42
 //===========================================================================
43 43
 //============================= Getting Started =============================
@@ -137,8 +137,9 @@
137 137
  *
138 138
  * 250000 works in most cases, but you might try a lower speed if
139 139
  * you commonly experience drop-outs during host printing.
140
+ * You may try up to 1000000 to speed up SD file transfer.
140 141
  *
141
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
142
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
142 143
  */
143 144
 #define BAUDRATE 250000
144 145
 
@@ -165,6 +166,9 @@
165 166
 // :[1, 2, 3, 4, 5]
166 167
 #define EXTRUDERS 1
167 168
 
169
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
170
+#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
171
+
168 172
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
169 173
 //#define SINGLENOZZLE
170 174
 
@@ -191,7 +195,10 @@
191 195
 //#define SWITCHING_EXTRUDER
192 196
 #if ENABLED(SWITCHING_EXTRUDER)
193 197
   #define SWITCHING_EXTRUDER_SERVO_NR 0
194
-  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1
198
+  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3]
199
+  #if EXTRUDERS > 3
200
+    #define SWITCHING_EXTRUDER_E23_SERVO_NR 1
201
+  #endif
195 202
 #endif
196 203
 
197 204
 // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles
@@ -203,6 +210,21 @@
203 210
 #endif
204 211
 
205 212
 /**
213
+ * Two separate X-carriages with extruders that connect to a moving part
214
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
215
+ */
216
+//#define PARKING_EXTRUDER
217
+#if ENABLED(PARKING_EXTRUDER)
218
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
219
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
220
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
221
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
222
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
223
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
224
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
225
+#endif
226
+
227
+/**
206 228
  * "Mixing Extruder"
207 229
  *   - Adds a new code, M165, to set the current mix factors.
208 230
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -347,8 +369,9 @@
347 369
 
348 370
 // Comment the following line to disable PID and enable bang-bang.
349 371
 #define PIDTEMP
350
-#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
351
-#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
372
+#define BANG_MAX 255     // Limits current to nozzle while in bang-bang mode; 255=full current
373
+#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
374
+#define PID_K1 0.95      // Smoothing factor within the PID
352 375
 #if ENABLED(PIDTEMP)
353 376
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
354 377
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -358,7 +381,6 @@
358 381
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
359 382
   #define PID_FUNCTIONAL_RANGE 20 // If the temperature difference between the target temperature and the actual temperature
360 383
                                   // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
361
-  #define K1 0.95 //smoothing factor within the PID
362 384
 
363 385
   // Merlin Hotend: From Autotune
364 386
   #define  DEFAULT_Kp 24.5
@@ -421,12 +443,13 @@
421 443
 //===========================================================================
422 444
 
423 445
 /**
424
- * Thermal Protection protects your printer from damage and fire if a
425
- * thermistor falls out or temperature sensors fail in any way.
446
+ * Thermal Protection provides additional protection to your printer from damage
447
+ * and fire. Marlin always includes safe min and max temperature ranges which
448
+ * protect against a broken or disconnected thermistor wire.
426 449
  *
427
- * The issue: If a thermistor falls out or a temperature sensor fails,
428
- * Marlin can no longer sense the actual temperature. Since a disconnected
429
- * thermistor reads as a low temperature, the firmware will keep the heater on.
450
+ * The issue: If a thermistor falls out, it will report the much lower
451
+ * temperature of the air in the room, and the the firmware will keep
452
+ * the heater on.
430 453
  *
431 454
  * If you get "Thermal Runaway" or "Heating failed" errors the
432 455
  * details can be tuned in Configuration_adv.h
@@ -566,7 +589,7 @@
566 589
 // @section probes
567 590
 
568 591
 //
569
-// See http://marlinfw.org/configuration/probes.html
592
+// See http://marlinfw.org/docs/configuration/probes.html
570 593
 //
571 594
 
572 595
 /**
@@ -632,14 +655,15 @@
632 655
 #endif
633 656
 
634 657
 /**
635
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
636
- * options selected below - will be disabled during probing so as to minimize
637
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
638
- * in current flowing through the wires).  This is likely most useful to users of the
639
- * BLTouch probe, but may also help those with inductive or other probe types.
658
+ * Enable one or more of the following if probing seems unreliable.
659
+ * Heaters and/or fans can be disabled during probing to minimize electrical
660
+ * noise. A delay can also be added to allow noise and vibration to settle.
661
+ * These options are most useful for the BLTouch probe, but may also improve
662
+ * readings with inductive probes and piezo sensors.
640 663
  */
641 664
 //#define PROBING_HEATERS_OFF       // Turn heaters off when probing
642 665
 //#define PROBING_FANS_OFF          // Turn fans off when probing
666
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
643 667
 
644 668
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
645 669
 //#define SOLENOID_PROBE
@@ -678,14 +702,16 @@
678 702
 // X and Y axis travel speed (mm/m) between probes
679 703
 #define XY_PROBE_SPEED 8000
680 704
 
681
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
705
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
682 706
 #define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
683 707
 
684 708
 // Speed for the "accurate" probe of each point
685 709
 #define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
686 710
 
687
-// Use double touch for probing
688
-//#define PROBE_DOUBLE_TOUCH
711
+// The number of probes to perform at each point.
712
+//   Set to 2 for a fast/slow probe, using the second probe result.
713
+//   Set to 3 or more for slow probes, averaging the results.
714
+//#define MULTIPLE_PROBING 2
689 715
 
690 716
 /**
691 717
  * Z probes require clearance when deploying, stowing, and moving between
@@ -752,6 +778,8 @@
752 778
 
753 779
 // @section homing
754 780
 
781
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
782
+
755 783
 //#define Z_HOMING_HEIGHT 4  // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
756 784
                              // Be sure you have this distance over your Z_MAX_POS in case.
757 785
 
@@ -763,18 +791,42 @@
763 791
 
764 792
 // @section machine
765 793
 
766
-// Travel limits after homing (units are in mm)
794
+// The size of the print bed
795
+#define X_BED_SIZE 200
796
+#define Y_BED_SIZE 200
797
+
798
+// Travel limits (mm) after homing, corresponding to endstop positions.
767 799
 #define X_MIN_POS 0
768 800
 #define Y_MIN_POS 0
769 801
 #define Z_MIN_POS MANUAL_Z_HOME_POS
770
-#define X_MAX_POS 200
771
-#define Y_MAX_POS 200
802
+#define X_MAX_POS X_BED_SIZE
803
+#define Y_MAX_POS Y_BED_SIZE
772 804
 #define Z_MAX_POS 225
773 805
 
774
-// If enabled, axes won't move below MIN_POS in response to movement commands.
806
+/**
807
+ * Software Endstops
808
+ *
809
+ * - Prevent moves outside the set machine bounds.
810
+ * - Individual axes can be disabled, if desired.
811
+ * - X and Y only apply to Cartesian robots.
812
+ * - Use 'M211' to set software endstops on/off or report current state
813
+ */
814
+
815
+// Min software endstops curtail movement below minimum coordinate bounds
775 816
 #define MIN_SOFTWARE_ENDSTOPS
776
-// If enabled, axes won't move above MAX_POS in response to movement commands.
817
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
818
+  #define MIN_SOFTWARE_ENDSTOP_X
819
+  #define MIN_SOFTWARE_ENDSTOP_Y
820
+  #define MIN_SOFTWARE_ENDSTOP_Z
821
+#endif
822
+
823
+// Max software endstops curtail movement above maximum coordinate bounds
777 824
 #define MAX_SOFTWARE_ENDSTOPS
825
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
826
+  #define MAX_SOFTWARE_ENDSTOP_X
827
+  #define MAX_SOFTWARE_ENDSTOP_Y
828
+  #define MAX_SOFTWARE_ENDSTOP_Z
829
+#endif
778 830
 
779 831
 /**
780 832
  * Filament Runout Sensor
@@ -794,7 +846,7 @@
794 846
 //===========================================================================
795 847
 //=============================== Bed Leveling ==============================
796 848
 //===========================================================================
797
-// @section bedlevel
849
+// @section calibrate
798 850
 
799 851
 /**
800 852
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -820,12 +872,7 @@
820 872
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
821 873
  *   A comprehensive bed leveling system combining the features and benefits
822 874
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
823
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
824
- *   for Cartesian Printers. That said, it was primarily designed to correct
825
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
826
- *   please post an issue if something doesn't work correctly. Initially,
827
- *   you will need to set a reduced bed size so you have a rectangular area
828
- *   to test on.
875
+ *   Validation and Mesh Editing systems.
829 876
  *
830 877
  * - MESH_BED_LEVELING
831 878
  *   Probe a grid manually
@@ -852,6 +899,24 @@
852 899
   // at which point movement will be level to the machine's XY plane.
853 900
   // The height can be set with M420 Z<height>
854 901
   #define ENABLE_LEVELING_FADE_HEIGHT
902
+
903
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
904
+  // split up moves into short segments like a Delta. This follows the
905
+  // contours of the bed more closely than edge-to-edge straight moves.
906
+  #define SEGMENT_LEVELED_MOVES
907
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
908
+
909
+  /**
910
+   * Enable the G26 Mesh Validation Pattern tool.
911
+   */
912
+  //#define G26_MESH_VALIDATION   // Enable G26 mesh validation
913
+  #if ENABLED(G26_MESH_VALIDATION)
914
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
915
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
916
+    #define MESH_TEST_HOTEND_TEMP   205.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
917
+    #define MESH_TEST_BED_TEMP       60.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
918
+  #endif
919
+
855 920
 #endif
856 921
 
857 922
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -907,7 +972,9 @@
907 972
   //========================= Unified Bed Leveling ============================
908 973
   //===========================================================================
909 974
 
910
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
975
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
976
+
977
+  #define MESH_INSET 1              // Mesh inset margin on print area
911 978
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
912 979
   #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
913 980
 
@@ -918,8 +985,8 @@
918 985
   #define UBL_PROBE_PT_3_X 180
919 986
   #define UBL_PROBE_PT_3_Y 20
920 987
 
921
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
922 988
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
989
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
923 990
 
924 991
 #elif ENABLED(MESH_BED_LEVELING)
925 992
 
@@ -946,6 +1013,9 @@
946 1013
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
947 1014
 #endif
948 1015
 
1016
+// Add a menu item to move between bed corners for manual bed adjustment
1017
+//#define LEVEL_BED_CORNERS
1018
+
949 1019
 /**
950 1020
  * Commands to execute at the end of G29 probing.
951 1021
  * Useful to retract or move the Z probe out of the way.
@@ -976,14 +1046,71 @@
976 1046
 //#define Z_SAFE_HOMING
977 1047
 
978 1048
 #if ENABLED(Z_SAFE_HOMING)
979
-  #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
980
-  #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
1049
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1050
+  #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2)    // Y point for Z homing when homing all axes (G28).
981 1051
 #endif
982 1052
 
983 1053
 // Homing speeds (mm/m)
984 1054
 #define HOMING_FEEDRATE_XY (40*60)
985 1055
 #define HOMING_FEEDRATE_Z  (10*60)
986 1056
 
1057
+// @section calibrate
1058
+
1059
+/**
1060
+ * Bed Skew Compensation
1061
+ *
1062
+ * This feature corrects for misalignment in the XYZ axes.
1063
+ *
1064
+ * Take the following steps to get the bed skew in the XY plane:
1065
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1066
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1067
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1068
+ *  4. For XY_SIDE_AD measure the edge A to D
1069
+ *
1070
+ * Marlin automatically computes skew factors from these measurements.
1071
+ * Skew factors may also be computed and set manually:
1072
+ *
1073
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1074
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1075
+ *
1076
+ * If desired, follow the same procedure for XZ and YZ.
1077
+ * Use these diagrams for reference:
1078
+ *
1079
+ *    Y                     Z                     Z
1080
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1081
+ *    |    /       /        |    /       /        |    /       /
1082
+ *    |   /       /         |   /       /         |   /       /
1083
+ *    |  A-------D          |  A-------D          |  A-------D
1084
+ *    +-------------->X     +-------------->X     +-------------->Y
1085
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1086
+ */
1087
+//#define SKEW_CORRECTION
1088
+
1089
+#if ENABLED(SKEW_CORRECTION)
1090
+  // Input all length measurements here:
1091
+  #define XY_DIAG_AC 282.8427124746
1092
+  #define XY_DIAG_BD 282.8427124746
1093
+  #define XY_SIDE_AD 200
1094
+
1095
+  // Or, set the default skew factors directly here
1096
+  // to override the above measurements:
1097
+  #define XY_SKEW_FACTOR 0.0
1098
+
1099
+  //#define SKEW_CORRECTION_FOR_Z
1100
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1101
+    #define XZ_DIAG_AC 282.8427124746
1102
+    #define XZ_DIAG_BD 282.8427124746
1103
+    #define YZ_DIAG_AC 282.8427124746
1104
+    #define YZ_DIAG_BD 282.8427124746
1105
+    #define YZ_SIDE_AD 200
1106
+    #define XZ_SKEW_FACTOR 0.0
1107
+    #define YZ_SKEW_FACTOR 0.0
1108
+  #endif
1109
+
1110
+  // Enable this option for M852 to set skew at runtime
1111
+  //#define SKEW_CORRECTION_GCODE
1112
+#endif
1113
+
987 1114
 //=============================================================================
988 1115
 //============================= Additional Features ===========================
989 1116
 //=============================================================================
@@ -1010,11 +1137,12 @@
1010 1137
 //
1011 1138
 #define HOST_KEEPALIVE_FEATURE        // Disable this if your host doesn't like keepalive messages
1012 1139
 #define DEFAULT_KEEPALIVE_INTERVAL 2  // Number of seconds between "busy" messages. Set with M113.
1140
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
1013 1141
 
1014 1142
 //
1015 1143
 // M100 Free Memory Watcher
1016 1144
 //
1017
-//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1145
+//#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
1018 1146
 
1019 1147
 //
1020 1148
 // G20/G21 Inch mode support
@@ -1159,13 +1287,13 @@
1159 1287
  *
1160 1288
  * Select the language to display on the LCD. These languages are available:
1161 1289
  *
1162
- *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
1163
- *    it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
1164
- *    zh_CN, zh_TW, test
1290
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1291
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1292
+ *    tr, uk, zh_CN, zh_TW, test
1165 1293
  *
1166
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1294
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1167 1295
  */
1168
-//#define LCD_LANGUAGE en
1296
+#define LCD_LANGUAGE en
1169 1297
 
1170 1298
 /**
1171 1299
  * LCD Character Set
@@ -1185,7 +1313,7 @@
1185 1313
  *  - Click the controller to view the LCD menu
1186 1314
  *  - The LCD will display Japanese, Western, or Cyrillic text
1187 1315
  *
1188
- * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1316
+ * See http://marlinfw.org/docs/development/lcd_language.html
1189 1317
  *
1190 1318
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1191 1319
  */
@@ -1291,8 +1419,8 @@
1291 1419
 // Note: Test audio output with the G-Code:
1292 1420
 //  M300 S<frequency Hz> P<duration ms>
1293 1421
 //
1294
-//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
1295
-//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
1422
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
1423
+//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
1296 1424
 
1297 1425
 //
1298 1426
 // CONTROLLER TYPE: Standard
@@ -1400,11 +1528,13 @@
1400 1528
 //#define CARTESIO_UI
1401 1529
 
1402 1530
 //
1403
-// ANET_10 Controller supported displays.
1531
+// ANET and Tronxy Controller supported displays.
1404 1532
 //
1405
-//#define ANET_KEYPAD_LCD         // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1533
+//#define ZONESTAR_LCD            // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1406 1534
                                   // This LCD is known to be susceptible to electrical interference
1407 1535
                                   // which scrambles the display.  Pressing any button clears it up.
1536
+                                  // This is a LCD2004 display with 5 analog buttons.
1537
+
1408 1538
 //#define ANET_FULL_GRAPHICS_LCD  // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1409 1539
                                   // A clone of the RepRapDiscount full graphics display but with
1410 1540
                                   // different pins/wiring (see pins_ANET_10.h).
@@ -1464,11 +1594,6 @@
1464 1594
 //#define U8GLIB_SSD1306
1465 1595
 
1466 1596
 //
1467
-// TinyBoy2 128x64 OLED / Encoder Panel
1468
-//
1469
-//#define OLED_PANEL_TINYBOY2
1470
-
1471
-//
1472 1597
 // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules
1473 1598
 //
1474 1599
 //#define SAV_3DGLCD
@@ -1485,6 +1610,45 @@
1485 1610
 //
1486 1611
 //#define SAV_3DLCD
1487 1612
 
1613
+//
1614
+// TinyBoy2 128x64 OLED / Encoder Panel
1615
+//
1616
+//#define OLED_PANEL_TINYBOY2
1617
+
1618
+//
1619
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1620
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1621
+//
1622
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1623
+
1624
+//
1625
+// MKS MINI12864 with graphic controller and SD support
1626
+// http://reprap.org/wiki/MKS_MINI_12864
1627
+//
1628
+//#define MKS_MINI_12864
1629
+
1630
+//
1631
+// Factory display for Creality CR-10
1632
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1633
+//
1634
+// This is RAMPS-compatible using a single 10-pin connector.
1635
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1636
+//
1637
+//#define CR10_STOCKDISPLAY
1638
+
1639
+//
1640
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1641
+// http://reprap.org/wiki/MKS_12864OLED
1642
+//
1643
+// Tiny, but very sharp OLED display
1644
+//
1645
+//#define MKS_12864OLED
1646
+
1647
+// Silvergate GLCD controller
1648
+// http://github.com/android444/Silvergate
1649
+//
1650
+//#define SILVER_GATE_GLCD_CONTROLLER
1651
+
1488 1652
 //=============================================================================
1489 1653
 //=============================== Extra Features ==============================
1490 1654
 //=============================================================================
@@ -1541,16 +1705,22 @@
1541 1705
  * Adds the M150 command to set the LED (or LED strip) color.
1542 1706
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1543 1707
  * luminance values can be set from 0 to 255.
1708
+ * For Neopixel LED an overall brightness parameter is also available.
1544 1709
  *
1545 1710
  * *** CAUTION ***
1546 1711
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1547 1712
  *  as the Arduino cannot handle the current the LEDs will require.
1548 1713
  *  Failure to follow this precaution can destroy your Arduino!
1714
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1715
+ *  more current than the Arduino 5V linear regulator can produce.
1549 1716
  * *** CAUTION ***
1550 1717
  *
1718
+ * LED Type. Enable only one of the following two options.
1719
+ *
1551 1720
  */
1552 1721
 //#define RGB_LED
1553 1722
 //#define RGBW_LED
1723
+
1554 1724
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1555 1725
   #define RGB_LED_R_PIN 34
1556 1726
   #define RGB_LED_G_PIN 43
@@ -1558,6 +1728,17 @@
1558 1728
   #define RGB_LED_W_PIN -1
1559 1729
 #endif
1560 1730
 
1731
+// Support for Adafruit Neopixel LED driver
1732
+//#define NEOPIXEL_LED
1733
+#if ENABLED(NEOPIXEL_LED)
1734
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1735
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1736
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1737
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1738
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1739
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1740
+#endif
1741
+
1561 1742
 /**
1562 1743
  * Printer Event LEDs
1563 1744
  *
@@ -1569,68 +1750,32 @@
1569 1750
  *  - Change to green once print has finished
1570 1751
  *  - Turn off after the print has finished and the user has pushed a button
1571 1752
  */
1572
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)
1753
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1573 1754
   #define PRINTER_EVENT_LEDS
1574 1755
 #endif
1575 1756
 
1576
-/*********************************************************************\
1577
-* R/C SERVO support
1578
-* Sponsored by TrinityLabs, Reworked by codexmas
1579
-**********************************************************************/
1757
+/**
1758
+ * R/C SERVO support
1759
+ * Sponsored by TrinityLabs, Reworked by codexmas
1760
+ */
1580 1761
 
1581
-// Number of servos
1582
-//
1583
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1584
-// set it manually if you have more servos than extruders and wish to manually control some
1585
-// leaving it undefined or defining as 0 will disable the servo subsystem
1586
-// If unsure, leave commented / disabled
1587
-//
1762
+/**
1763
+ * Number of servos
1764
+ *
1765
+ * For some servo-related options NUM_SERVOS will be set automatically.
1766
+ * Set this manually if there are extra servos needing manual control.
1767
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1768
+ */
1588 1769
 //#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
1589 1770
 
1590 1771
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1591 1772
 // 300ms is a good value but you can try less delay.
1592 1773
 // If the servo can't reach the requested position, increase it.
1593
-#define SERVO_DELAY 300
1774
+#define SERVO_DELAY { 300 }
1594 1775
 
1595 1776
 // Servo deactivation
1596 1777
 //
1597 1778
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1598 1779
 //#define DEACTIVATE_SERVOS_AFTER_MOVE
1599 1780
 
1600
-/**
1601
- * Filament Width Sensor
1602
- *
1603
- * Measures the filament width in real-time and adjusts
1604
- * flow rate to compensate for any irregularities.
1605
- *
1606
- * Also allows the measured filament diameter to set the
1607
- * extrusion rate, so the slicer only has to specify the
1608
- * volume.
1609
- *
1610
- * Only a single extruder is supported at this time.
1611
- *
1612
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1613
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1614
- * 301 RAMBO       : Analog input 3
1615
- *
1616
- * Note: May require analog pins to be defined for other boards.
1617
- */
1618
-//#define FILAMENT_WIDTH_SENSOR
1619
-
1620
-#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00   // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
1621
-
1622
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1623
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1624
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1625
-
1626
-  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1627
-  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1628
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1629
-
1630
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1631
-
1632
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1633
-  //#define FILAMENT_LCD_DISPLAY
1634
-#endif
1635
-
1636 1781
 #endif // CONFIGURATION_H

+ 370
- 157
Marlin/example_configurations/SCARA/Configuration_adv.h 파일 보기

@@ -32,7 +32,7 @@
32 32
  */
33 33
 #ifndef CONFIGURATION_ADV_H
34 34
 #define CONFIGURATION_ADV_H
35
-#define CONFIGURATION_ADV_H_VERSION 010100
35
+#define CONFIGURATION_ADV_H_VERSION 010107
36 36
 
37 37
 // @section temperature
38 38
 
@@ -48,31 +48,36 @@
48 48
 #endif
49 49
 
50 50
 /**
51
- * Thermal Protection protects your printer from damage and fire if a
52
- * thermistor falls out or temperature sensors fail in any way.
51
+ * Thermal Protection provides additional protection to your printer from damage
52
+ * and fire. Marlin always includes safe min and max temperature ranges which
53
+ * protect against a broken or disconnected thermistor wire.
53 54
  *
54
- * The issue: If a thermistor falls out or a temperature sensor fails,
55
- * Marlin can no longer sense the actual temperature. Since a disconnected
56
- * thermistor reads as a low temperature, the firmware will keep the heater on.
55
+ * The issue: If a thermistor falls out, it will report the much lower
56
+ * temperature of the air in the room, and the the firmware will keep
57
+ * the heater on.
57 58
  *
58 59
  * The solution: Once the temperature reaches the target, start observing.
59
- * If the temperature stays too far below the target (hysteresis) for too long (period),
60
- * the firmware will halt the machine as a safety precaution.
60
+ * If the temperature stays too far below the target (hysteresis) for too
61
+ * long (period), the firmware will halt the machine as a safety precaution.
61 62
  *
62
- * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63
+ * If you get false positives for "Thermal Runaway", increase
64
+ * THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63 65
  */
64 66
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
65 67
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
66 68
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
67 69
 
68 70
   /**
69
-   * Whenever an M104 or M109 increases the target temperature the firmware will wait for the
70
-   * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
71
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
72
-   * but only if the current temperature is far enough below the target for a reliable test.
71
+   * Whenever an M104, M109, or M303 increases the target temperature, the
72
+   * firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
73
+   * hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
74
+   * requires a hard reset. This test restarts with any M104/M109/M303, but only
75
+   * if the current temperature is far enough below the target for a reliable
76
+   * test.
73 77
    *
74
-   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
75
-   * WATCH_TEMP_INCREASE should not be below 2.
78
+   * If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
79
+   * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
80
+   * below 2.
76 81
    */
77 82
   #define WATCH_TEMP_PERIOD 20                // Seconds
78 83
   #define WATCH_TEMP_INCREASE 2               // Degrees Celsius
@@ -86,13 +91,7 @@
86 91
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
87 92
 
88 93
   /**
89
-   * Whenever an M140 or M190 increases the target temperature the firmware will wait for the
90
-   * WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
91
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
92
-   * but only if the current temperature is far enough below the target for a reliable test.
93
-   *
94
-   * If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
95
-   * WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
94
+   * As described above, except for the bed (M140/M190/M303).
96 95
    */
97 96
   #define WATCH_BED_TEMP_PERIOD 60                // Seconds
98 97
   #define WATCH_BED_TEMP_INCREASE 2               // Degrees Celsius
@@ -123,6 +122,9 @@
123 122
   #define AUTOTEMP_OLDWEIGHT 0.98
124 123
 #endif
125 124
 
125
+// Show extra position information in M114
126
+//#define M114_DETAIL
127
+
126 128
 // Show Temperature ADC value
127 129
 // Enable for M105 to include ADC values read from temperature sensors.
128 130
 //#define SHOW_TEMP_ADC_VALUES
@@ -221,6 +223,17 @@
221 223
 #define EXTRUDER_AUTO_FAN_SPEED   255  // == full speed
222 224
 
223 225
 /**
226
+ * Part-Cooling Fan Multiplexer
227
+ *
228
+ * This feature allows you to digitally multiplex the fan output.
229
+ * The multiplexer is automatically switched at tool-change.
230
+ * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans.
231
+ */
232
+#define FANMUX0_PIN -1
233
+#define FANMUX1_PIN -1
234
+#define FANMUX2_PIN -1
235
+
236
+/**
224 237
  * M355 Case Light on-off / brightness
225 238
  */
226 239
 //#define CASE_LIGHT_ENABLE
@@ -246,48 +259,49 @@
246 259
 
247 260
 //#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
248 261
 
249
-// Dual X Steppers
250
-// Uncomment this option to drive two X axis motors.
251
-// The next unused E driver will be assigned to the second X stepper.
262
+/**
263
+ * Dual Steppers / Dual Endstops
264
+ *
265
+ * This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
266
+ *
267
+ * For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
268
+ * spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
269
+ * set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
270
+ * that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
271
+ *
272
+ * Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
273
+ * this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
274
+ * in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
275
+ */
276
+
252 277
 //#define X_DUAL_STEPPER_DRIVERS
253 278
 #if ENABLED(X_DUAL_STEPPER_DRIVERS)
254
-  // Set true if the two X motors need to rotate in opposite directions
255
-  #define INVERT_X2_VS_X_DIR true
279
+  #define INVERT_X2_VS_X_DIR true   // Set 'true' if X motors should rotate in opposite directions
280
+  //#define X_DUAL_ENDSTOPS
281
+  #if ENABLED(X_DUAL_ENDSTOPS)
282
+    #define X2_USE_ENDSTOP _XMAX_
283
+    #define X_DUAL_ENDSTOPS_ADJUSTMENT  0
284
+  #endif
256 285
 #endif
257 286
 
258
-// Dual Y Steppers
259
-// Uncomment this option to drive two Y axis motors.
260
-// The next unused E driver will be assigned to the second Y stepper.
261 287
 //#define Y_DUAL_STEPPER_DRIVERS
262 288
 #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
263
-  // Set true if the two Y motors need to rotate in opposite directions
264
-  #define INVERT_Y2_VS_Y_DIR true
289
+  #define INVERT_Y2_VS_Y_DIR true   // Set 'true' if Y motors should rotate in opposite directions
290
+  //#define Y_DUAL_ENDSTOPS
291
+  #if ENABLED(Y_DUAL_ENDSTOPS)
292
+    #define Y2_USE_ENDSTOP _YMAX_
293
+    #define Y_DUAL_ENDSTOPS_ADJUSTMENT  0
294
+  #endif
265 295
 #endif
266 296
 
267
-// A single Z stepper driver is usually used to drive 2 stepper motors.
268
-// Uncomment this option to use a separate stepper driver for each Z axis motor.
269
-// The next unused E driver will be assigned to the second Z stepper.
270 297
 //#define Z_DUAL_STEPPER_DRIVERS
271
-
272 298
 #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
273
-
274
-  // Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper.
275
-  // That way the machine is capable to align the bed during home, since both Z steppers are homed.
276
-  // There is also an implementation of M666 (software endstops adjustment) to this feature.
277
-  // After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
278
-  // One just need to home the Z axis and measure the distance difference between both Z axis and apply the math: Z adjust = Z - Z2.
279
-  // If the Z stepper axis is closer to the bed, the measure Z > Z2 (yes, it is.. think about it) and the Z adjust would be positive.
280
-  // Play a little bit with small adjustments (0.5mm) and check the behaviour.
281
-  // The M119 (endstops report) will start reporting the Z2 Endstop as well.
282
-
283 299
   //#define Z_DUAL_ENDSTOPS
284
-
285 300
   #if ENABLED(Z_DUAL_ENDSTOPS)
286 301
     #define Z2_USE_ENDSTOP _XMAX_
287
-    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0  // use M666 command to determine this value
302
+    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0
288 303
   #endif
289
-
290
-#endif // Z_DUAL_STEPPER_DRIVERS
304
+#endif
291 305
 
292 306
 // Enable this for dual x-carriage printers.
293 307
 // A dual x-carriage design has the advantage that the inactive extruder can be parked which
@@ -334,12 +348,12 @@
334 348
 
335 349
 // @section homing
336 350
 
337
-//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
351
+// Homing hits each endstop, retracts by these distances, then does a slower bump.
338 352
 #define X_HOME_BUMP_MM 3
339 353
 #define Y_HOME_BUMP_MM 3
340 354
 #define Z_HOME_BUMP_MM 3
341
-#define HOMING_BUMP_DIVISOR {2, 2, 4}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
342
-//#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
355
+#define HOMING_BUMP_DIVISOR { 2, 2, 4 }  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
356
+//#define QUICK_HOME                     // If homing includes X and Y, do a diagonal move initially
343 357
 
344 358
 // When G28 is called, this option will make Y home before X
345 359
 //#define HOME_Y_BEFORE_X
@@ -394,7 +408,7 @@
394 408
 // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
395 409
 // of the buffer and all stops. This should not be much greater than zero and should only be changed
396 410
 // if unwanted behavior is observed on a user's machine when running at very slow speeds.
397
-#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
411
+#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
398 412
 
399 413
 // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
400 414
 #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
@@ -423,8 +437,21 @@
423 437
 //#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 }   // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
424 438
 //#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 }    // Default drive percent - X, Y, Z, E axis
425 439
 
426
-// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
440
+// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
427 441
 //#define DIGIPOT_I2C
442
+#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
443
+  /**
444
+   * Common slave addresses:
445
+   *
446
+   *                    A   (A shifted)   B   (B shifted)  IC
447
+   * Smoothie          0x2C (0x58)       0x2D (0x5A)       MCP4451
448
+   * AZTEEG_X3_PRO     0x2C (0x58)       0x2E (0x5C)       MCP4451
449
+   * MIGHTYBOARD_REVE  0x2F (0x5E)                         MCP4018
450
+   */
451
+  #define DIGIPOT_I2C_ADDRESS_A 0x2C  // unshifted slave address for first DIGIPOT
452
+  #define DIGIPOT_I2C_ADDRESS_B 0x2D  // unshifted slave address for second DIGIPOT
453
+#endif
454
+
428 455
 //#define DIGIPOT_MCP4018          // Requires library from https://github.com/stawel/SlowSoftI2CMaster
429 456
 #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4     AZTEEG_X3_PRO: 8
430 457
 // Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
@@ -452,6 +479,26 @@
452 479
 // On the Info Screen, display XY with one decimal place when possible
453 480
 //#define LCD_DECIMAL_SMALL_XY
454 481
 
482
+// The timeout (in ms) to return to the status screen from sub-menus
483
+//#define LCD_TIMEOUT_TO_STATUS 15000
484
+
485
+/**
486
+ * LED Control Menu
487
+ * Enable this feature to add LED Control to the LCD menu
488
+ */
489
+//#define LED_CONTROL_MENU
490
+#if ENABLED(LED_CONTROL_MENU)
491
+  #define LED_COLOR_PRESETS                 // Enable the Preset Color menu option
492
+  #if ENABLED(LED_COLOR_PRESETS)
493
+    #define LED_USER_PRESET_RED        255  // User defined RED value
494
+    #define LED_USER_PRESET_GREEN      128  // User defined GREEN value
495
+    #define LED_USER_PRESET_BLUE         0  // User defined BLUE value
496
+    #define LED_USER_PRESET_WHITE      255  // User defined WHITE value
497
+    #define LED_USER_PRESET_BRIGHTNESS 255  // User defined intensity
498
+    //#define LED_USER_PRESET_STARTUP       // Have the printer display the user preset color on startup
499
+  #endif
500
+#endif // LED_CONTROL_MENU
501
+
455 502
 #if ENABLED(SDSUPPORT)
456 503
 
457 504
   // Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -461,12 +508,14 @@
461 508
   // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
462 509
   #define SD_DETECT_INVERTED
463 510
 
464
-  #define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
511
+  #define SD_FINISHED_STEPPERRELEASE true          // Disable steppers when SD Print is finished
465 512
   #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
466 513
 
467
-  #define SDCARD_RATHERRECENTFIRST  //reverse file order of sd card menu display. Its sorted practically after the file system block order.
468
-  // if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that.
469
-  // using:
514
+  // Reverse SD sort to show "more recent" files first, according to the card's FAT.
515
+  // Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
516
+  #define SDCARD_RATHERRECENTFIRST
517
+
518
+  // Add an option in the menu to run all auto#.g files
470 519
   //#define MENU_ADDAUTOSTART
471 520
 
472 521
   /**
@@ -496,13 +545,15 @@
496 545
 
497 546
   // SD Card Sorting options
498 547
   #if ENABLED(SDCARD_SORT_ALPHA)
499
-    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256).
548
+    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256). Costs 27 bytes each.
500 549
     #define FOLDER_SORTING     -1     // -1=above  0=none  1=below
501 550
     #define SDSORT_GCODE       false  // Allow turning sorting on/off with LCD and M34 g-code.
502 551
     #define SDSORT_USES_RAM    false  // Pre-allocate a static array for faster pre-sorting.
503 552
     #define SDSORT_USES_STACK  false  // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
504 553
     #define SDSORT_CACHE_NAMES false  // Keep sorted items in RAM longer for speedy performance. Most expensive option.
505 554
     #define SDSORT_DYNAMIC_RAM false  // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
555
+    #define SDSORT_CACHE_VFATS 2      // Maximum number of 13-byte VFAT entries to use for sorting.
556
+                                      // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
506 557
   #endif
507 558
 
508 559
   // Show a progress bar on HD44780 LCDs for SD printing
@@ -521,14 +572,29 @@
521 572
     //#define LCD_PROGRESS_BAR_TEST
522 573
   #endif
523 574
 
575
+  // Add an 'M73' G-code to set the current percentage
576
+  //#define LCD_SET_PROGRESS_MANUALLY
577
+
524 578
   // This allows hosts to request long names for files and folders with M33
525 579
   //#define LONG_FILENAME_HOST_SUPPORT
526 580
 
527
-  // This option allows you to abort SD printing when any endstop is triggered.
528
-  // This feature must be enabled with "M540 S1" or from the LCD menu.
529
-  // To have any effect, endstops must be enabled during SD printing.
581
+  // Enable this option to scroll long filenames in the SD card menu
582
+  //#define SCROLL_LONG_FILENAMES
583
+
584
+  /**
585
+   * This option allows you to abort SD printing when any endstop is triggered.
586
+   * This feature must be enabled with "M540 S1" or from the LCD menu.
587
+   * To have any effect, endstops must be enabled during SD printing.
588
+   */
530 589
   //#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
531 590
 
591
+  /**
592
+   * This option makes it easier to print the same SD Card file again.
593
+   * On print completion the LCD Menu will open with the file selected.
594
+   * You can just click to start the print, or navigate elsewhere.
595
+   */
596
+  //#define SD_REPRINT_LAST_SELECTED_FILE
597
+
532 598
 #endif // SDSUPPORT
533 599
 
534 600
 /**
@@ -561,6 +627,10 @@
561 627
   // Enable this option and reduce the value to optimize screen updates.
562 628
   // The normal delay is 10µs. Use the lowest value that still gives a reliable display.
563 629
   //#define DOGM_SPI_DELAY_US 5
630
+
631
+  // Swap the CW/CCW indicators in the graphics overlay
632
+  //#define OVERLAY_GFX_REVERSE
633
+
564 634
 #endif // DOGLCD
565 635
 
566 636
 // @section safety
@@ -587,31 +657,18 @@
587 657
  */
588 658
 //#define BABYSTEPPING
589 659
 #if ENABLED(BABYSTEPPING)
590
-  #define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
591
-  #define BABYSTEP_INVERT_Z false  // Change if Z babysteps should go the other way
592
-  #define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
593
-  //#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
660
+  //#define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
661
+  #define BABYSTEP_INVERT_Z false    // Change if Z babysteps should go the other way
662
+  #define BABYSTEP_MULTIPLICATOR 1   // Babysteps are very small. Increase for faster motion.
663
+  //#define BABYSTEP_ZPROBE_OFFSET   // Enable to combine M851 and Babystepping
594 664
   //#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
595 665
   #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
596 666
                                         // Note: Extra time may be added to mitigate controller latency.
667
+  //#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
597 668
 #endif
598 669
 
599 670
 // @section extruder
600 671
 
601
-// extruder advance constant (s2/mm3)
602
-//
603
-// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
604
-//
605
-// Hooke's law says:    force = k * distance
606
-// Bernoulli's principle says:  v ^ 2 / 2 + g . h + pressure / density = constant
607
-// so: v ^ 2 is proportional to number of steps we advance the extruder
608
-#define ADVANCE
609
-
610
-#if ENABLED(ADVANCE)
611
-  #define EXTRUDER_ADVANCE_K .0
612
-  #define D_FILAMENT 1.75
613
-#endif
614
-
615 672
 /**
616 673
  * Implementation of linear pressure control
617 674
  *
@@ -645,7 +702,7 @@
645 702
    *
646 703
    * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
647 704
    *
648
-   * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode.
705
+   * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
649 706
    * Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
650 707
    */
651 708
   #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
@@ -654,19 +711,18 @@
654 711
 
655 712
 // @section leveling
656 713
 
657
-// Default mesh area is an area with an inset margin on the print area.
658
-// Below are the macros that are used to define the borders for the mesh area,
659
-// made available here for specialized needs, ie dual extruder setup.
660
-#if ENABLED(MESH_BED_LEVELING)
661
-  #define MESH_MIN_X (X_MIN_POS + MESH_INSET)
662
-  #define MESH_MAX_X (X_MAX_POS - (MESH_INSET))
663
-  #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET)
664
-  #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET))
665
-#elif ENABLED(AUTO_BED_LEVELING_UBL)
666
-  #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET)
667
-  #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET))
668
-  #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET)
669
-  #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET))
714
+#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
715
+  #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
716
+#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
717
+  #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
718
+#endif
719
+
720
+#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
721
+  // Override the mesh area if the automatic (max) area is too large
722
+  //#define MESH_MIN_X MESH_INSET
723
+  //#define MESH_MIN_Y MESH_INSET
724
+  //#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
725
+  //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
670 726
 #endif
671 727
 
672 728
 // @section extras
@@ -686,7 +742,7 @@
686 742
 //#define BEZIER_CURVE_SUPPORT
687 743
 
688 744
 // G38.2 and G38.3 Probe Target
689
-// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
745
+// Set MULTIPLE_PROBING if you want G38 to double touch
690 746
 //#define G38_PROBE_TARGET
691 747
 #if ENABLED(G38_PROBE_TARGET)
692 748
   #define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
@@ -711,7 +767,7 @@
711 767
 // @section hidden
712 768
 
713 769
 // The number of linear motions that can be in the plan at any give time.
714
-// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
770
+// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
715 771
 #if ENABLED(SDSUPPORT)
716 772
   #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
717 773
 #else
@@ -724,7 +780,7 @@
724 780
 #define MAX_CMD_SIZE 96
725 781
 #define BUFSIZE 4
726 782
 
727
-// Transfer Buffer Size
783
+// Transmission to Host Buffer Size
728 784
 // To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0.
729 785
 // To buffer a simple "ok" you need 4 bytes.
730 786
 // For ADVANCED_OK (M105) you need 32 bytes.
@@ -733,6 +789,28 @@
733 789
 // :[0, 2, 4, 8, 16, 32, 64, 128, 256]
734 790
 #define TX_BUFFER_SIZE 0
735 791
 
792
+// Host Receive Buffer Size
793
+// Without XON/XOFF flow control (see SERIAL_XON_XOFF below) 32 bytes should be enough.
794
+// To use flow control, set this buffer size to at least 1024 bytes.
795
+// :[0, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048]
796
+//#define RX_BUFFER_SIZE 1024
797
+
798
+#if RX_BUFFER_SIZE >= 1024
799
+  // Enable to have the controller send XON/XOFF control characters to
800
+  // the host to signal the RX buffer is becoming full.
801
+  //#define SERIAL_XON_XOFF
802
+#endif
803
+
804
+#if ENABLED(SDSUPPORT)
805
+  // Enable this option to collect and display the maximum
806
+  // RX queue usage after transferring a file to SD.
807
+  //#define SERIAL_STATS_MAX_RX_QUEUED
808
+
809
+  // Enable this option to collect and display the number
810
+  // of dropped bytes after a file transfer to SD.
811
+  //#define SERIAL_STATS_DROPPED_RX
812
+#endif
813
+
736 814
 // Enable an emergency-command parser to intercept certain commands as they
737 815
 // enter the serial receive buffer, so they cannot be blocked.
738 816
 // Currently handles M108, M112, M410
@@ -748,27 +826,47 @@
748 826
 // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary.
749 827
 //#define ADVANCED_OK
750 828
 
751
-// @section fwretract
752
-
753
-// Firmware based and LCD controlled retract
754
-// M207 and M208 can be used to define parameters for the retraction.
755
-// The retraction can be called by the slicer using G10 and G11
756
-// until then, intended retractions can be detected by moves that only extrude and the direction.
757
-// the moves are than replaced by the firmware controlled ones.
829
+// @section extras
758 830
 
759
-//#define FWRETRACT  //ONLY PARTIALLY TESTED
831
+/**
832
+ * Firmware-based and LCD-controlled retract
833
+ *
834
+ * Add G10 / G11 commands for automatic firmware-based retract / recover.
835
+ * Use M207 and M208 to define parameters for retract / recover.
836
+ *
837
+ * Use M209 to enable or disable auto-retract.
838
+ * With auto-retract enabled, all G1 E moves within the set range
839
+ * will be converted to firmware-based retract/recover moves.
840
+ *
841
+ * Be sure to turn off auto-retract during filament change.
842
+ *
843
+ * Note that M207 / M208 / M209 settings are saved to EEPROM.
844
+ *
845
+ */
846
+//#define FWRETRACT  // ONLY PARTIALLY TESTED
760 847
 #if ENABLED(FWRETRACT)
761
-  #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
762
-  #define RETRACT_LENGTH 3               //default retract length (positive mm)
763
-  #define RETRACT_LENGTH_SWAP 13         //default swap retract length (positive mm), for extruder change
764
-  #define RETRACT_FEEDRATE 35            //default feedrate for retracting (mm/s)
765
-  #define RETRACT_ZLIFT 0                //default retract Z-lift
766
-  #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
767
-  #define RETRACT_RECOVER_LENGTH_SWAP 0  //default additional swap recover length (mm, added to retract length when recovering from extruder change)
768
-  #define RETRACT_RECOVER_FEEDRATE 8     //default feedrate for recovering from retraction (mm/s)
848
+  #define MIN_AUTORETRACT 0.1             // When auto-retract is on, convert E moves of this length and over
849
+  #define MAX_AUTORETRACT 10.0            // Upper limit for auto-retract conversion
850
+  #define RETRACT_LENGTH 3                // Default retract length (positive mm)
851
+  #define RETRACT_LENGTH_SWAP 13          // Default swap retract length (positive mm), for extruder change
852
+  #define RETRACT_FEEDRATE 35             // Default feedrate for retracting (mm/s)
853
+  #define RETRACT_ZLIFT 0                 // Default retract Z-lift
854
+  #define RETRACT_RECOVER_LENGTH 0        // Default additional recover length (mm, added to retract length when recovering)
855
+  #define RETRACT_RECOVER_LENGTH_SWAP 0   // Default additional swap recover length (mm, added to retract length when recovering from extruder change)
856
+  #define RETRACT_RECOVER_FEEDRATE 8      // Default feedrate for recovering from retraction (mm/s)
857
+  #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
769 858
 #endif
770 859
 
771 860
 /**
861
+ * Extra Fan Speed
862
+ * Adds a secondary fan speed for each print-cooling fan.
863
+ *   'M106 P<fan> T3-255' : Set a secondary speed for <fan>
864
+ *   'M106 P<fan> T2'     : Use the set secondary speed
865
+ *   'M106 P<fan> T1'     : Restore the previous fan speed
866
+ */
867
+//#define EXTRA_FAN_SPEED
868
+
869
+/**
772 870
  * Advanced Pause
773 871
  * Experimental feature for filament change support and for parking the nozzle when paused.
774 872
  * Adds the GCode M600 for initiating filament change.
@@ -878,7 +976,7 @@
878 976
 
879 977
 #endif
880 978
 
881
-// @section TMC2130
979
+// @section TMC2130, TMC2208
882 980
 
883 981
 /**
884 982
  * Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
@@ -892,7 +990,19 @@
892 990
  */
893 991
 //#define HAVE_TMC2130
894 992
 
895
-#if ENABLED(HAVE_TMC2130)
993
+/**
994
+ * Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
995
+ * Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
996
+ * To use the reading capabilities, also connect #_SERIAL_RX_PIN
997
+ * to #_SERIAL_TX_PIN with a 1K resistor.
998
+ * The drivers can also be used with hardware serial.
999
+ *
1000
+ * You'll also need the TMC2208Stepper Arduino library
1001
+ * (https://github.com/teemuatlut/TMC2208Stepper).
1002
+ */
1003
+//#define HAVE_TMC2208
1004
+
1005
+#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
896 1006
 
897 1007
   // CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
898 1008
   //#define X_IS_TMC2130
@@ -907,46 +1017,58 @@
907 1017
   //#define E3_IS_TMC2130
908 1018
   //#define E4_IS_TMC2130
909 1019
 
1020
+  //#define X_IS_TMC2208
1021
+  //#define X2_IS_TMC2208
1022
+  //#define Y_IS_TMC2208
1023
+  //#define Y2_IS_TMC2208
1024
+  //#define Z_IS_TMC2208
1025
+  //#define Z2_IS_TMC2208
1026
+  //#define E0_IS_TMC2208
1027
+  //#define E1_IS_TMC2208
1028
+  //#define E2_IS_TMC2208
1029
+  //#define E3_IS_TMC2208
1030
+  //#define E4_IS_TMC2208
1031
+
910 1032
   /**
911 1033
    * Stepper driver settings
912 1034
    */
913 1035
 
914 1036
   #define R_SENSE           0.11  // R_sense resistor for SilentStepStick2130
915 1037
   #define HOLD_MULTIPLIER    0.5  // Scales down the holding current from run current
916
-  #define INTERPOLATE          1  // Interpolate X/Y/Z_MICROSTEPS to 256
1038
+  #define INTERPOLATE       true  // Interpolate X/Y/Z_MICROSTEPS to 256
917 1039
 
918
-  #define X_CURRENT         1000  // rms current in mA. Multiply by 1.41 for peak current.
1040
+  #define X_CURRENT          800  // rms current in mA. Multiply by 1.41 for peak current.
919 1041
   #define X_MICROSTEPS        16  // 0..256
920 1042
 
921
-  #define Y_CURRENT         1000
1043
+  #define Y_CURRENT          800
922 1044
   #define Y_MICROSTEPS        16
923 1045
 
924
-  #define Z_CURRENT         1000
1046
+  #define Z_CURRENT          800
925 1047
   #define Z_MICROSTEPS        16
926 1048
 
927
-  //#define X2_CURRENT      1000
928
-  //#define X2_MICROSTEPS     16
1049
+  #define X2_CURRENT         800
1050
+  #define X2_MICROSTEPS       16
929 1051
 
930
-  //#define Y2_CURRENT      1000
931
-  //#define Y2_MICROSTEPS     16
1052
+  #define Y2_CURRENT         800
1053
+  #define Y2_MICROSTEPS       16
932 1054
 
933
-  //#define Z2_CURRENT      1000
934
-  //#define Z2_MICROSTEPS     16
1055
+  #define Z2_CURRENT         800
1056
+  #define Z2_MICROSTEPS       16
935 1057
 
936
-  //#define E0_CURRENT      1000
937
-  //#define E0_MICROSTEPS     16
1058
+  #define E0_CURRENT         800
1059
+  #define E0_MICROSTEPS       16
938 1060
 
939
-  //#define E1_CURRENT      1000
940
-  //#define E1_MICROSTEPS     16
1061
+  #define E1_CURRENT         800
1062
+  #define E1_MICROSTEPS       16
941 1063
 
942
-  //#define E2_CURRENT      1000
943
-  //#define E2_MICROSTEPS     16
1064
+  #define E2_CURRENT         800
1065
+  #define E2_MICROSTEPS       16
944 1066
 
945
-  //#define E3_CURRENT      1000
946
-  //#define E3_MICROSTEPS     16
1067
+  #define E3_CURRENT         800
1068
+  #define E3_MICROSTEPS       16
947 1069
 
948
-  //#define E4_CURRENT      1000
949
-  //#define E4_MICROSTEPS     16
1070
+  #define E4_CURRENT         800
1071
+  #define E4_MICROSTEPS       16
950 1072
 
951 1073
   /**
952 1074
    * Use Trinamic's ultra quiet stepping mode.
@@ -955,24 +1077,22 @@
955 1077
   #define STEALTHCHOP
956 1078
 
957 1079
   /**
958
-   * Let Marlin automatically control stepper current.
959
-   * This is still an experimental feature.
960
-   * Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
961
-   * then decrease current by CURRENT_STEP until temperature prewarn is cleared.
962
-   * Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
1080
+   * Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
1081
+   * like overtemperature and short to ground. TMC2208 requires hardware serial.
1082
+   * In the case of overtemperature Marlin can decrease the driver current until error condition clears.
1083
+   * Other detected conditions can be used to stop the current print.
963 1084
    * Relevant g-codes:
964 1085
    * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
965
-   * M906 S1 - Start adjusting current
966
-   * M906 S0 - Stop adjusting current
967 1086
    * M911 - Report stepper driver overtemperature pre-warn condition.
968 1087
    * M912 - Clear stepper driver overtemperature pre-warn condition flag.
1088
+   * M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
969 1089
    */
970
-  //#define AUTOMATIC_CURRENT_CONTROL
1090
+  //#define MONITOR_DRIVER_STATUS
971 1091
 
972
-  #if ENABLED(AUTOMATIC_CURRENT_CONTROL)
973
-    #define CURRENT_STEP          50  // [mA]
974
-    #define AUTO_ADJUST_MAX     1300  // [mA], 1300mA_rms = 1840mA_peak
1092
+  #if ENABLED(MONITOR_DRIVER_STATUS)
1093
+    #define CURRENT_STEP_DOWN     50  // [mA]
975 1094
     #define REPORT_CURRENT_CHANGE
1095
+    #define STOP_ON_ERROR
976 1096
   #endif
977 1097
 
978 1098
   /**
@@ -987,8 +1107,8 @@
987 1107
   #define X2_HYBRID_THRESHOLD    100
988 1108
   #define Y_HYBRID_THRESHOLD     100
989 1109
   #define Y2_HYBRID_THRESHOLD    100
990
-  #define Z_HYBRID_THRESHOLD       4
991
-  #define Z2_HYBRID_THRESHOLD      4
1110
+  #define Z_HYBRID_THRESHOLD       3
1111
+  #define Z2_HYBRID_THRESHOLD      3
992 1112
   #define E0_HYBRID_THRESHOLD     30
993 1113
   #define E1_HYBRID_THRESHOLD     30
994 1114
   #define E2_HYBRID_THRESHOLD     30
@@ -998,7 +1118,7 @@
998 1118
   /**
999 1119
    * Use stallGuard2 to sense an obstacle and trigger an endstop.
1000 1120
    * You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
1001
-   * If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
1121
+   * X and Y homing will always be done in spreadCycle mode.
1002 1122
    *
1003 1123
    * X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
1004 1124
    * Higher values make the system LESS sensitive.
@@ -1007,27 +1127,34 @@
1007 1127
    * It is advised to set X/Y_HOME_BUMP_MM to 0.
1008 1128
    * M914 X/Y to live tune the setting
1009 1129
    */
1010
-  //#define SENSORLESS_HOMING
1130
+  //#define SENSORLESS_HOMING // TMC2130 only
1011 1131
 
1012 1132
   #if ENABLED(SENSORLESS_HOMING)
1013
-    #define X_HOMING_SENSITIVITY  19
1014
-    #define Y_HOMING_SENSITIVITY  19
1133
+    #define X_HOMING_SENSITIVITY  8
1134
+    #define Y_HOMING_SENSITIVITY  8
1015 1135
   #endif
1016 1136
 
1017 1137
   /**
1138
+   * Enable M122 debugging command for TMC stepper drivers.
1139
+   * M122 S0/1 will enable continous reporting.
1140
+   */
1141
+  //#define TMC_DEBUG
1142
+
1143
+  /**
1018 1144
    * You can set your own advanced settings by filling in predefined functions.
1019 1145
    * A list of available functions can be found on the library github page
1020 1146
    * https://github.com/teemuatlut/TMC2130Stepper
1147
+   * https://github.com/teemuatlut/TMC2208Stepper
1021 1148
    *
1022 1149
    * Example:
1023
-   * #define TMC2130_ADV() { \
1150
+   * #define TMC_ADV() { \
1024 1151
    *   stepperX.diag0_temp_prewarn(1); \
1025
-   *   stepperX.interpolate(0); \
1152
+   *   stepperY.interpolate(0); \
1026 1153
    * }
1027 1154
    */
1028
-  #define  TMC2130_ADV() {  }
1155
+  #define  TMC_ADV() {  }
1029 1156
 
1030
-#endif // HAVE_TMC2130
1157
+#endif // TMC2130 || TMC2208
1031 1158
 
1032 1159
 // @section L6470
1033 1160
 
@@ -1192,6 +1319,48 @@
1192 1319
 #endif
1193 1320
 
1194 1321
 /**
1322
+ * Filament Width Sensor
1323
+ *
1324
+ * Measures the filament width in real-time and adjusts
1325
+ * flow rate to compensate for any irregularities.
1326
+ *
1327
+ * Also allows the measured filament diameter to set the
1328
+ * extrusion rate, so the slicer only has to specify the
1329
+ * volume.
1330
+ *
1331
+ * Only a single extruder is supported at this time.
1332
+ *
1333
+ *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1334
+ *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1335
+ * 301 RAMBO       : Analog input 3
1336
+ *
1337
+ * Note: May require analog pins to be defined for other boards.
1338
+ */
1339
+//#define FILAMENT_WIDTH_SENSOR
1340
+
1341
+#if ENABLED(FILAMENT_WIDTH_SENSOR)
1342
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
1343
+  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1344
+
1345
+  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1346
+  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1347
+  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1348
+
1349
+  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1350
+
1351
+  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1352
+  //#define FILAMENT_LCD_DISPLAY
1353
+#endif
1354
+
1355
+/**
1356
+ * CNC Coordinate Systems
1357
+ *
1358
+ * Enables G53 and G54-G59.3 commands to select coordinate systems
1359
+ * and G92.1 to reset the workspace to native machine space.
1360
+ */
1361
+//#define CNC_COORDINATE_SYSTEMS
1362
+
1363
+/**
1195 1364
  * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
1196 1365
  */
1197 1366
 //#define PINS_DEBUGGING
@@ -1244,6 +1413,8 @@
1244 1413
 //#define CUSTOM_USER_MENUS
1245 1414
 #if ENABLED(CUSTOM_USER_MENUS)
1246 1415
   #define USER_SCRIPT_DONE "M117 User Script Done"
1416
+  #define USER_SCRIPT_AUDIBLE_FEEDBACK
1417
+  //#define USER_SCRIPT_RETURN  // Return to status screen after a script
1247 1418
 
1248 1419
   #define USER_DESC_1 "Home & UBL Info"
1249 1420
   #define USER_GCODE_1 "G28\nG29 W"
@@ -1271,6 +1442,7 @@
1271 1442
 //===========================================================================
1272 1443
 //====================== I2C Position Encoder Settings ======================
1273 1444
 //===========================================================================
1445
+
1274 1446
 /**
1275 1447
  *  I2C position encoders for closed loop control.
1276 1448
  *  Developed by Chris Barr at Aus3D.
@@ -1351,4 +1523,45 @@
1351 1523
 
1352 1524
 #endif // I2C_POSITION_ENCODERS
1353 1525
 
1526
+/**
1527
+ * MAX7219 Debug Matrix
1528
+ *
1529
+ * Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
1530
+ * display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
1531
+ *
1532
+ * Fully assembled MAX7219 boards can be found on the internet for under $2(US).
1533
+ * For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
1534
+ */
1535
+//#define MAX7219_DEBUG
1536
+#if ENABLED(MAX7219_DEBUG)
1537
+  #define MAX7219_CLK_PIN   64  // 77 on Re-ARM       // Configuration of the 3 pins to control the display
1538
+  #define MAX7219_DIN_PIN   57  // 78 on Re-ARM
1539
+  #define MAX7219_LOAD_PIN  44  // 79 on Re-ARM
1540
+
1541
+  /**
1542
+   * Sample debug features
1543
+   * If you add more debug displays, be careful to avoid conflicts!
1544
+   */
1545
+  #define MAX7219_DEBUG_PRINTER_ALIVE    // Blink corner LED of 8x8 matrix to show that the firmware is functioning
1546
+  #define MAX7219_DEBUG_STEPPER_HEAD  3  // Show the stepper queue head position on this and the next LED matrix row
1547
+  #define MAX7219_DEBUG_STEPPER_TAIL  5  // Show the stepper queue tail position on this and the next LED matrix row
1548
+
1549
+  #define MAX7219_DEBUG_STEPPER_QUEUE 0  // Show the current stepper queue depth on this and the next LED matrix row
1550
+                                         // If you experience stuttering, reboots, etc. this option can reveal how
1551
+                                         // tweaks made to the configuration are affecting the printer in real-time.
1552
+#endif
1553
+
1554
+/**
1555
+ * NanoDLP Sync support
1556
+ *
1557
+ * Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
1558
+ * string to enable synchronization with DLP projector exposure. This change will allow to use
1559
+ * [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
1560
+ */
1561
+//#define NANODLP_Z_SYNC
1562
+#if ENABLED(NANODLP_Z_SYNC)
1563
+  //#define NANODLP_ALL_AXIS  // Enables "Z_move_comp" output on any axis move.
1564
+                              // Default behaviour is limited to Z axis only.
1565
+#endif
1566
+
1354 1567
 #endif // CONFIGURATION_ADV_H

+ 1800
- 0
Marlin/example_configurations/Sanguinololu/Configuration.h
파일 크기가 너무 크기때문에 변경 상태를 표시하지 않습니다.
파일 보기


Marlin/example_configurations/M150/Configuration_adv.h → Marlin/example_configurations/Sanguinololu/Configuration_adv.h 파일 보기

@@ -32,7 +32,7 @@
32 32
  */
33 33
 #ifndef CONFIGURATION_ADV_H
34 34
 #define CONFIGURATION_ADV_H
35
-#define CONFIGURATION_ADV_H_VERSION 010100
35
+#define CONFIGURATION_ADV_H_VERSION 010107
36 36
 
37 37
 // @section temperature
38 38
 
@@ -48,31 +48,36 @@
48 48
 #endif
49 49
 
50 50
 /**
51
- * Thermal Protection protects your printer from damage and fire if a
52
- * thermistor falls out or temperature sensors fail in any way.
51
+ * Thermal Protection provides additional protection to your printer from damage
52
+ * and fire. Marlin always includes safe min and max temperature ranges which
53
+ * protect against a broken or disconnected thermistor wire.
53 54
  *
54
- * The issue: If a thermistor falls out or a temperature sensor fails,
55
- * Marlin can no longer sense the actual temperature. Since a disconnected
56
- * thermistor reads as a low temperature, the firmware will keep the heater on.
55
+ * The issue: If a thermistor falls out, it will report the much lower
56
+ * temperature of the air in the room, and the the firmware will keep
57
+ * the heater on.
57 58
  *
58 59
  * The solution: Once the temperature reaches the target, start observing.
59
- * If the temperature stays too far below the target (hysteresis) for too long (period),
60
- * the firmware will halt the machine as a safety precaution.
60
+ * If the temperature stays too far below the target (hysteresis) for too
61
+ * long (period), the firmware will halt the machine as a safety precaution.
61 62
  *
62
- * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63
+ * If you get false positives for "Thermal Runaway", increase
64
+ * THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63 65
  */
64 66
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
65 67
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
66 68
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
67 69
 
68 70
   /**
69
-   * Whenever an M104 or M109 increases the target temperature the firmware will wait for the
70
-   * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
71
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
72
-   * but only if the current temperature is far enough below the target for a reliable test.
71
+   * Whenever an M104, M109, or M303 increases the target temperature, the
72
+   * firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
73
+   * hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
74
+   * requires a hard reset. This test restarts with any M104/M109/M303, but only
75
+   * if the current temperature is far enough below the target for a reliable
76
+   * test.
73 77
    *
74
-   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
75
-   * WATCH_TEMP_INCREASE should not be below 2.
78
+   * If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
79
+   * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
80
+   * below 2.
76 81
    */
77 82
   #define WATCH_TEMP_PERIOD 20                // Seconds
78 83
   #define WATCH_TEMP_INCREASE 2               // Degrees Celsius
@@ -82,17 +87,11 @@
82 87
  * Thermal Protection parameters for the bed are just as above for hotends.
83 88
  */
84 89
 #if ENABLED(THERMAL_PROTECTION_BED)
85
-  #define THERMAL_PROTECTION_BED_PERIOD 120    // Seconds
90
+  #define THERMAL_PROTECTION_BED_PERIOD 20    // Seconds
86 91
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
87 92
 
88 93
   /**
89
-   * Whenever an M140 or M190 increases the target temperature the firmware will wait for the
90
-   * WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
91
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
92
-   * but only if the current temperature is far enough below the target for a reliable test.
93
-   *
94
-   * If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
95
-   * WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
94
+   * As described above, except for the bed (M140/M190/M303).
96 95
    */
97 96
   #define WATCH_BED_TEMP_PERIOD 60                // Seconds
98 97
   #define WATCH_BED_TEMP_INCREASE 2               // Degrees Celsius
@@ -118,11 +117,14 @@
118 117
  * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
119 118
  * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
120 119
  */
121
-//#define AUTOTEMP
120
+#define AUTOTEMP
122 121
 #if ENABLED(AUTOTEMP)
123 122
   #define AUTOTEMP_OLDWEIGHT 0.98
124 123
 #endif
125 124
 
125
+// Show extra position information in M114
126
+//#define M114_DETAIL
127
+
126 128
 // Show Temperature ADC value
127 129
 // Enable for M105 to include ADC values read from temperature sensors.
128 130
 //#define SHOW_TEMP_ADC_VALUES
@@ -246,48 +248,49 @@
246 248
 
247 249
 //#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
248 250
 
249
-// Dual X Steppers
250
-// Uncomment this option to drive two X axis motors.
251
-// The next unused E driver will be assigned to the second X stepper.
251
+/**
252
+ * Dual Steppers / Dual Endstops
253
+ *
254
+ * This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
255
+ *
256
+ * For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
257
+ * spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
258
+ * set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
259
+ * that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
260
+ *
261
+ * Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
262
+ * this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
263
+ * in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
264
+ */
265
+
252 266
 //#define X_DUAL_STEPPER_DRIVERS
253 267
 #if ENABLED(X_DUAL_STEPPER_DRIVERS)
254
-  // Set true if the two X motors need to rotate in opposite directions
255
-  #define INVERT_X2_VS_X_DIR true
268
+  #define INVERT_X2_VS_X_DIR true   // Set 'true' if X motors should rotate in opposite directions
269
+  //#define X_DUAL_ENDSTOPS
270
+  #if ENABLED(X_DUAL_ENDSTOPS)
271
+    #define X2_USE_ENDSTOP _XMAX_
272
+    #define X_DUAL_ENDSTOPS_ADJUSTMENT  0
273
+  #endif
256 274
 #endif
257 275
 
258
-// Dual Y Steppers
259
-// Uncomment this option to drive two Y axis motors.
260
-// The next unused E driver will be assigned to the second Y stepper.
261 276
 //#define Y_DUAL_STEPPER_DRIVERS
262 277
 #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
263
-  // Set true if the two Y motors need to rotate in opposite directions
264
-  #define INVERT_Y2_VS_Y_DIR true
278
+  #define INVERT_Y2_VS_Y_DIR true   // Set 'true' if Y motors should rotate in opposite directions
279
+  //#define Y_DUAL_ENDSTOPS
280
+  #if ENABLED(Y_DUAL_ENDSTOPS)
281
+    #define Y2_USE_ENDSTOP _YMAX_
282
+    #define Y_DUAL_ENDSTOPS_ADJUSTMENT  0
283
+  #endif
265 284
 #endif
266 285
 
267
-// A single Z stepper driver is usually used to drive 2 stepper motors.
268
-// Uncomment this option to use a separate stepper driver for each Z axis motor.
269
-// The next unused E driver will be assigned to the second Z stepper.
270 286
 //#define Z_DUAL_STEPPER_DRIVERS
271
-
272 287
 #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
273
-
274
-  // Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper.
275
-  // That way the machine is capable to align the bed during home, since both Z steppers are homed.
276
-  // There is also an implementation of M666 (software endstops adjustment) to this feature.
277
-  // After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
278
-  // One just need to home the Z axis and measure the distance difference between both Z axis and apply the math: Z adjust = Z - Z2.
279
-  // If the Z stepper axis is closer to the bed, the measure Z > Z2 (yes, it is.. think about it) and the Z adjust would be positive.
280
-  // Play a little bit with small adjustments (0.5mm) and check the behaviour.
281
-  // The M119 (endstops report) will start reporting the Z2 Endstop as well.
282
-
283 288
   //#define Z_DUAL_ENDSTOPS
284
-
285 289
   #if ENABLED(Z_DUAL_ENDSTOPS)
286 290
     #define Z2_USE_ENDSTOP _XMAX_
287
-    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0  // use M666 command to determine/test this value
291
+    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0
288 292
   #endif
289
-
290
-#endif // Z_DUAL_STEPPER_DRIVERS
293
+#endif
291 294
 
292 295
 // Enable this for dual x-carriage printers.
293 296
 // A dual x-carriage design has the advantage that the inactive extruder can be parked which
@@ -334,12 +337,12 @@
334 337
 
335 338
 // @section homing
336 339
 
337
-//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
340
+// Homing hits each endstop, retracts by these distances, then does a slower bump.
338 341
 #define X_HOME_BUMP_MM 5
339 342
 #define Y_HOME_BUMP_MM 5
340 343
 #define Z_HOME_BUMP_MM 2
341
-#define HOMING_BUMP_DIVISOR {2, 2, 4}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
342
-//#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
344
+#define HOMING_BUMP_DIVISOR { 2, 2, 4 }  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
345
+#define QUICK_HOME                       // If homing includes X and Y, do a diagonal move initially
343 346
 
344 347
 // When G28 is called, this option will make Y home before X
345 348
 //#define HOME_Y_BEFORE_X
@@ -394,7 +397,7 @@
394 397
 // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
395 398
 // of the buffer and all stops. This should not be much greater than zero and should only be changed
396 399
 // if unwanted behavior is observed on a user's machine when running at very slow speeds.
397
-#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
400
+#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
398 401
 
399 402
 // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
400 403
 #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
@@ -423,8 +426,21 @@
423 426
 //#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 }   // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
424 427
 //#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 }    // Default drive percent - X, Y, Z, E axis
425 428
 
426
-// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
429
+// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
427 430
 //#define DIGIPOT_I2C
431
+#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
432
+  /**
433
+   * Common slave addresses:
434
+   *
435
+   *                    A   (A shifted)   B   (B shifted)  IC
436
+   * Smoothie          0x2C (0x58)       0x2D (0x5A)       MCP4451
437
+   * AZTEEG_X3_PRO     0x2C (0x58)       0x2E (0x5C)       MCP4451
438
+   * MIGHTYBOARD_REVE  0x2F (0x5E)                         MCP4018
439
+   */
440
+  #define DIGIPOT_I2C_ADDRESS_A 0x2C  // unshifted slave address for first DIGIPOT
441
+  #define DIGIPOT_I2C_ADDRESS_B 0x2D  // unshifted slave address for second DIGIPOT
442
+#endif
443
+
428 444
 //#define DIGIPOT_MCP4018          // Requires library from https://github.com/stawel/SlowSoftI2CMaster
429 445
 #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4     AZTEEG_X3_PRO: 8
430 446
 // Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
@@ -436,7 +452,7 @@
436 452
 
437 453
 #define ENCODER_RATE_MULTIPLIER         // If defined, certain menu edit operations automatically multiply the steps when the encoder is moved quickly
438 454
 #define ENCODER_10X_STEPS_PER_SEC 75    // If the encoder steps per sec exceeds this value, multiply steps moved x10 to quickly advance the value
439
-#define ENCODER_100X_STEPS_PER_SEC 300  // If the encoder steps per sec exceeds this value, multiply steps moved x100 to really quickly advance the value
455
+#define ENCODER_100X_STEPS_PER_SEC 160  // If the encoder steps per sec exceeds this value, multiply steps moved x100 to really quickly advance the value
440 456
 
441 457
 //#define CHDK 4        //Pin for triggering CHDK to take a picture see how to use it here http://captain-slow.dk/2014/03/09/3d-printing-timelapses/
442 458
 #define CHDK_DELAY 50 //How long in ms the pin should stay HIGH before going LOW again
@@ -455,6 +471,23 @@
455 471
 // The timeout (in ms) to return to the status screen from sub-menus
456 472
 //#define LCD_TIMEOUT_TO_STATUS 15000
457 473
 
474
+/**
475
+ * LED Control Menu
476
+ * Enable this feature to add LED Control to the LCD menu
477
+ */
478
+//#define LED_CONTROL_MENU
479
+#if ENABLED(LED_CONTROL_MENU)
480
+  #define LED_COLOR_PRESETS                 // Enable the Preset Color menu option
481
+  #if ENABLED(LED_COLOR_PRESETS)
482
+    #define LED_USER_PRESET_RED        255  // User defined RED value
483
+    #define LED_USER_PRESET_GREEN      128  // User defined GREEN value
484
+    #define LED_USER_PRESET_BLUE         0  // User defined BLUE value
485
+    #define LED_USER_PRESET_WHITE      255  // User defined WHITE value
486
+    #define LED_USER_PRESET_BRIGHTNESS 255  // User defined intensity
487
+    //#define LED_USER_PRESET_STARTUP       // Have the printer display the user preset color on startup
488
+  #endif
489
+#endif // LED_CONTROL_MENU
490
+
458 491
 #if ENABLED(SDSUPPORT)
459 492
 
460 493
   // Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -464,12 +497,14 @@
464 497
   // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
465 498
   #define SD_DETECT_INVERTED
466 499
 
467
-  #define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
500
+  #define SD_FINISHED_STEPPERRELEASE true          // Disable steppers when SD Print is finished
468 501
   #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
469 502
 
470
-  #define SDCARD_RATHERRECENTFIRST  //reverse file order of sd card menu display. Its sorted practically after the file system block order.
471
-  // if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that.
472
-  // using:
503
+  // Reverse SD sort to show "more recent" files first, according to the card's FAT.
504
+  // Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
505
+  #define SDCARD_RATHERRECENTFIRST
506
+
507
+  // Add an option in the menu to run all auto#.g files
473 508
   //#define MENU_ADDAUTOSTART
474 509
 
475 510
   /**
@@ -499,13 +534,15 @@
499 534
 
500 535
   // SD Card Sorting options
501 536
   #if ENABLED(SDCARD_SORT_ALPHA)
502
-    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256).
537
+    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256). Costs 27 bytes each.
503 538
     #define FOLDER_SORTING     -1     // -1=above  0=none  1=below
504 539
     #define SDSORT_GCODE       false  // Allow turning sorting on/off with LCD and M34 g-code.
505 540
     #define SDSORT_USES_RAM    false  // Pre-allocate a static array for faster pre-sorting.
506 541
     #define SDSORT_USES_STACK  false  // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
507 542
     #define SDSORT_CACHE_NAMES false  // Keep sorted items in RAM longer for speedy performance. Most expensive option.
508 543
     #define SDSORT_DYNAMIC_RAM false  // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
544
+    #define SDSORT_CACHE_VFATS 2      // Maximum number of 13-byte VFAT entries to use for sorting.
545
+                                      // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
509 546
   #endif
510 547
 
511 548
   // Show a progress bar on HD44780 LCDs for SD printing
@@ -524,14 +561,29 @@
524 561
     //#define LCD_PROGRESS_BAR_TEST
525 562
   #endif
526 563
 
564
+  // Add an 'M73' G-code to set the current percentage
565
+  //#define LCD_SET_PROGRESS_MANUALLY
566
+
527 567
   // This allows hosts to request long names for files and folders with M33
528
-  #define LONG_FILENAME_HOST_SUPPORT
568
+  //#define LONG_FILENAME_HOST_SUPPORT
569
+
570
+  // Enable this option to scroll long filenames in the SD card menu
571
+  //#define SCROLL_LONG_FILENAMES
529 572
 
530
-  // This option allows you to abort SD printing when any endstop is triggered.
531
-  // This feature must be enabled with "M540 S1" or from the LCD menu.
532
-  // To have any effect, endstops must be enabled during SD printing.
573
+  /**
574
+   * This option allows you to abort SD printing when any endstop is triggered.
575
+   * This feature must be enabled with "M540 S1" or from the LCD menu.
576
+   * To have any effect, endstops must be enabled during SD printing.
577
+   */
533 578
   //#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
534 579
 
580
+  /**
581
+   * This option makes it easier to print the same SD Card file again.
582
+   * On print completion the LCD Menu will open with the file selected.
583
+   * You can just click to start the print, or navigate elsewhere.
584
+   */
585
+  //#define SD_REPRINT_LAST_SELECTED_FILE
586
+
535 587
 #endif // SDSUPPORT
536 588
 
537 589
 /**
@@ -564,6 +616,10 @@
564 616
   // Enable this option and reduce the value to optimize screen updates.
565 617
   // The normal delay is 10µs. Use the lowest value that still gives a reliable display.
566 618
   //#define DOGM_SPI_DELAY_US 5
619
+
620
+  // Swap the CW/CCW indicators in the graphics overlay
621
+  //#define OVERLAY_GFX_REVERSE
622
+
567 623
 #endif // DOGLCD
568 624
 
569 625
 // @section safety
@@ -590,31 +646,18 @@
590 646
  */
591 647
 //#define BABYSTEPPING
592 648
 #if ENABLED(BABYSTEPPING)
593
-  #define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
594
-  #define BABYSTEP_INVERT_Z false  // Change if Z babysteps should go the other way
595
-  #define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
596
-  //#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
649
+  //#define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
650
+  #define BABYSTEP_INVERT_Z false    // Change if Z babysteps should go the other way
651
+  #define BABYSTEP_MULTIPLICATOR 1   // Babysteps are very small. Increase for faster motion.
652
+  //#define BABYSTEP_ZPROBE_OFFSET   // Enable to combine M851 and Babystepping
597 653
   //#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
598 654
   #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
599 655
                                         // Note: Extra time may be added to mitigate controller latency.
656
+  //#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
600 657
 #endif
601 658
 
602 659
 // @section extruder
603 660
 
604
-// extruder advance constant (s2/mm3)
605
-//
606
-// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
607
-//
608
-// Hooke's law says:    force = k * distance
609
-// Bernoulli's principle says:  v ^ 2 / 2 + g . h + pressure / density = constant
610
-// so: v ^ 2 is proportional to number of steps we advance the extruder
611
-//#define ADVANCE
612
-
613
-#if ENABLED(ADVANCE)
614
-  #define EXTRUDER_ADVANCE_K .0
615
-  #define D_FILAMENT 2.85
616
-#endif
617
-
618 661
 /**
619 662
  * Implementation of linear pressure control
620 663
  *
@@ -648,7 +691,7 @@
648 691
    *
649 692
    * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
650 693
    *
651
-   * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode.
694
+   * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
652 695
    * Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
653 696
    */
654 697
   #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
@@ -657,23 +700,18 @@
657 700
 
658 701
 // @section leveling
659 702
 
660
-// Default mesh area is an area with an inset margin on the print area.
661
-// Below are the macros that are used to define the borders for the mesh area,
662
-// made available here for specialized needs, ie dual extruder setup.
663
-#if ENABLED(MESH_BED_LEVELING)
664
-  #define MESH_MIN_X (X_MIN_POS + MESH_INSET)
665
-  #define MESH_MAX_X (X_MAX_POS - (MESH_INSET))
666
-  #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET)
667
-  #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET))
668
-#elif ENABLED(AUTO_BED_LEVELING_UBL)
669
-  #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET)
670
-  #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET))
671
-  #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET)
672
-  #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET))
673
-
674
-  // If this is defined, the currently active mesh will be saved in the
675
-  // current slot on M500.
676
-  #define UBL_SAVE_ACTIVE_ON_M500
703
+#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
704
+  #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
705
+#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
706
+  #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
707
+#endif
708
+
709
+#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
710
+  // Override the mesh area if the automatic (max) area is too large
711
+  //#define MESH_MIN_X MESH_INSET
712
+  //#define MESH_MIN_Y MESH_INSET
713
+  //#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
714
+  //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
677 715
 #endif
678 716
 
679 717
 // @section extras
@@ -693,7 +731,7 @@
693 731
 //#define BEZIER_CURVE_SUPPORT
694 732
 
695 733
 // G38.2 and G38.3 Probe Target
696
-// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
734
+// Set MULTIPLE_PROBING if you want G38 to double touch
697 735
 //#define G38_PROBE_TARGET
698 736
 #if ENABLED(G38_PROBE_TARGET)
699 737
   #define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
@@ -718,7 +756,7 @@
718 756
 // @section hidden
719 757
 
720 758
 // The number of linear motions that can be in the plan at any give time.
721
-// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
759
+// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
722 760
 #if ENABLED(SDSUPPORT)
723 761
   #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
724 762
 #else
@@ -731,7 +769,7 @@
731 769
 #define MAX_CMD_SIZE 96
732 770
 #define BUFSIZE 4
733 771
 
734
-// Transfer Buffer Size
772
+// Transmission to Host Buffer Size
735 773
 // To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0.
736 774
 // To buffer a simple "ok" you need 4 bytes.
737 775
 // For ADVANCED_OK (M105) you need 32 bytes.
@@ -744,7 +782,7 @@
744 782
 // enter the serial receive buffer, so they cannot be blocked.
745 783
 // Currently handles M108, M112, M410
746 784
 // Does not work on boards using AT90USB (USBCON) processors!
747
-//#define EMERGENCY_PARSER
785
+#define EMERGENCY_PARSER
748 786
 
749 787
 // Bad Serial-connections can miss a received command by sending an 'ok'
750 788
 // Therefore some clients abort after 30 seconds in a timeout.
@@ -755,27 +793,47 @@
755 793
 // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary.
756 794
 //#define ADVANCED_OK
757 795
 
758
-// @section fwretract
759
-
760
-// Firmware based and LCD controlled retract
761
-// M207 and M208 can be used to define parameters for the retraction.
762
-// The retraction can be called by the slicer using G10 and G11
763
-// until then, intended retractions can be detected by moves that only extrude and the direction.
764
-// the moves are than replaced by the firmware controlled ones.
796
+// @section extras
765 797
 
766
-//#define FWRETRACT  //ONLY PARTIALLY TESTED
798
+/**
799
+ * Firmware-based and LCD-controlled retract
800
+ *
801
+ * Add G10 / G11 commands for automatic firmware-based retract / recover.
802
+ * Use M207 and M208 to define parameters for retract / recover.
803
+ *
804
+ * Use M209 to enable or disable auto-retract.
805
+ * With auto-retract enabled, all G1 E moves within the set range
806
+ * will be converted to firmware-based retract/recover moves.
807
+ *
808
+ * Be sure to turn off auto-retract during filament change.
809
+ *
810
+ * Note that M207 / M208 / M209 settings are saved to EEPROM.
811
+ *
812
+ */
813
+//#define FWRETRACT  // ONLY PARTIALLY TESTED
767 814
 #if ENABLED(FWRETRACT)
768
-  #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
769
-  #define RETRACT_LENGTH 3               //default retract length (positive mm)
770
-  #define RETRACT_LENGTH_SWAP 13         //default swap retract length (positive mm), for extruder change
771
-  #define RETRACT_FEEDRATE 45            //default feedrate for retracting (mm/s)
772
-  #define RETRACT_ZLIFT 0                //default retract Z-lift
773
-  #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
774
-  #define RETRACT_RECOVER_LENGTH_SWAP 0  //default additional swap recover length (mm, added to retract length when recovering from extruder change)
775
-  #define RETRACT_RECOVER_FEEDRATE 8     //default feedrate for recovering from retraction (mm/s)
815
+  #define MIN_AUTORETRACT 0.1             // When auto-retract is on, convert E moves of this length and over
816
+  #define MAX_AUTORETRACT 10.0            // Upper limit for auto-retract conversion
817
+  #define RETRACT_LENGTH 3                // Default retract length (positive mm)
818
+  #define RETRACT_LENGTH_SWAP 13          // Default swap retract length (positive mm), for extruder change
819
+  #define RETRACT_FEEDRATE 45             // Default feedrate for retracting (mm/s)
820
+  #define RETRACT_ZLIFT 0                 // Default retract Z-lift
821
+  #define RETRACT_RECOVER_LENGTH 0        // Default additional recover length (mm, added to retract length when recovering)
822
+  #define RETRACT_RECOVER_LENGTH_SWAP 0   // Default additional swap recover length (mm, added to retract length when recovering from extruder change)
823
+  #define RETRACT_RECOVER_FEEDRATE 8      // Default feedrate for recovering from retraction (mm/s)
824
+  #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
776 825
 #endif
777 826
 
778 827
 /**
828
+ * Extra Fan Speed
829
+ * Adds a secondary fan speed for each print-cooling fan.
830
+ *   'M106 P<fan> T3-255' : Set a secondary speed for <fan>
831
+ *   'M106 P<fan> T2'     : Use the set secondary speed
832
+ *   'M106 P<fan> T1'     : Restore the previous fan speed
833
+ */
834
+//#define EXTRA_FAN_SPEED
835
+
836
+/**
779 837
  * Advanced Pause
780 838
  * Experimental feature for filament change support and for parking the nozzle when paused.
781 839
  * Adds the GCode M600 for initiating filament change.
@@ -885,7 +943,7 @@
885 943
 
886 944
 #endif
887 945
 
888
-// @section TMC2130
946
+// @section TMC2130, TMC2208
889 947
 
890 948
 /**
891 949
  * Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
@@ -899,7 +957,19 @@
899 957
  */
900 958
 //#define HAVE_TMC2130
901 959
 
902
-#if ENABLED(HAVE_TMC2130)
960
+/**
961
+ * Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
962
+ * Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
963
+ * To use the reading capabilities, also connect #_SERIAL_RX_PIN
964
+ * to #_SERIAL_TX_PIN with a 1K resistor.
965
+ * The drivers can also be used with hardware serial.
966
+ *
967
+ * You'll also need the TMC2208Stepper Arduino library
968
+ * (https://github.com/teemuatlut/TMC2208Stepper).
969
+ */
970
+//#define HAVE_TMC2208
971
+
972
+#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
903 973
 
904 974
   // CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
905 975
   //#define X_IS_TMC2130
@@ -914,46 +984,58 @@
914 984
   //#define E3_IS_TMC2130
915 985
   //#define E4_IS_TMC2130
916 986
 
987
+  //#define X_IS_TMC2208
988
+  //#define X2_IS_TMC2208
989
+  //#define Y_IS_TMC2208
990
+  //#define Y2_IS_TMC2208
991
+  //#define Z_IS_TMC2208
992
+  //#define Z2_IS_TMC2208
993
+  //#define E0_IS_TMC2208
994
+  //#define E1_IS_TMC2208
995
+  //#define E2_IS_TMC2208
996
+  //#define E3_IS_TMC2208
997
+  //#define E4_IS_TMC2208
998
+
917 999
   /**
918 1000
    * Stepper driver settings
919 1001
    */
920 1002
 
921 1003
   #define R_SENSE           0.11  // R_sense resistor for SilentStepStick2130
922 1004
   #define HOLD_MULTIPLIER    0.5  // Scales down the holding current from run current
923
-  #define INTERPOLATE          1  // Interpolate X/Y/Z_MICROSTEPS to 256
1005
+  #define INTERPOLATE       true  // Interpolate X/Y/Z_MICROSTEPS to 256
924 1006
 
925
-  #define X_CURRENT         1000  // rms current in mA. Multiply by 1.41 for peak current.
1007
+  #define X_CURRENT          800  // rms current in mA. Multiply by 1.41 for peak current.
926 1008
   #define X_MICROSTEPS        16  // 0..256
927 1009
 
928
-  #define Y_CURRENT         1000
1010
+  #define Y_CURRENT          800
929 1011
   #define Y_MICROSTEPS        16
930 1012
 
931
-  #define Z_CURRENT         1000
1013
+  #define Z_CURRENT          800
932 1014
   #define Z_MICROSTEPS        16
933 1015
 
934
-  //#define X2_CURRENT      1000
935
-  //#define X2_MICROSTEPS     16
1016
+  #define X2_CURRENT         800
1017
+  #define X2_MICROSTEPS       16
936 1018
 
937
-  //#define Y2_CURRENT      1000
938
-  //#define Y2_MICROSTEPS     16
1019
+  #define Y2_CURRENT         800
1020
+  #define Y2_MICROSTEPS       16
939 1021
 
940
-  //#define Z2_CURRENT      1000
941
-  //#define Z2_MICROSTEPS     16
1022
+  #define Z2_CURRENT         800
1023
+  #define Z2_MICROSTEPS       16
942 1024
 
943
-  //#define E0_CURRENT      1000
944
-  //#define E0_MICROSTEPS     16
1025
+  #define E0_CURRENT         800
1026
+  #define E0_MICROSTEPS       16
945 1027
 
946
-  //#define E1_CURRENT      1000
947
-  //#define E1_MICROSTEPS     16
1028
+  #define E1_CURRENT         800
1029
+  #define E1_MICROSTEPS       16
948 1030
 
949
-  //#define E2_CURRENT      1000
950
-  //#define E2_MICROSTEPS     16
1031
+  #define E2_CURRENT         800
1032
+  #define E2_MICROSTEPS       16
951 1033
 
952
-  //#define E3_CURRENT      1000
953
-  //#define E3_MICROSTEPS     16
1034
+  #define E3_CURRENT         800
1035
+  #define E3_MICROSTEPS       16
954 1036
 
955
-  //#define E4_CURRENT      1000
956
-  //#define E4_MICROSTEPS     16
1037
+  #define E4_CURRENT         800
1038
+  #define E4_MICROSTEPS       16
957 1039
 
958 1040
   /**
959 1041
    * Use Trinamic's ultra quiet stepping mode.
@@ -962,24 +1044,22 @@
962 1044
   #define STEALTHCHOP
963 1045
 
964 1046
   /**
965
-   * Let Marlin automatically control stepper current.
966
-   * This is still an experimental feature.
967
-   * Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
968
-   * then decrease current by CURRENT_STEP until temperature prewarn is cleared.
969
-   * Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
1047
+   * Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
1048
+   * like overtemperature and short to ground. TMC2208 requires hardware serial.
1049
+   * In the case of overtemperature Marlin can decrease the driver current until error condition clears.
1050
+   * Other detected conditions can be used to stop the current print.
970 1051
    * Relevant g-codes:
971 1052
    * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
972
-   * M906 S1 - Start adjusting current
973
-   * M906 S0 - Stop adjusting current
974 1053
    * M911 - Report stepper driver overtemperature pre-warn condition.
975 1054
    * M912 - Clear stepper driver overtemperature pre-warn condition flag.
1055
+   * M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
976 1056
    */
977
-  //#define AUTOMATIC_CURRENT_CONTROL
1057
+  //#define MONITOR_DRIVER_STATUS
978 1058
 
979
-  #if ENABLED(AUTOMATIC_CURRENT_CONTROL)
980
-    #define CURRENT_STEP          50  // [mA]
981
-    #define AUTO_ADJUST_MAX     1300  // [mA], 1300mA_rms = 1840mA_peak
1059
+  #if ENABLED(MONITOR_DRIVER_STATUS)
1060
+    #define CURRENT_STEP_DOWN     50  // [mA]
982 1061
     #define REPORT_CURRENT_CHANGE
1062
+    #define STOP_ON_ERROR
983 1063
   #endif
984 1064
 
985 1065
   /**
@@ -994,8 +1074,8 @@
994 1074
   #define X2_HYBRID_THRESHOLD    100
995 1075
   #define Y_HYBRID_THRESHOLD     100
996 1076
   #define Y2_HYBRID_THRESHOLD    100
997
-  #define Z_HYBRID_THRESHOLD       4
998
-  #define Z2_HYBRID_THRESHOLD      4
1077
+  #define Z_HYBRID_THRESHOLD       3
1078
+  #define Z2_HYBRID_THRESHOLD      3
999 1079
   #define E0_HYBRID_THRESHOLD     30
1000 1080
   #define E1_HYBRID_THRESHOLD     30
1001 1081
   #define E2_HYBRID_THRESHOLD     30
@@ -1005,7 +1085,7 @@
1005 1085
   /**
1006 1086
    * Use stallGuard2 to sense an obstacle and trigger an endstop.
1007 1087
    * You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
1008
-   * If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
1088
+   * X and Y homing will always be done in spreadCycle mode.
1009 1089
    *
1010 1090
    * X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
1011 1091
    * Higher values make the system LESS sensitive.
@@ -1014,27 +1094,34 @@
1014 1094
    * It is advised to set X/Y_HOME_BUMP_MM to 0.
1015 1095
    * M914 X/Y to live tune the setting
1016 1096
    */
1017
-  //#define SENSORLESS_HOMING
1097
+  //#define SENSORLESS_HOMING // TMC2130 only
1018 1098
 
1019 1099
   #if ENABLED(SENSORLESS_HOMING)
1020
-    #define X_HOMING_SENSITIVITY  19
1021
-    #define Y_HOMING_SENSITIVITY  19
1100
+    #define X_HOMING_SENSITIVITY  8
1101
+    #define Y_HOMING_SENSITIVITY  8
1022 1102
   #endif
1023 1103
 
1024 1104
   /**
1105
+   * Enable M122 debugging command for TMC stepper drivers.
1106
+   * M122 S0/1 will enable continous reporting.
1107
+   */
1108
+  //#define TMC_DEBUG
1109
+
1110
+  /**
1025 1111
    * You can set your own advanced settings by filling in predefined functions.
1026 1112
    * A list of available functions can be found on the library github page
1027 1113
    * https://github.com/teemuatlut/TMC2130Stepper
1114
+   * https://github.com/teemuatlut/TMC2208Stepper
1028 1115
    *
1029 1116
    * Example:
1030
-   * #define TMC2130_ADV() { \
1117
+   * #define TMC_ADV() { \
1031 1118
    *   stepperX.diag0_temp_prewarn(1); \
1032
-   *   stepperX.interpolate(0); \
1119
+   *   stepperY.interpolate(0); \
1033 1120
    * }
1034 1121
    */
1035
-  #define  TMC2130_ADV() {  }
1122
+  #define  TMC_ADV() {  }
1036 1123
 
1037
-#endif // HAVE_TMC2130
1124
+#endif // TMC2130 || TMC2208
1038 1125
 
1039 1126
 // @section L6470
1040 1127
 
@@ -1199,6 +1286,48 @@
1199 1286
 #endif
1200 1287
 
1201 1288
 /**
1289
+ * Filament Width Sensor
1290
+ *
1291
+ * Measures the filament width in real-time and adjusts
1292
+ * flow rate to compensate for any irregularities.
1293
+ *
1294
+ * Also allows the measured filament diameter to set the
1295
+ * extrusion rate, so the slicer only has to specify the
1296
+ * volume.
1297
+ *
1298
+ * Only a single extruder is supported at this time.
1299
+ *
1300
+ *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1301
+ *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1302
+ * 301 RAMBO       : Analog input 3
1303
+ *
1304
+ * Note: May require analog pins to be defined for other boards.
1305
+ */
1306
+//#define FILAMENT_WIDTH_SENSOR
1307
+
1308
+#if ENABLED(FILAMENT_WIDTH_SENSOR)
1309
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
1310
+  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1311
+
1312
+  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1313
+  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1314
+  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1315
+
1316
+  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1317
+
1318
+  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1319
+  //#define FILAMENT_LCD_DISPLAY
1320
+#endif
1321
+
1322
+/**
1323
+ * CNC Coordinate Systems
1324
+ *
1325
+ * Enables G53 and G54-G59.3 commands to select coordinate systems
1326
+ * and G92.1 to reset the workspace to native machine space.
1327
+ */
1328
+//#define CNC_COORDINATE_SYSTEMS
1329
+
1330
+/**
1202 1331
  * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
1203 1332
  */
1204 1333
 //#define PINS_DEBUGGING
@@ -1229,7 +1358,7 @@
1229 1358
  *  - M206 and M428 are disabled.
1230 1359
  *  - G92 will revert to its behavior from Marlin 1.0.
1231 1360
  */
1232
-//#define NO_WORKSPACE_OFFSETS
1361
+#define NO_WORKSPACE_OFFSETS
1233 1362
 
1234 1363
 /**
1235 1364
  * Set the number of proportional font spaces required to fill up a typical character space.
@@ -1251,6 +1380,8 @@
1251 1380
 //#define CUSTOM_USER_MENUS
1252 1381
 #if ENABLED(CUSTOM_USER_MENUS)
1253 1382
   #define USER_SCRIPT_DONE "M117 User Script Done"
1383
+  #define USER_SCRIPT_AUDIBLE_FEEDBACK
1384
+  //#define USER_SCRIPT_RETURN  // Return to status screen after a script
1254 1385
 
1255 1386
   #define USER_DESC_1 "Home & UBL Info"
1256 1387
   #define USER_GCODE_1 "G28\nG29 W"
@@ -1278,6 +1409,7 @@
1278 1409
 //===========================================================================
1279 1410
 //====================== I2C Position Encoder Settings ======================
1280 1411
 //===========================================================================
1412
+
1281 1413
 /**
1282 1414
  *  I2C position encoders for closed loop control.
1283 1415
  *  Developed by Chris Barr at Aus3D.
@@ -1358,4 +1490,45 @@
1358 1490
 
1359 1491
 #endif // I2C_POSITION_ENCODERS
1360 1492
 
1493
+/**
1494
+ * MAX7219 Debug Matrix
1495
+ *
1496
+ * Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
1497
+ * display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
1498
+ *
1499
+ * Fully assembled MAX7219 boards can be found on the internet for under $2(US).
1500
+ * For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
1501
+ */
1502
+//#define MAX7219_DEBUG
1503
+#if ENABLED(MAX7219_DEBUG)
1504
+  #define MAX7219_CLK_PIN   64  // 77 on Re-ARM       // Configuration of the 3 pins to control the display
1505
+  #define MAX7219_DIN_PIN   57  // 78 on Re-ARM
1506
+  #define MAX7219_LOAD_PIN  44  // 79 on Re-ARM
1507
+
1508
+  /**
1509
+   * Sample debug features
1510
+   * If you add more debug displays, be careful to avoid conflicts!
1511
+   */
1512
+  #define MAX7219_DEBUG_PRINTER_ALIVE    // Blink corner LED of 8x8 matrix to show that the firmware is functioning
1513
+  #define MAX7219_DEBUG_STEPPER_HEAD  3  // Show the stepper queue head position on this and the next LED matrix row
1514
+  #define MAX7219_DEBUG_STEPPER_TAIL  5  // Show the stepper queue tail position on this and the next LED matrix row
1515
+
1516
+  #define MAX7219_DEBUG_STEPPER_QUEUE 0  // Show the current stepper queue depth on this and the next LED matrix row
1517
+                                         // If you experience stuttering, reboots, etc. this option can reveal how
1518
+                                         // tweaks made to the configuration are affecting the printer in real-time.
1519
+#endif
1520
+
1521
+/**
1522
+ * NanoDLP Sync support
1523
+ *
1524
+ * Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
1525
+ * string to enable synchronization with DLP projector exposure. This change will allow to use
1526
+ * [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
1527
+ */
1528
+//#define NANODLP_Z_SYNC
1529
+#if ENABLED(NANODLP_Z_SYNC)
1530
+  //#define NANODLP_ALL_AXIS  // Enables "Z_move_comp" output on any axis move.
1531
+                              // Default behaviour is limited to Z axis only.
1532
+#endif
1533
+
1361 1534
 #endif // CONFIGURATION_ADV_H

+ 242
- 102
Marlin/example_configurations/TinyBoy2/Configuration.h 파일 보기

@@ -37,7 +37,7 @@
37 37
  */
38 38
 #ifndef CONFIGURATION_H
39 39
 #define CONFIGURATION_H
40
-#define CONFIGURATION_H_VERSION 010100
40
+#define CONFIGURATION_H_VERSION 010107
41 41
 
42 42
 /**
43 43
  * Sample configuration file for TinyBoy2 L10/L16
@@ -90,7 +90,7 @@
90 90
 // User-specified version info of this build to display in [Pronterface, etc] terminal window during
91 91
 // startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
92 92
 // build by the user have been successfully uploaded into firmware.
93
-#define STRING_CONFIG_H_AUTHOR "(StefanB, default config)" // Who made the changes.
93
+#define STRING_CONFIG_H_AUTHOR "(StefanB, TinyBoy2)" // Who made the changes.
94 94
 #define SHOW_BOOTSCREEN
95 95
 #define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
96 96
 #define STRING_SPLASH_LINE2 WEBSITE_URL         // will be shown during bootup in line 2
@@ -123,8 +123,9 @@
123 123
  *
124 124
  * 250000 works in most cases, but you might try a lower speed if
125 125
  * you commonly experience drop-outs during host printing.
126
+ * You may try up to 1000000 to speed up SD file transfer.
126 127
  *
127
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
128
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
128 129
  */
129 130
 #define BAUDRATE 115200
130 131
 
@@ -157,6 +158,9 @@
157 158
 // :[1, 2, 3, 4, 5]
158 159
 #define EXTRUDERS 1
159 160
 
161
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
162
+#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75
163
+
160 164
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
161 165
 //#define SINGLENOZZLE
162 166
 
@@ -183,7 +187,10 @@
183 187
 //#define SWITCHING_EXTRUDER
184 188
 #if ENABLED(SWITCHING_EXTRUDER)
185 189
   #define SWITCHING_EXTRUDER_SERVO_NR 0
186
-  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1
190
+  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3]
191
+  #if EXTRUDERS > 3
192
+    #define SWITCHING_EXTRUDER_E23_SERVO_NR 1
193
+  #endif
187 194
 #endif
188 195
 
189 196
 // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles
@@ -195,6 +202,21 @@
195 202
 #endif
196 203
 
197 204
 /**
205
+ * Two separate X-carriages with extruders that connect to a moving part
206
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
207
+ */
208
+//#define PARKING_EXTRUDER
209
+#if ENABLED(PARKING_EXTRUDER)
210
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
211
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
212
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
213
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
214
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
215
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
216
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
217
+#endif
218
+
219
+/**
198 220
  * "Mixing Extruder"
199 221
  *   - Adds a new code, M165, to set the current mix factors.
200 222
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -344,8 +366,9 @@
344 366
 
345 367
 // Comment the following line to disable PID and enable bang-bang.
346 368
 #define PIDTEMP
347
-#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
348
-#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
369
+#define BANG_MAX 255     // Limits current to nozzle while in bang-bang mode; 255=full current
370
+#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
371
+#define PID_K1 0.95      // Smoothing factor within the PID
349 372
 #if ENABLED(PIDTEMP)
350 373
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
351 374
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -355,7 +378,6 @@
355 378
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
356 379
   #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
357 380
                                   // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
358
-  #define K1 0.95 //smoothing factor within the PID
359 381
 
360 382
   // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
361 383
 
@@ -459,12 +481,13 @@
459 481
 //===========================================================================
460 482
 
461 483
 /**
462
- * Thermal Protection protects your printer from damage and fire if a
463
- * thermistor falls out or temperature sensors fail in any way.
484
+ * Thermal Protection provides additional protection to your printer from damage
485
+ * and fire. Marlin always includes safe min and max temperature ranges which
486
+ * protect against a broken or disconnected thermistor wire.
464 487
  *
465
- * The issue: If a thermistor falls out or a temperature sensor fails,
466
- * Marlin can no longer sense the actual temperature. Since a disconnected
467
- * thermistor reads as a low temperature, the firmware will keep the heater on.
488
+ * The issue: If a thermistor falls out, it will report the much lower
489
+ * temperature of the air in the room, and the the firmware will keep
490
+ * the heater on.
468 491
  *
469 492
  * If you get "Thermal Runaway" or "Heating failed" errors the
470 493
  * details can be tuned in Configuration_adv.h
@@ -605,7 +628,7 @@
605 628
 // @section probes
606 629
 
607 630
 //
608
-// See http://marlinfw.org/configuration/probes.html
631
+// See http://marlinfw.org/docs/configuration/probes.html
609 632
 //
610 633
 
611 634
 /**
@@ -671,14 +694,15 @@
671 694
 #endif
672 695
 
673 696
 /**
674
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
675
- * options selected below - will be disabled during probing so as to minimize
676
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
677
- * in current flowing through the wires).  This is likely most useful to users of the
678
- * BLTouch probe, but may also help those with inductive or other probe types.
697
+ * Enable one or more of the following if probing seems unreliable.
698
+ * Heaters and/or fans can be disabled during probing to minimize electrical
699
+ * noise. A delay can also be added to allow noise and vibration to settle.
700
+ * These options are most useful for the BLTouch probe, but may also improve
701
+ * readings with inductive probes and piezo sensors.
679 702
  */
680 703
 //#define PROBING_HEATERS_OFF       // Turn heaters off when probing
681 704
 //#define PROBING_FANS_OFF          // Turn fans off when probing
705
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
682 706
 
683 707
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
684 708
 //#define SOLENOID_PROBE
@@ -717,14 +741,16 @@
717 741
 // X and Y axis travel speed (mm/m) between probes
718 742
 #define XY_PROBE_SPEED 8000
719 743
 
720
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
744
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
721 745
 #define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
722 746
 
723 747
 // Speed for the "accurate" probe of each point
724 748
 #define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
725 749
 
726
-// Use double touch for probing
727
-//#define PROBE_DOUBLE_TOUCH
750
+// The number of probes to perform at each point.
751
+//   Set to 2 for a fast/slow probe, using the second probe result.
752
+//   Set to 3 or more for slow probes, averaging the results.
753
+//#define MULTIPLE_PROBING 2
728 754
 
729 755
 /**
730 756
  * Z probes require clearance when deploying, stowing, and moving between
@@ -791,6 +817,8 @@
791 817
 
792 818
 // @section homing
793 819
 
820
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
821
+
794 822
 //#define Z_HOMING_HEIGHT 4  // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
795 823
                              // Be sure you have this distance over your Z_MAX_POS in case.
796 824
 
@@ -802,23 +830,47 @@
802 830
 
803 831
 // @section machine
804 832
 
805
-// Travel limits after homing (units are in mm)
833
+// The size of the print bed
834
+// Tinyboy2: 100mm are marketed, actual length between endstop and end of rail is 98mm
835
+#define X_BED_SIZE 98
836
+#define Y_BED_SIZE 98
837
+
838
+// Travel limits (mm) after homing, corresponding to endstop positions.
806 839
 #define X_MIN_POS 0
807 840
 #define Y_MIN_POS 0
808 841
 #define Z_MIN_POS 0
809
-// Tinyboy2: 100mm are marketed, actual length between endstop and end of rail is 98mm
810
-#define X_MAX_POS 98
811
-#define Y_MAX_POS 98
842
+#define X_MAX_POS X_BED_SIZE
843
+#define Y_MAX_POS Y_BED_SIZE
812 844
 #if ENABLED(TB2_L10)
813 845
   #define Z_MAX_POS 98
814 846
 #else
815 847
   #define Z_MAX_POS 158
816 848
 #endif
817 849
 
818
-// If enabled, axes won't move below MIN_POS in response to movement commands.
850
+/**
851
+ * Software Endstops
852
+ *
853
+ * - Prevent moves outside the set machine bounds.
854
+ * - Individual axes can be disabled, if desired.
855
+ * - X and Y only apply to Cartesian robots.
856
+ * - Use 'M211' to set software endstops on/off or report current state
857
+ */
858
+
859
+// Min software endstops curtail movement below minimum coordinate bounds
819 860
 #define MIN_SOFTWARE_ENDSTOPS
820
-// If enabled, axes won't move above MAX_POS in response to movement commands.
861
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
862
+  #define MIN_SOFTWARE_ENDSTOP_X
863
+  #define MIN_SOFTWARE_ENDSTOP_Y
864
+  #define MIN_SOFTWARE_ENDSTOP_Z
865
+#endif
866
+
867
+// Max software endstops curtail movement above maximum coordinate bounds
821 868
 #define MAX_SOFTWARE_ENDSTOPS
869
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
870
+  #define MAX_SOFTWARE_ENDSTOP_X
871
+  #define MAX_SOFTWARE_ENDSTOP_Y
872
+  #define MAX_SOFTWARE_ENDSTOP_Z
873
+#endif
822 874
 
823 875
 /**
824 876
  * Filament Runout Sensor
@@ -838,7 +890,7 @@
838 890
 //===========================================================================
839 891
 //=============================== Bed Leveling ==============================
840 892
 //===========================================================================
841
-// @section bedlevel
893
+// @section calibrate
842 894
 
843 895
 /**
844 896
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -864,12 +916,7 @@
864 916
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
865 917
  *   A comprehensive bed leveling system combining the features and benefits
866 918
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
867
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
868
- *   for Cartesian Printers. That said, it was primarily designed to correct
869
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
870
- *   please post an issue if something doesn't work correctly. Initially,
871
- *   you will need to set a reduced bed size so you have a rectangular area
872
- *   to test on.
919
+ *   Validation and Mesh Editing systems.
873 920
  *
874 921
  * - MESH_BED_LEVELING
875 922
  *   Probe a grid manually
@@ -896,6 +943,24 @@
896 943
   // at which point movement will be level to the machine's XY plane.
897 944
   // The height can be set with M420 Z<height>
898 945
   #define ENABLE_LEVELING_FADE_HEIGHT
946
+
947
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
948
+  // split up moves into short segments like a Delta. This follows the
949
+  // contours of the bed more closely than edge-to-edge straight moves.
950
+  #define SEGMENT_LEVELED_MOVES
951
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
952
+
953
+  /**
954
+   * Enable the G26 Mesh Validation Pattern tool.
955
+   */
956
+  //#define G26_MESH_VALIDATION   // Enable G26 mesh validation
957
+  #if ENABLED(G26_MESH_VALIDATION)
958
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
959
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
960
+    #define MESH_TEST_HOTEND_TEMP   205.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
961
+    #define MESH_TEST_BED_TEMP       60.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
962
+  #endif
963
+
899 964
 #endif
900 965
 
901 966
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -951,7 +1016,9 @@
951 1016
   //========================= Unified Bed Leveling ============================
952 1017
   //===========================================================================
953 1018
 
954
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
1019
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
1020
+
1021
+  #define MESH_INSET 1              // Mesh inset margin on print area
955 1022
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
956 1023
   #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
957 1024
 
@@ -962,8 +1029,8 @@
962 1029
   #define UBL_PROBE_PT_3_X 180
963 1030
   #define UBL_PROBE_PT_3_Y 20
964 1031
 
965
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
966 1032
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
1033
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
967 1034
 
968 1035
 #elif ENABLED(MESH_BED_LEVELING)
969 1036
 
@@ -990,6 +1057,9 @@
990 1057
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
991 1058
 #endif
992 1059
 
1060
+// Add a menu item to move between bed corners for manual bed adjustment
1061
+//#define LEVEL_BED_CORNERS
1062
+
993 1063
 /**
994 1064
  * Commands to execute at the end of G29 probing.
995 1065
  * Useful to retract or move the Z probe out of the way.
@@ -1020,14 +1090,71 @@
1020 1090
 //#define Z_SAFE_HOMING
1021 1091
 
1022 1092
 #if ENABLED(Z_SAFE_HOMING)
1023
-  #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
1024
-  #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
1093
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1094
+  #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2)    // Y point for Z homing when homing all axes (G28).
1025 1095
 #endif
1026 1096
 
1027 1097
 // Homing speeds (mm/m)
1028 1098
 #define HOMING_FEEDRATE_XY (40*60)
1029 1099
 #define HOMING_FEEDRATE_Z  (3*60)
1030 1100
 
1101
+// @section calibrate
1102
+
1103
+/**
1104
+ * Bed Skew Compensation
1105
+ *
1106
+ * This feature corrects for misalignment in the XYZ axes.
1107
+ *
1108
+ * Take the following steps to get the bed skew in the XY plane:
1109
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1110
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1111
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1112
+ *  4. For XY_SIDE_AD measure the edge A to D
1113
+ *
1114
+ * Marlin automatically computes skew factors from these measurements.
1115
+ * Skew factors may also be computed and set manually:
1116
+ *
1117
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1118
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1119
+ *
1120
+ * If desired, follow the same procedure for XZ and YZ.
1121
+ * Use these diagrams for reference:
1122
+ *
1123
+ *    Y                     Z                     Z
1124
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1125
+ *    |    /       /        |    /       /        |    /       /
1126
+ *    |   /       /         |   /       /         |   /       /
1127
+ *    |  A-------D          |  A-------D          |  A-------D
1128
+ *    +-------------->X     +-------------->X     +-------------->Y
1129
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1130
+ */
1131
+//#define SKEW_CORRECTION
1132
+
1133
+#if ENABLED(SKEW_CORRECTION)
1134
+  // Input all length measurements here:
1135
+  #define XY_DIAG_AC 282.8427124746
1136
+  #define XY_DIAG_BD 282.8427124746
1137
+  #define XY_SIDE_AD 200
1138
+
1139
+  // Or, set the default skew factors directly here
1140
+  // to override the above measurements:
1141
+  #define XY_SKEW_FACTOR 0.0
1142
+
1143
+  //#define SKEW_CORRECTION_FOR_Z
1144
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1145
+    #define XZ_DIAG_AC 282.8427124746
1146
+    #define XZ_DIAG_BD 282.8427124746
1147
+    #define YZ_DIAG_AC 282.8427124746
1148
+    #define YZ_DIAG_BD 282.8427124746
1149
+    #define YZ_SIDE_AD 200
1150
+    #define XZ_SKEW_FACTOR 0.0
1151
+    #define YZ_SKEW_FACTOR 0.0
1152
+  #endif
1153
+
1154
+  // Enable this option for M852 to set skew at runtime
1155
+  //#define SKEW_CORRECTION_GCODE
1156
+#endif
1157
+
1031 1158
 //=============================================================================
1032 1159
 //============================= Additional Features ===========================
1033 1160
 //=============================================================================
@@ -1054,11 +1181,12 @@
1054 1181
 //
1055 1182
 #define HOST_KEEPALIVE_FEATURE        // Disable this if your host doesn't like keepalive messages
1056 1183
 #define DEFAULT_KEEPALIVE_INTERVAL 2  // Number of seconds between "busy" messages. Set with M113.
1184
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
1057 1185
 
1058 1186
 //
1059 1187
 // M100 Free Memory Watcher
1060 1188
 //
1061
-//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1189
+//#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
1062 1190
 
1063 1191
 //
1064 1192
 // G20/G21 Inch mode support
@@ -1203,11 +1331,11 @@
1203 1331
  *
1204 1332
  * Select the language to display on the LCD. These languages are available:
1205 1333
  *
1206
- *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
1207
- *    it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
1208
- *    zh_CN, zh_TW, test
1334
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1335
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1336
+ *    tr, uk, zh_CN, zh_TW, test
1209 1337
  *
1210
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1338
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1211 1339
  */
1212 1340
 #define LCD_LANGUAGE en
1213 1341
 
@@ -1229,7 +1357,7 @@
1229 1357
  *  - Click the controller to view the LCD menu
1230 1358
  *  - The LCD will display Japanese, Western, or Cyrillic text
1231 1359
  *
1232
- * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1360
+ * See http://marlinfw.org/docs/development/lcd_language.html
1233 1361
  *
1234 1362
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1235 1363
  */
@@ -1335,8 +1463,8 @@
1335 1463
 // Note: Test audio output with the G-Code:
1336 1464
 //  M300 S<frequency Hz> P<duration ms>
1337 1465
 //
1338
-//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
1339
-//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
1466
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
1467
+//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
1340 1468
 
1341 1469
 //
1342 1470
 // CONTROLLER TYPE: Standard
@@ -1444,11 +1572,13 @@
1444 1572
 //#define CARTESIO_UI
1445 1573
 
1446 1574
 //
1447
-// ANET_10 Controller supported displays.
1575
+// ANET and Tronxy Controller supported displays.
1448 1576
 //
1449
-//#define ANET_KEYPAD_LCD         // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1577
+//#define ZONESTAR_LCD            // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1450 1578
                                   // This LCD is known to be susceptible to electrical interference
1451 1579
                                   // which scrambles the display.  Pressing any button clears it up.
1580
+                                  // This is a LCD2004 display with 5 analog buttons.
1581
+
1452 1582
 //#define ANET_FULL_GRAPHICS_LCD  // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1453 1583
                                   // A clone of the RepRapDiscount full graphics display but with
1454 1584
                                   // different pins/wiring (see pins_ANET_10.h).
@@ -1508,11 +1638,6 @@
1508 1638
 //#define U8GLIB_SSD1306
1509 1639
 
1510 1640
 //
1511
-// TinyBoy2 128x64 OLED / Encoder Panel
1512
-//
1513
-//#define OLED_PANEL_TINYBOY2
1514
-
1515
-//
1516 1641
 // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules
1517 1642
 //
1518 1643
 //#define SAV_3DGLCD
@@ -1534,6 +1659,40 @@
1534 1659
 //
1535 1660
 #define OLED_PANEL_TINYBOY2
1536 1661
 
1662
+//
1663
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1664
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1665
+//
1666
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1667
+
1668
+//
1669
+// MKS MINI12864 with graphic controller and SD support
1670
+// http://reprap.org/wiki/MKS_MINI_12864
1671
+//
1672
+//#define MKS_MINI_12864
1673
+
1674
+//
1675
+// Factory display for Creality CR-10
1676
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1677
+//
1678
+// This is RAMPS-compatible using a single 10-pin connector.
1679
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1680
+//
1681
+//#define CR10_STOCKDISPLAY
1682
+
1683
+//
1684
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1685
+// http://reprap.org/wiki/MKS_12864OLED
1686
+//
1687
+// Tiny, but very sharp OLED display
1688
+//
1689
+//#define MKS_12864OLED
1690
+
1691
+// Silvergate GLCD controller
1692
+// http://github.com/android444/Silvergate
1693
+//
1694
+//#define SILVER_GATE_GLCD_CONTROLLER
1695
+
1537 1696
 //=============================================================================
1538 1697
 //=============================== Extra Features ==============================
1539 1698
 //=============================================================================
@@ -1590,16 +1749,22 @@
1590 1749
  * Adds the M150 command to set the LED (or LED strip) color.
1591 1750
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1592 1751
  * luminance values can be set from 0 to 255.
1752
+ * For Neopixel LED an overall brightness parameter is also available.
1593 1753
  *
1594 1754
  * *** CAUTION ***
1595 1755
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1596 1756
  *  as the Arduino cannot handle the current the LEDs will require.
1597 1757
  *  Failure to follow this precaution can destroy your Arduino!
1758
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1759
+ *  more current than the Arduino 5V linear regulator can produce.
1598 1760
  * *** CAUTION ***
1599 1761
  *
1762
+ * LED Type. Enable only one of the following two options.
1763
+ *
1600 1764
  */
1601 1765
 //#define RGB_LED
1602 1766
 //#define RGBW_LED
1767
+
1603 1768
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1604 1769
   #define RGB_LED_R_PIN 34
1605 1770
   #define RGB_LED_G_PIN 43
@@ -1607,6 +1772,17 @@
1607 1772
   #define RGB_LED_W_PIN -1
1608 1773
 #endif
1609 1774
 
1775
+// Support for Adafruit Neopixel LED driver
1776
+//#define NEOPIXEL_LED
1777
+#if ENABLED(NEOPIXEL_LED)
1778
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1779
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1780
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1781
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1782
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1783
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1784
+#endif
1785
+
1610 1786
 /**
1611 1787
  * Printer Event LEDs
1612 1788
  *
@@ -1618,68 +1794,32 @@
1618 1794
  *  - Change to green once print has finished
1619 1795
  *  - Turn off after the print has finished and the user has pushed a button
1620 1796
  */
1621
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)
1797
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1622 1798
   #define PRINTER_EVENT_LEDS
1623 1799
 #endif
1624 1800
 
1625
-/*********************************************************************\
1626
-* R/C SERVO support
1627
-* Sponsored by TrinityLabs, Reworked by codexmas
1628
-**********************************************************************/
1801
+/**
1802
+ * R/C SERVO support
1803
+ * Sponsored by TrinityLabs, Reworked by codexmas
1804
+ */
1629 1805
 
1630
-// Number of servos
1631
-//
1632
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1633
-// set it manually if you have more servos than extruders and wish to manually control some
1634
-// leaving it undefined or defining as 0 will disable the servo subsystem
1635
-// If unsure, leave commented / disabled
1636
-//
1806
+/**
1807
+ * Number of servos
1808
+ *
1809
+ * For some servo-related options NUM_SERVOS will be set automatically.
1810
+ * Set this manually if there are extra servos needing manual control.
1811
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1812
+ */
1637 1813
 //#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
1638 1814
 
1639 1815
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1640 1816
 // 300ms is a good value but you can try less delay.
1641 1817
 // If the servo can't reach the requested position, increase it.
1642
-#define SERVO_DELAY 300
1818
+#define SERVO_DELAY { 300 }
1643 1819
 
1644 1820
 // Servo deactivation
1645 1821
 //
1646 1822
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1647 1823
 //#define DEACTIVATE_SERVOS_AFTER_MOVE
1648 1824
 
1649
-/**
1650
- * Filament Width Sensor
1651
- *
1652
- * Measures the filament width in real-time and adjusts
1653
- * flow rate to compensate for any irregularities.
1654
- *
1655
- * Also allows the measured filament diameter to set the
1656
- * extrusion rate, so the slicer only has to specify the
1657
- * volume.
1658
- *
1659
- * Only a single extruder is supported at this time.
1660
- *
1661
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1662
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1663
- * 301 RAMBO       : Analog input 3
1664
- *
1665
- * Note: May require analog pins to be defined for other boards.
1666
- */
1667
-//#define FILAMENT_WIDTH_SENSOR
1668
-
1669
-#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75   // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
1670
-
1671
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1672
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1673
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1674
-
1675
-  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1676
-  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1677
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1678
-
1679
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1680
-
1681
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1682
-  //#define FILAMENT_LCD_DISPLAY
1683
-#endif
1684
-
1685 1825
 #endif // CONFIGURATION_H

+ 367
- 157
Marlin/example_configurations/TinyBoy2/Configuration_adv.h 파일 보기

@@ -32,7 +32,7 @@
32 32
  */
33 33
 #ifndef CONFIGURATION_ADV_H
34 34
 #define CONFIGURATION_ADV_H
35
-#define CONFIGURATION_ADV_H_VERSION 010100
35
+#define CONFIGURATION_ADV_H_VERSION 010107
36 36
 
37 37
 // @section temperature
38 38
 
@@ -48,31 +48,36 @@
48 48
 #endif
49 49
 
50 50
 /**
51
- * Thermal Protection protects your printer from damage and fire if a
52
- * thermistor falls out or temperature sensors fail in any way.
51
+ * Thermal Protection provides additional protection to your printer from damage
52
+ * and fire. Marlin always includes safe min and max temperature ranges which
53
+ * protect against a broken or disconnected thermistor wire.
53 54
  *
54
- * The issue: If a thermistor falls out or a temperature sensor fails,
55
- * Marlin can no longer sense the actual temperature. Since a disconnected
56
- * thermistor reads as a low temperature, the firmware will keep the heater on.
55
+ * The issue: If a thermistor falls out, it will report the much lower
56
+ * temperature of the air in the room, and the the firmware will keep
57
+ * the heater on.
57 58
  *
58 59
  * The solution: Once the temperature reaches the target, start observing.
59
- * If the temperature stays too far below the target (hysteresis) for too long (period),
60
- * the firmware will halt the machine as a safety precaution.
60
+ * If the temperature stays too far below the target (hysteresis) for too
61
+ * long (period), the firmware will halt the machine as a safety precaution.
61 62
  *
62
- * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63
+ * If you get false positives for "Thermal Runaway", increase
64
+ * THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
63 65
  */
64 66
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
65 67
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
66 68
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
67 69
 
68 70
   /**
69
-   * Whenever an M104 or M109 increases the target temperature the firmware will wait for the
70
-   * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
71
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
72
-   * but only if the current temperature is far enough below the target for a reliable test.
71
+   * Whenever an M104, M109, or M303 increases the target temperature, the
72
+   * firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
73
+   * hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
74
+   * requires a hard reset. This test restarts with any M104/M109/M303, but only
75
+   * if the current temperature is far enough below the target for a reliable
76
+   * test.
73 77
    *
74
-   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
75
-   * WATCH_TEMP_INCREASE should not be below 2.
78
+   * If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
79
+   * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
80
+   * below 2.
76 81
    */
77 82
   #define WATCH_TEMP_PERIOD 20                // Seconds
78 83
   #define WATCH_TEMP_INCREASE 2               // Degrees Celsius
@@ -86,13 +91,7 @@
86 91
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
87 92
 
88 93
   /**
89
-   * Whenever an M140 or M190 increases the target temperature the firmware will wait for the
90
-   * WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
91
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
92
-   * but only if the current temperature is far enough below the target for a reliable test.
93
-   *
94
-   * If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
95
-   * WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
94
+   * As described above, except for the bed (M140/M190/M303).
96 95
    */
97 96
   #define WATCH_BED_TEMP_PERIOD 60                // Seconds
98 97
   #define WATCH_BED_TEMP_INCREASE 2               // Degrees Celsius
@@ -123,6 +122,9 @@
123 122
   #define AUTOTEMP_OLDWEIGHT 0.98
124 123
 #endif
125 124
 
125
+// Show extra position information in M114
126
+//#define M114_DETAIL
127
+
126 128
 // Show Temperature ADC value
127 129
 // Enable for M105 to include ADC values read from temperature sensors.
128 130
 //#define SHOW_TEMP_ADC_VALUES
@@ -221,6 +223,17 @@
221 223
 #define EXTRUDER_AUTO_FAN_SPEED   255  // == full speed
222 224
 
223 225
 /**
226
+ * Part-Cooling Fan Multiplexer
227
+ *
228
+ * This feature allows you to digitally multiplex the fan output.
229
+ * The multiplexer is automatically switched at tool-change.
230
+ * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans.
231
+ */
232
+#define FANMUX0_PIN -1
233
+#define FANMUX1_PIN -1
234
+#define FANMUX2_PIN -1
235
+
236
+/**
224 237
  * M355 Case Light on-off / brightness
225 238
  */
226 239
 //#define CASE_LIGHT_ENABLE
@@ -246,48 +259,49 @@
246 259
 
247 260
 //#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
248 261
 
249
-// Dual X Steppers
250
-// Uncomment this option to drive two X axis motors.
251
-// The next unused E driver will be assigned to the second X stepper.
262
+/**
263
+ * Dual Steppers / Dual Endstops
264
+ *
265
+ * This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
266
+ *
267
+ * For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
268
+ * spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
269
+ * set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
270
+ * that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
271
+ *
272
+ * Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
273
+ * this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
274
+ * in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
275
+ */
276
+
252 277
 //#define X_DUAL_STEPPER_DRIVERS
253 278
 #if ENABLED(X_DUAL_STEPPER_DRIVERS)
254
-  // Set true if the two X motors need to rotate in opposite directions
255
-  #define INVERT_X2_VS_X_DIR true
279
+  #define INVERT_X2_VS_X_DIR true   // Set 'true' if X motors should rotate in opposite directions
280
+  //#define X_DUAL_ENDSTOPS
281
+  #if ENABLED(X_DUAL_ENDSTOPS)
282
+    #define X2_USE_ENDSTOP _XMAX_
283
+    #define X_DUAL_ENDSTOPS_ADJUSTMENT  0
284
+  #endif
256 285
 #endif
257 286
 
258
-// Dual Y Steppers
259
-// Uncomment this option to drive two Y axis motors.
260
-// The next unused E driver will be assigned to the second Y stepper.
261 287
 //#define Y_DUAL_STEPPER_DRIVERS
262 288
 #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
263
-  // Set true if the two Y motors need to rotate in opposite directions
264
-  #define INVERT_Y2_VS_Y_DIR true
289
+  #define INVERT_Y2_VS_Y_DIR true   // Set 'true' if Y motors should rotate in opposite directions
290
+  //#define Y_DUAL_ENDSTOPS
291
+  #if ENABLED(Y_DUAL_ENDSTOPS)
292
+    #define Y2_USE_ENDSTOP _YMAX_
293
+    #define Y_DUAL_ENDSTOPS_ADJUSTMENT  0
294
+  #endif
265 295
 #endif
266 296
 
267
-// A single Z stepper driver is usually used to drive 2 stepper motors.
268
-// Uncomment this option to use a separate stepper driver for each Z axis motor.
269
-// The next unused E driver will be assigned to the second Z stepper.
270 297
 //#define Z_DUAL_STEPPER_DRIVERS
271
-
272 298
 #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
273
-
274
-  // Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper.
275
-  // That way the machine is capable to align the bed during home, since both Z steppers are homed.
276
-  // There is also an implementation of M666 (software endstops adjustment) to this feature.
277
-  // After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
278
-  // One just need to home the Z axis and measure the distance difference between both Z axis and apply the math: Z adjust = Z - Z2.
279
-  // If the Z stepper axis is closer to the bed, the measure Z > Z2 (yes, it is.. think about it) and the Z adjust would be positive.
280
-  // Play a little bit with small adjustments (0.5mm) and check the behaviour.
281
-  // The M119 (endstops report) will start reporting the Z2 Endstop as well.
282
-
283 299
   //#define Z_DUAL_ENDSTOPS
284
-
285 300
   #if ENABLED(Z_DUAL_ENDSTOPS)
286 301
     #define Z2_USE_ENDSTOP _XMAX_
287
-    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0  // use M666 command to determine/test this value
302
+    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0
288 303
   #endif
289
-
290
-#endif // Z_DUAL_STEPPER_DRIVERS
304
+#endif
291 305
 
292 306
 // Enable this for dual x-carriage printers.
293 307
 // A dual x-carriage design has the advantage that the inactive extruder can be parked which
@@ -334,12 +348,12 @@
334 348
 
335 349
 // @section homing
336 350
 
337
-//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
351
+// Homing hits each endstop, retracts by these distances, then does a slower bump.
338 352
 #define X_HOME_BUMP_MM 5
339 353
 #define Y_HOME_BUMP_MM 5
340 354
 #define Z_HOME_BUMP_MM 2
341
-#define HOMING_BUMP_DIVISOR {2, 2, 4}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
342
-//#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
355
+#define HOMING_BUMP_DIVISOR { 2, 2, 4 }  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
356
+//#define QUICK_HOME                     // If homing includes X and Y, do a diagonal move initially
343 357
 
344 358
 // When G28 is called, this option will make Y home before X
345 359
 //#define HOME_Y_BEFORE_X
@@ -394,7 +408,7 @@
394 408
 // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
395 409
 // of the buffer and all stops. This should not be much greater than zero and should only be changed
396 410
 // if unwanted behavior is observed on a user's machine when running at very slow speeds.
397
-#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
411
+#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
398 412
 
399 413
 // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
400 414
 #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
@@ -423,8 +437,21 @@
423 437
 //#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 }   // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
424 438
 //#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 }    // Default drive percent - X, Y, Z, E axis
425 439
 
426
-// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
440
+// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
427 441
 //#define DIGIPOT_I2C
442
+#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
443
+  /**
444
+   * Common slave addresses:
445
+   *
446
+   *                    A   (A shifted)   B   (B shifted)  IC
447
+   * Smoothie          0x2C (0x58)       0x2D (0x5A)       MCP4451
448
+   * AZTEEG_X3_PRO     0x2C (0x58)       0x2E (0x5C)       MCP4451
449
+   * MIGHTYBOARD_REVE  0x2F (0x5E)                         MCP4018
450
+   */
451
+  #define DIGIPOT_I2C_ADDRESS_A 0x2C  // unshifted slave address for first DIGIPOT
452
+  #define DIGIPOT_I2C_ADDRESS_B 0x2D  // unshifted slave address for second DIGIPOT
453
+#endif
454
+
428 455
 //#define DIGIPOT_MCP4018          // Requires library from https://github.com/stawel/SlowSoftI2CMaster
429 456
 #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4     AZTEEG_X3_PRO: 8
430 457
 // Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
@@ -455,6 +482,23 @@
455 482
 // The timeout (in ms) to return to the status screen from sub-menus
456 483
 //#define LCD_TIMEOUT_TO_STATUS 15000
457 484
 
485
+/**
486
+ * LED Control Menu
487
+ * Enable this feature to add LED Control to the LCD menu
488
+ */
489
+//#define LED_CONTROL_MENU
490
+#if ENABLED(LED_CONTROL_MENU)
491
+  #define LED_COLOR_PRESETS                 // Enable the Preset Color menu option
492
+  #if ENABLED(LED_COLOR_PRESETS)
493
+    #define LED_USER_PRESET_RED        255  // User defined RED value
494
+    #define LED_USER_PRESET_GREEN      128  // User defined GREEN value
495
+    #define LED_USER_PRESET_BLUE         0  // User defined BLUE value
496
+    #define LED_USER_PRESET_WHITE      255  // User defined WHITE value
497
+    #define LED_USER_PRESET_BRIGHTNESS 255  // User defined intensity
498
+    //#define LED_USER_PRESET_STARTUP       // Have the printer display the user preset color on startup
499
+  #endif
500
+#endif // LED_CONTROL_MENU
501
+
458 502
 #if ENABLED(SDSUPPORT)
459 503
 
460 504
   // Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -464,12 +508,14 @@
464 508
   // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
465 509
   #define SD_DETECT_INVERTED
466 510
 
467
-  #define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
511
+  #define SD_FINISHED_STEPPERRELEASE true          // Disable steppers when SD Print is finished
468 512
   #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
469 513
 
470
-  #define SDCARD_RATHERRECENTFIRST  //reverse file order of sd card menu display. Its sorted practically after the file system block order.
471
-  // if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that.
472
-  // using:
514
+  // Reverse SD sort to show "more recent" files first, according to the card's FAT.
515
+  // Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
516
+  #define SDCARD_RATHERRECENTFIRST
517
+
518
+  // Add an option in the menu to run all auto#.g files
473 519
   //#define MENU_ADDAUTOSTART
474 520
 
475 521
   /**
@@ -499,13 +545,15 @@
499 545
 
500 546
   // SD Card Sorting options
501 547
   #if ENABLED(SDCARD_SORT_ALPHA)
502
-    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256).
548
+    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256). Costs 27 bytes each.
503 549
     #define FOLDER_SORTING     -1     // -1=above  0=none  1=below
504 550
     #define SDSORT_GCODE       false  // Allow turning sorting on/off with LCD and M34 g-code.
505 551
     #define SDSORT_USES_RAM    false  // Pre-allocate a static array for faster pre-sorting.
506 552
     #define SDSORT_USES_STACK  false  // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
507 553
     #define SDSORT_CACHE_NAMES false  // Keep sorted items in RAM longer for speedy performance. Most expensive option.
508 554
     #define SDSORT_DYNAMIC_RAM false  // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
555
+    #define SDSORT_CACHE_VFATS 2      // Maximum number of 13-byte VFAT entries to use for sorting.
556
+                                      // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
509 557
   #endif
510 558
 
511 559
   // Show a progress bar on HD44780 LCDs for SD printing
@@ -524,14 +572,29 @@
524 572
     //#define LCD_PROGRESS_BAR_TEST
525 573
   #endif
526 574
 
575
+  // Add an 'M73' G-code to set the current percentage
576
+  //#define LCD_SET_PROGRESS_MANUALLY
577
+
527 578
   // This allows hosts to request long names for files and folders with M33
528 579
   //#define LONG_FILENAME_HOST_SUPPORT
529 580
 
530
-  // This option allows you to abort SD printing when any endstop is triggered.
531
-  // This feature must be enabled with "M540 S1" or from the LCD menu.
532
-  // To have any effect, endstops must be enabled during SD printing.
581
+  // Enable this option to scroll long filenames in the SD card menu
582
+  //#define SCROLL_LONG_FILENAMES
583
+
584
+  /**
585
+   * This option allows you to abort SD printing when any endstop is triggered.
586
+   * This feature must be enabled with "M540 S1" or from the LCD menu.
587
+   * To have any effect, endstops must be enabled during SD printing.
588
+   */
533 589
   //#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
534 590
 
591
+  /**
592
+   * This option makes it easier to print the same SD Card file again.
593
+   * On print completion the LCD Menu will open with the file selected.
594
+   * You can just click to start the print, or navigate elsewhere.
595
+   */
596
+  //#define SD_REPRINT_LAST_SELECTED_FILE
597
+
535 598
 #endif // SDSUPPORT
536 599
 
537 600
 /**
@@ -564,6 +627,10 @@
564 627
   // Enable this option and reduce the value to optimize screen updates.
565 628
   // The normal delay is 10µs. Use the lowest value that still gives a reliable display.
566 629
   //#define DOGM_SPI_DELAY_US 5
630
+
631
+  // Swap the CW/CCW indicators in the graphics overlay
632
+  //#define OVERLAY_GFX_REVERSE
633
+
567 634
 #endif // DOGLCD
568 635
 
569 636
 // @section safety
@@ -590,31 +657,18 @@
590 657
  */
591 658
 //#define BABYSTEPPING
592 659
 #if ENABLED(BABYSTEPPING)
593
-  #define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
594
-  #define BABYSTEP_INVERT_Z false  // Change if Z babysteps should go the other way
595
-  #define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
596
-  //#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
660
+  //#define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
661
+  #define BABYSTEP_INVERT_Z false    // Change if Z babysteps should go the other way
662
+  #define BABYSTEP_MULTIPLICATOR 1   // Babysteps are very small. Increase for faster motion.
663
+  //#define BABYSTEP_ZPROBE_OFFSET   // Enable to combine M851 and Babystepping
597 664
   //#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
598 665
   #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
599 666
                                         // Note: Extra time may be added to mitigate controller latency.
667
+  //#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
600 668
 #endif
601 669
 
602 670
 // @section extruder
603 671
 
604
-// extruder advance constant (s2/mm3)
605
-//
606
-// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
607
-//
608
-// Hooke's law says:    force = k * distance
609
-// Bernoulli's principle says:  v ^ 2 / 2 + g . h + pressure / density = constant
610
-// so: v ^ 2 is proportional to number of steps we advance the extruder
611
-//#define ADVANCE
612
-
613
-#if ENABLED(ADVANCE)
614
-  #define EXTRUDER_ADVANCE_K .0
615
-  #define D_FILAMENT 2.85
616
-#endif
617
-
618 672
 /**
619 673
  * Implementation of linear pressure control
620 674
  *
@@ -648,7 +702,7 @@
648 702
    *
649 703
    * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
650 704
    *
651
-   * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode.
705
+   * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
652 706
    * Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
653 707
    */
654 708
   #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
@@ -657,19 +711,18 @@
657 711
 
658 712
 // @section leveling
659 713
 
660
-// Default mesh area is an area with an inset margin on the print area.
661
-// Below are the macros that are used to define the borders for the mesh area,
662
-// made available here for specialized needs, ie dual extruder setup.
663
-#if ENABLED(MESH_BED_LEVELING)
664
-  #define MESH_MIN_X (X_MIN_POS + MESH_INSET)
665
-  #define MESH_MAX_X (X_MAX_POS - (MESH_INSET))
666
-  #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET)
667
-  #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET))
668
-#elif ENABLED(AUTO_BED_LEVELING_UBL)
669
-  #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET)
670
-  #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET))
671
-  #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET)
672
-  #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET))
714
+#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
715
+  #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
716
+#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
717
+  #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
718
+#endif
719
+
720
+#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
721
+  // Override the mesh area if the automatic (max) area is too large
722
+  //#define MESH_MIN_X MESH_INSET
723
+  //#define MESH_MIN_Y MESH_INSET
724
+  //#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
725
+  //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
673 726
 #endif
674 727
 
675 728
 // @section extras
@@ -689,7 +742,7 @@
689 742
 //#define BEZIER_CURVE_SUPPORT
690 743
 
691 744
 // G38.2 and G38.3 Probe Target
692
-// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
745
+// Set MULTIPLE_PROBING if you want G38 to double touch
693 746
 //#define G38_PROBE_TARGET
694 747
 #if ENABLED(G38_PROBE_TARGET)
695 748
   #define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
@@ -714,7 +767,7 @@
714 767
 // @section hidden
715 768
 
716 769
 // The number of linear motions that can be in the plan at any give time.
717
-// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
770
+// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
718 771
 #if ENABLED(SDSUPPORT)
719 772
   #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
720 773
 #else
@@ -727,7 +780,7 @@
727 780
 #define MAX_CMD_SIZE 96
728 781
 #define BUFSIZE 4
729 782
 
730
-// Transfer Buffer Size
783
+// Transmission to Host Buffer Size
731 784
 // To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0.
732 785
 // To buffer a simple "ok" you need 4 bytes.
733 786
 // For ADVANCED_OK (M105) you need 32 bytes.
@@ -736,6 +789,28 @@
736 789
 // :[0, 2, 4, 8, 16, 32, 64, 128, 256]
737 790
 #define TX_BUFFER_SIZE 64
738 791
 
792
+// Host Receive Buffer Size
793
+// Without XON/XOFF flow control (see SERIAL_XON_XOFF below) 32 bytes should be enough.
794
+// To use flow control, set this buffer size to at least 1024 bytes.
795
+// :[0, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048]
796
+//#define RX_BUFFER_SIZE 1024
797
+
798
+#if RX_BUFFER_SIZE >= 1024
799
+  // Enable to have the controller send XON/XOFF control characters to
800
+  // the host to signal the RX buffer is becoming full.
801
+  //#define SERIAL_XON_XOFF
802
+#endif
803
+
804
+#if ENABLED(SDSUPPORT)
805
+  // Enable this option to collect and display the maximum
806
+  // RX queue usage after transferring a file to SD.
807
+  //#define SERIAL_STATS_MAX_RX_QUEUED
808
+
809
+  // Enable this option to collect and display the number
810
+  // of dropped bytes after a file transfer to SD.
811
+  //#define SERIAL_STATS_DROPPED_RX
812
+#endif
813
+
739 814
 // Enable an emergency-command parser to intercept certain commands as they
740 815
 // enter the serial receive buffer, so they cannot be blocked.
741 816
 // Currently handles M108, M112, M410
@@ -751,27 +826,47 @@
751 826
 // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary.
752 827
 //#define ADVANCED_OK
753 828
 
754
-// @section fwretract
755
-
756
-// Firmware based and LCD controlled retract
757
-// M207 and M208 can be used to define parameters for the retraction.
758
-// The retraction can be called by the slicer using G10 and G11
759
-// until then, intended retractions can be detected by moves that only extrude and the direction.
760
-// the moves are than replaced by the firmware controlled ones.
829
+// @section extras
761 830
 
762
-//#define FWRETRACT  //ONLY PARTIALLY TESTED
831
+/**
832
+ * Firmware-based and LCD-controlled retract
833
+ *
834
+ * Add G10 / G11 commands for automatic firmware-based retract / recover.
835
+ * Use M207 and M208 to define parameters for retract / recover.
836
+ *
837
+ * Use M209 to enable or disable auto-retract.
838
+ * With auto-retract enabled, all G1 E moves within the set range
839
+ * will be converted to firmware-based retract/recover moves.
840
+ *
841
+ * Be sure to turn off auto-retract during filament change.
842
+ *
843
+ * Note that M207 / M208 / M209 settings are saved to EEPROM.
844
+ *
845
+ */
846
+//#define FWRETRACT  // ONLY PARTIALLY TESTED
763 847
 #if ENABLED(FWRETRACT)
764
-  #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
765
-  #define RETRACT_LENGTH 3               //default retract length (positive mm)
766
-  #define RETRACT_LENGTH_SWAP 13         //default swap retract length (positive mm), for extruder change
767
-  #define RETRACT_FEEDRATE 45            //default feedrate for retracting (mm/s)
768
-  #define RETRACT_ZLIFT 0                //default retract Z-lift
769
-  #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
770
-  #define RETRACT_RECOVER_LENGTH_SWAP 0  //default additional swap recover length (mm, added to retract length when recovering from extruder change)
771
-  #define RETRACT_RECOVER_FEEDRATE 8     //default feedrate for recovering from retraction (mm/s)
848
+  #define MIN_AUTORETRACT 0.1             // When auto-retract is on, convert E moves of this length and over
849
+  #define MAX_AUTORETRACT 10.0            // Upper limit for auto-retract conversion
850
+  #define RETRACT_LENGTH 3                // Default retract length (positive mm)
851
+  #define RETRACT_LENGTH_SWAP 13          // Default swap retract length (positive mm), for extruder change
852
+  #define RETRACT_FEEDRATE 45             // Default feedrate for retracting (mm/s)
853
+  #define RETRACT_ZLIFT 0                 // Default retract Z-lift
854
+  #define RETRACT_RECOVER_LENGTH 0        // Default additional recover length (mm, added to retract length when recovering)
855
+  #define RETRACT_RECOVER_LENGTH_SWAP 0   // Default additional swap recover length (mm, added to retract length when recovering from extruder change)
856
+  #define RETRACT_RECOVER_FEEDRATE 8      // Default feedrate for recovering from retraction (mm/s)
857
+  #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
772 858
 #endif
773 859
 
774 860
 /**
861
+ * Extra Fan Speed
862
+ * Adds a secondary fan speed for each print-cooling fan.
863
+ *   'M106 P<fan> T3-255' : Set a secondary speed for <fan>
864
+ *   'M106 P<fan> T2'     : Use the set secondary speed
865
+ *   'M106 P<fan> T1'     : Restore the previous fan speed
866
+ */
867
+//#define EXTRA_FAN_SPEED
868
+
869
+/**
775 870
  * Advanced Pause
776 871
  * Experimental feature for filament change support and for parking the nozzle when paused.
777 872
  * Adds the GCode M600 for initiating filament change.
@@ -881,7 +976,7 @@
881 976
 
882 977
 #endif
883 978
 
884
-// @section TMC2130
979
+// @section TMC2130, TMC2208
885 980
 
886 981
 /**
887 982
  * Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
@@ -895,7 +990,19 @@
895 990
  */
896 991
 //#define HAVE_TMC2130
897 992
 
898
-#if ENABLED(HAVE_TMC2130)
993
+/**
994
+ * Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
995
+ * Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
996
+ * To use the reading capabilities, also connect #_SERIAL_RX_PIN
997
+ * to #_SERIAL_TX_PIN with a 1K resistor.
998
+ * The drivers can also be used with hardware serial.
999
+ *
1000
+ * You'll also need the TMC2208Stepper Arduino library
1001
+ * (https://github.com/teemuatlut/TMC2208Stepper).
1002
+ */
1003
+//#define HAVE_TMC2208
1004
+
1005
+#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
899 1006
 
900 1007
   // CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
901 1008
   //#define X_IS_TMC2130
@@ -910,46 +1017,58 @@
910 1017
   //#define E3_IS_TMC2130
911 1018
   //#define E4_IS_TMC2130
912 1019
 
1020
+  //#define X_IS_TMC2208
1021
+  //#define X2_IS_TMC2208
1022
+  //#define Y_IS_TMC2208
1023
+  //#define Y2_IS_TMC2208
1024
+  //#define Z_IS_TMC2208
1025
+  //#define Z2_IS_TMC2208
1026
+  //#define E0_IS_TMC2208
1027
+  //#define E1_IS_TMC2208
1028
+  //#define E2_IS_TMC2208
1029
+  //#define E3_IS_TMC2208
1030
+  //#define E4_IS_TMC2208
1031
+
913 1032
   /**
914 1033
    * Stepper driver settings
915 1034
    */
916 1035
 
917 1036
   #define R_SENSE           0.11  // R_sense resistor for SilentStepStick2130
918 1037
   #define HOLD_MULTIPLIER    0.5  // Scales down the holding current from run current
919
-  #define INTERPOLATE          1  // Interpolate X/Y/Z_MICROSTEPS to 256
1038
+  #define INTERPOLATE       true  // Interpolate X/Y/Z_MICROSTEPS to 256
920 1039
 
921
-  #define X_CURRENT         1000  // rms current in mA. Multiply by 1.41 for peak current.
1040
+  #define X_CURRENT          800  // rms current in mA. Multiply by 1.41 for peak current.
922 1041
   #define X_MICROSTEPS        16  // 0..256
923 1042
 
924
-  #define Y_CURRENT         1000
1043
+  #define Y_CURRENT          800
925 1044
   #define Y_MICROSTEPS        16
926 1045
 
927
-  #define Z_CURRENT         1000
1046
+  #define Z_CURRENT          800
928 1047
   #define Z_MICROSTEPS        16
929 1048
 
930
-  //#define X2_CURRENT      1000
931
-  //#define X2_MICROSTEPS     16
1049
+  #define X2_CURRENT         800
1050
+  #define X2_MICROSTEPS       16
932 1051
 
933
-  //#define Y2_CURRENT      1000
934
-  //#define Y2_MICROSTEPS     16
1052
+  #define Y2_CURRENT         800
1053
+  #define Y2_MICROSTEPS       16
935 1054
 
936
-  //#define Z2_CURRENT      1000
937
-  //#define Z2_MICROSTEPS     16
1055
+  #define Z2_CURRENT         800
1056
+  #define Z2_MICROSTEPS       16
938 1057
 
939
-  //#define E0_CURRENT      1000
940
-  //#define E0_MICROSTEPS     16
1058
+  #define E0_CURRENT         800
1059
+  #define E0_MICROSTEPS       16
941 1060
 
942
-  //#define E1_CURRENT      1000
943
-  //#define E1_MICROSTEPS     16
1061
+  #define E1_CURRENT         800
1062
+  #define E1_MICROSTEPS       16
944 1063
 
945
-  //#define E2_CURRENT      1000
946
-  //#define E2_MICROSTEPS     16
1064
+  #define E2_CURRENT         800
1065
+  #define E2_MICROSTEPS       16
947 1066
 
948
-  //#define E3_CURRENT      1000
949
-  //#define E3_MICROSTEPS     16
1067
+  #define E3_CURRENT         800
1068
+  #define E3_MICROSTEPS       16
950 1069
 
951
-  //#define E4_CURRENT      1000
952
-  //#define E4_MICROSTEPS     16
1070
+  #define E4_CURRENT         800
1071
+  #define E4_MICROSTEPS       16
953 1072
 
954 1073
   /**
955 1074
    * Use Trinamic's ultra quiet stepping mode.
@@ -958,24 +1077,22 @@
958 1077
   #define STEALTHCHOP
959 1078
 
960 1079
   /**
961
-   * Let Marlin automatically control stepper current.
962
-   * This is still an experimental feature.
963
-   * Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
964
-   * then decrease current by CURRENT_STEP until temperature prewarn is cleared.
965
-   * Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
1080
+   * Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
1081
+   * like overtemperature and short to ground. TMC2208 requires hardware serial.
1082
+   * In the case of overtemperature Marlin can decrease the driver current until error condition clears.
1083
+   * Other detected conditions can be used to stop the current print.
966 1084
    * Relevant g-codes:
967 1085
    * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
968
-   * M906 S1 - Start adjusting current
969
-   * M906 S0 - Stop adjusting current
970 1086
    * M911 - Report stepper driver overtemperature pre-warn condition.
971 1087
    * M912 - Clear stepper driver overtemperature pre-warn condition flag.
1088
+   * M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
972 1089
    */
973
-  //#define AUTOMATIC_CURRENT_CONTROL
1090
+  //#define MONITOR_DRIVER_STATUS
974 1091
 
975
-  #if ENABLED(AUTOMATIC_CURRENT_CONTROL)
976
-    #define CURRENT_STEP          50  // [mA]
977
-    #define AUTO_ADJUST_MAX     1300  // [mA], 1300mA_rms = 1840mA_peak
1092
+  #if ENABLED(MONITOR_DRIVER_STATUS)
1093
+    #define CURRENT_STEP_DOWN     50  // [mA]
978 1094
     #define REPORT_CURRENT_CHANGE
1095
+    #define STOP_ON_ERROR
979 1096
   #endif
980 1097
 
981 1098
   /**
@@ -990,8 +1107,8 @@
990 1107
   #define X2_HYBRID_THRESHOLD    100
991 1108
   #define Y_HYBRID_THRESHOLD     100
992 1109
   #define Y2_HYBRID_THRESHOLD    100
993
-  #define Z_HYBRID_THRESHOLD       4
994
-  #define Z2_HYBRID_THRESHOLD      4
1110
+  #define Z_HYBRID_THRESHOLD       3
1111
+  #define Z2_HYBRID_THRESHOLD      3
995 1112
   #define E0_HYBRID_THRESHOLD     30
996 1113
   #define E1_HYBRID_THRESHOLD     30
997 1114
   #define E2_HYBRID_THRESHOLD     30
@@ -1001,7 +1118,7 @@
1001 1118
   /**
1002 1119
    * Use stallGuard2 to sense an obstacle and trigger an endstop.
1003 1120
    * You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
1004
-   * If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
1121
+   * X and Y homing will always be done in spreadCycle mode.
1005 1122
    *
1006 1123
    * X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
1007 1124
    * Higher values make the system LESS sensitive.
@@ -1010,27 +1127,34 @@
1010 1127
    * It is advised to set X/Y_HOME_BUMP_MM to 0.
1011 1128
    * M914 X/Y to live tune the setting
1012 1129
    */
1013
-  //#define SENSORLESS_HOMING
1130
+  //#define SENSORLESS_HOMING // TMC2130 only
1014 1131
 
1015 1132
   #if ENABLED(SENSORLESS_HOMING)
1016
-    #define X_HOMING_SENSITIVITY  19
1017
-    #define Y_HOMING_SENSITIVITY  19
1133
+    #define X_HOMING_SENSITIVITY  8
1134
+    #define Y_HOMING_SENSITIVITY  8
1018 1135
   #endif
1019 1136
 
1020 1137
   /**
1138
+   * Enable M122 debugging command for TMC stepper drivers.
1139
+   * M122 S0/1 will enable continous reporting.
1140
+   */
1141
+  //#define TMC_DEBUG
1142
+
1143
+  /**
1021 1144
    * You can set your own advanced settings by filling in predefined functions.
1022 1145
    * A list of available functions can be found on the library github page
1023 1146
    * https://github.com/teemuatlut/TMC2130Stepper
1147
+   * https://github.com/teemuatlut/TMC2208Stepper
1024 1148
    *
1025 1149
    * Example:
1026
-   * #define TMC2130_ADV() { \
1150
+   * #define TMC_ADV() { \
1027 1151
    *   stepperX.diag0_temp_prewarn(1); \
1028
-   *   stepperX.interpolate(0); \
1152
+   *   stepperY.interpolate(0); \
1029 1153
    * }
1030 1154
    */
1031
-  #define  TMC2130_ADV() {  }
1155
+  #define  TMC_ADV() {  }
1032 1156
 
1033
-#endif // HAVE_TMC2130
1157
+#endif // TMC2130 || TMC2208
1034 1158
 
1035 1159
 // @section L6470
1036 1160
 
@@ -1195,6 +1319,48 @@
1195 1319
 #endif
1196 1320
 
1197 1321
 /**
1322
+ * Filament Width Sensor
1323
+ *
1324
+ * Measures the filament width in real-time and adjusts
1325
+ * flow rate to compensate for any irregularities.
1326
+ *
1327
+ * Also allows the measured filament diameter to set the
1328
+ * extrusion rate, so the slicer only has to specify the
1329
+ * volume.
1330
+ *
1331
+ * Only a single extruder is supported at this time.
1332
+ *
1333
+ *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1334
+ *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1335
+ * 301 RAMBO       : Analog input 3
1336
+ *
1337
+ * Note: May require analog pins to be defined for other boards.
1338
+ */
1339
+//#define FILAMENT_WIDTH_SENSOR
1340
+
1341
+#if ENABLED(FILAMENT_WIDTH_SENSOR)
1342
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
1343
+  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1344
+
1345
+  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1346
+  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1347
+  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1348
+
1349
+  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1350
+
1351
+  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1352
+  //#define FILAMENT_LCD_DISPLAY
1353
+#endif
1354
+
1355
+/**
1356
+ * CNC Coordinate Systems
1357
+ *
1358
+ * Enables G53 and G54-G59.3 commands to select coordinate systems
1359
+ * and G92.1 to reset the workspace to native machine space.
1360
+ */
1361
+//#define CNC_COORDINATE_SYSTEMS
1362
+
1363
+/**
1198 1364
  * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
1199 1365
  */
1200 1366
 //#define PINS_DEBUGGING
@@ -1247,6 +1413,8 @@
1247 1413
 //#define CUSTOM_USER_MENUS
1248 1414
 #if ENABLED(CUSTOM_USER_MENUS)
1249 1415
   #define USER_SCRIPT_DONE "M117 User Script Done"
1416
+  #define USER_SCRIPT_AUDIBLE_FEEDBACK
1417
+  //#define USER_SCRIPT_RETURN  // Return to status screen after a script
1250 1418
 
1251 1419
   #define USER_DESC_1 "Home & UBL Info"
1252 1420
   #define USER_GCODE_1 "G28\nG29 W"
@@ -1274,6 +1442,7 @@
1274 1442
 //===========================================================================
1275 1443
 //====================== I2C Position Encoder Settings ======================
1276 1444
 //===========================================================================
1445
+
1277 1446
 /**
1278 1447
  *  I2C position encoders for closed loop control.
1279 1448
  *  Developed by Chris Barr at Aus3D.
@@ -1354,4 +1523,45 @@
1354 1523
 
1355 1524
 #endif // I2C_POSITION_ENCODERS
1356 1525
 
1526
+/**
1527
+ * MAX7219 Debug Matrix
1528
+ *
1529
+ * Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
1530
+ * display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
1531
+ *
1532
+ * Fully assembled MAX7219 boards can be found on the internet for under $2(US).
1533
+ * For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
1534
+ */
1535
+//#define MAX7219_DEBUG
1536
+#if ENABLED(MAX7219_DEBUG)
1537
+  #define MAX7219_CLK_PIN   64  // 77 on Re-ARM       // Configuration of the 3 pins to control the display
1538
+  #define MAX7219_DIN_PIN   57  // 78 on Re-ARM
1539
+  #define MAX7219_LOAD_PIN  44  // 79 on Re-ARM
1540
+
1541
+  /**
1542
+   * Sample debug features
1543
+   * If you add more debug displays, be careful to avoid conflicts!
1544
+   */
1545
+  #define MAX7219_DEBUG_PRINTER_ALIVE    // Blink corner LED of 8x8 matrix to show that the firmware is functioning
1546
+  #define MAX7219_DEBUG_STEPPER_HEAD  3  // Show the stepper queue head position on this and the next LED matrix row
1547
+  #define MAX7219_DEBUG_STEPPER_TAIL  5  // Show the stepper queue tail position on this and the next LED matrix row
1548
+
1549
+  #define MAX7219_DEBUG_STEPPER_QUEUE 0  // Show the current stepper queue depth on this and the next LED matrix row
1550
+                                         // If you experience stuttering, reboots, etc. this option can reveal how
1551
+                                         // tweaks made to the configuration are affecting the printer in real-time.
1552
+#endif
1553
+
1554
+/**
1555
+ * NanoDLP Sync support
1556
+ *
1557
+ * Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
1558
+ * string to enable synchronization with DLP projector exposure. This change will allow to use
1559
+ * [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
1560
+ */
1561
+//#define NANODLP_Z_SYNC
1562
+#if ENABLED(NANODLP_Z_SYNC)
1563
+  //#define NANODLP_ALL_AXIS  // Enables "Z_move_comp" output on any axis move.
1564
+                              // Default behaviour is limited to Z axis only.
1565
+#endif
1566
+
1357 1567
 #endif // CONFIGURATION_ADV_H

Marlin/example_configurations/K8200/Configuration.h → Marlin/example_configurations/Velleman/K8200/Configuration.h 파일 보기

@@ -37,7 +37,7 @@
37 37
  */
38 38
 #ifndef CONFIGURATION_H
39 39
 #define CONFIGURATION_H
40
-#define CONFIGURATION_H_VERSION 010100
40
+#define CONFIGURATION_H_VERSION 010107
41 41
 
42 42
 /**
43 43
  * Sample configuration file for Vellemann K8200
@@ -123,8 +123,9 @@
123 123
  *
124 124
  * 250000 works in most cases, but you might try a lower speed if
125 125
  * you commonly experience drop-outs during host printing.
126
+ * You may try up to 1000000 to speed up SD file transfer.
126 127
  *
127
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
128
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
128 129
  */
129 130
 #define BAUDRATE 250000
130 131
 
@@ -155,6 +156,9 @@
155 156
 // :[1, 2, 3, 4, 5]
156 157
 #define EXTRUDERS 1
157 158
 
159
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
160
+#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
161
+
158 162
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
159 163
 //#define SINGLENOZZLE
160 164
 
@@ -181,7 +185,10 @@
181 185
 //#define SWITCHING_EXTRUDER
182 186
 #if ENABLED(SWITCHING_EXTRUDER)
183 187
   #define SWITCHING_EXTRUDER_SERVO_NR 0
184
-  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1
188
+  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3]
189
+  #if EXTRUDERS > 3
190
+    #define SWITCHING_EXTRUDER_E23_SERVO_NR 1
191
+  #endif
185 192
 #endif
186 193
 
187 194
 // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles
@@ -193,6 +200,21 @@
193 200
 #endif
194 201
 
195 202
 /**
203
+ * Two separate X-carriages with extruders that connect to a moving part
204
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
205
+ */
206
+//#define PARKING_EXTRUDER
207
+#if ENABLED(PARKING_EXTRUDER)
208
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
209
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
210
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
211
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
212
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
213
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
214
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
215
+#endif
216
+
217
+/**
196 218
  * "Mixing Extruder"
197 219
  *   - Adds a new code, M165, to set the current mix factors.
198 220
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -337,8 +359,9 @@
337 359
 
338 360
 // Comment the following line to disable PID and enable bang-bang.
339 361
 #define PIDTEMP
340
-#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
341
-#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
362
+#define BANG_MAX 255     // Limits current to nozzle while in bang-bang mode; 255=full current
363
+#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
364
+#define PID_K1 0.95      // Smoothing factor within the PID
342 365
 #if ENABLED(PIDTEMP)
343 366
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
344 367
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -348,7 +371,6 @@
348 371
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
349 372
   #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
350 373
                                   // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
351
-  #define K1 0.95 //smoothing factor within the PID
352 374
 
353 375
   // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
354 376
 
@@ -439,12 +461,13 @@
439 461
 //===========================================================================
440 462
 
441 463
 /**
442
- * Thermal Protection protects your printer from damage and fire if a
443
- * thermistor falls out or temperature sensors fail in any way.
464
+ * Thermal Protection provides additional protection to your printer from damage
465
+ * and fire. Marlin always includes safe min and max temperature ranges which
466
+ * protect against a broken or disconnected thermistor wire.
444 467
  *
445
- * The issue: If a thermistor falls out or a temperature sensor fails,
446
- * Marlin can no longer sense the actual temperature. Since a disconnected
447
- * thermistor reads as a low temperature, the firmware will keep the heater on.
468
+ * The issue: If a thermistor falls out, it will report the much lower
469
+ * temperature of the air in the room, and the the firmware will keep
470
+ * the heater on.
448 471
  *
449 472
  * If you get "Thermal Runaway" or "Heating failed" errors the
450 473
  * details can be tuned in Configuration_adv.h
@@ -583,7 +606,7 @@
583 606
 // @section probes
584 607
 
585 608
 //
586
-// See http://marlinfw.org/configuration/probes.html
609
+// See http://marlinfw.org/docs/configuration/probes.html
587 610
 //
588 611
 
589 612
 /**
@@ -649,14 +672,15 @@
649 672
 #endif
650 673
 
651 674
 /**
652
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
653
- * options selected below - will be disabled during probing so as to minimize
654
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
655
- * in current flowing through the wires).  This is likely most useful to users of the
656
- * BLTouch probe, but may also help those with inductive or other probe types.
675
+ * Enable one or more of the following if probing seems unreliable.
676
+ * Heaters and/or fans can be disabled during probing to minimize electrical
677
+ * noise. A delay can also be added to allow noise and vibration to settle.
678
+ * These options are most useful for the BLTouch probe, but may also improve
679
+ * readings with inductive probes and piezo sensors.
657 680
  */
658 681
 //#define PROBING_HEATERS_OFF       // Turn heaters off when probing
659 682
 //#define PROBING_FANS_OFF          // Turn fans off when probing
683
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
660 684
 
661 685
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
662 686
 //#define SOLENOID_PROBE
@@ -695,14 +719,16 @@
695 719
 // X and Y axis travel speed (mm/m) between probes
696 720
 #define XY_PROBE_SPEED 8000
697 721
 
698
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
722
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
699 723
 #define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
700 724
 
701 725
 // Speed for the "accurate" probe of each point
702 726
 #define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
703 727
 
704
-// Use double touch for probing
705
-//#define PROBE_DOUBLE_TOUCH
728
+// The number of probes to perform at each point.
729
+//   Set to 2 for a fast/slow probe, using the second probe result.
730
+//   Set to 3 or more for slow probes, averaging the results.
731
+//#define MULTIPLE_PROBING 2
706 732
 
707 733
 /**
708 734
  * Z probes require clearance when deploying, stowing, and moving between
@@ -768,6 +794,9 @@
768 794
 #define INVERT_E4_DIR true
769 795
 
770 796
 // @section homing
797
+
798
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
799
+
771 800
 // K8200: it is usual to have clamps for the glass plate on the heatbed
772 801
 #define Z_HOMING_HEIGHT 4   // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
773 802
                             // Be sure you have this distance over your Z_MAX_POS in case.
@@ -780,18 +809,42 @@
780 809
 
781 810
 // @section machine
782 811
 
783
-// Travel limits after homing (units are in mm)
812
+// The size of the print bed
813
+#define X_BED_SIZE 200
814
+#define Y_BED_SIZE 200
815
+
816
+// Travel limits (mm) after homing, corresponding to endstop positions.
784 817
 #define X_MIN_POS 0
785 818
 #define Y_MIN_POS 0
786 819
 #define Z_MIN_POS 0
787
-#define X_MAX_POS 200
788
-#define Y_MAX_POS 200
820
+#define X_MAX_POS X_BED_SIZE
821
+#define Y_MAX_POS Y_BED_SIZE
789 822
 #define Z_MAX_POS 200
790 823
 
791
-// If enabled, axes won't move below MIN_POS in response to movement commands.
824
+/**
825
+ * Software Endstops
826
+ *
827
+ * - Prevent moves outside the set machine bounds.
828
+ * - Individual axes can be disabled, if desired.
829
+ * - X and Y only apply to Cartesian robots.
830
+ * - Use 'M211' to set software endstops on/off or report current state
831
+ */
832
+
833
+// Min software endstops curtail movement below minimum coordinate bounds
792 834
 #define MIN_SOFTWARE_ENDSTOPS
793
-// If enabled, axes won't move above MAX_POS in response to movement commands.
835
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
836
+  #define MIN_SOFTWARE_ENDSTOP_X
837
+  #define MIN_SOFTWARE_ENDSTOP_Y
838
+  #define MIN_SOFTWARE_ENDSTOP_Z
839
+#endif
840
+
841
+// Max software endstops curtail movement above maximum coordinate bounds
794 842
 #define MAX_SOFTWARE_ENDSTOPS
843
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
844
+  #define MAX_SOFTWARE_ENDSTOP_X
845
+  #define MAX_SOFTWARE_ENDSTOP_Y
846
+  #define MAX_SOFTWARE_ENDSTOP_Z
847
+#endif
795 848
 
796 849
 /**
797 850
  * Filament Runout Sensor
@@ -811,7 +864,7 @@
811 864
 //===========================================================================
812 865
 //=============================== Bed Leveling ==============================
813 866
 //===========================================================================
814
-// @section bedlevel
867
+// @section calibrate
815 868
 
816 869
 /**
817 870
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -837,12 +890,7 @@
837 890
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
838 891
  *   A comprehensive bed leveling system combining the features and benefits
839 892
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
840
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
841
- *   for Cartesian Printers. That said, it was primarily designed to correct
842
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
843
- *   please post an issue if something doesn't work correctly. Initially,
844
- *   you will need to set a reduced bed size so you have a rectangular area
845
- *   to test on.
893
+ *   Validation and Mesh Editing systems.
846 894
  *
847 895
  * - MESH_BED_LEVELING
848 896
  *   Probe a grid manually
@@ -869,6 +917,24 @@
869 917
   // at which point movement will be level to the machine's XY plane.
870 918
   // The height can be set with M420 Z<height>
871 919
   #define ENABLE_LEVELING_FADE_HEIGHT
920
+
921
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
922
+  // split up moves into short segments like a Delta. This follows the
923
+  // contours of the bed more closely than edge-to-edge straight moves.
924
+  #define SEGMENT_LEVELED_MOVES
925
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
926
+
927
+  /**
928
+   * Enable the G26 Mesh Validation Pattern tool.
929
+   */
930
+  //#define G26_MESH_VALIDATION   // Enable G26 mesh validation
931
+  #if ENABLED(G26_MESH_VALIDATION)
932
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
933
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
934
+    #define MESH_TEST_HOTEND_TEMP   205.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
935
+    #define MESH_TEST_BED_TEMP       60.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
936
+  #endif
937
+
872 938
 #endif
873 939
 
874 940
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -924,7 +990,9 @@
924 990
   //========================= Unified Bed Leveling ============================
925 991
   //===========================================================================
926 992
 
927
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
993
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
994
+
995
+  #define MESH_INSET 1              // Mesh inset margin on print area
928 996
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
929 997
   #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
930 998
 
@@ -935,8 +1003,8 @@
935 1003
   #define UBL_PROBE_PT_3_X 180
936 1004
   #define UBL_PROBE_PT_3_Y 20
937 1005
 
938
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
939 1006
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
1007
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
940 1008
 
941 1009
 #elif ENABLED(MESH_BED_LEVELING)
942 1010
 
@@ -963,6 +1031,9 @@
963 1031
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
964 1032
 #endif
965 1033
 
1034
+// Add a menu item to move between bed corners for manual bed adjustment
1035
+//#define LEVEL_BED_CORNERS
1036
+
966 1037
 /**
967 1038
  * Commands to execute at the end of G29 probing.
968 1039
  * Useful to retract or move the Z probe out of the way.
@@ -993,14 +1064,71 @@
993 1064
 //#define Z_SAFE_HOMING
994 1065
 
995 1066
 #if ENABLED(Z_SAFE_HOMING)
996
-  #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
997
-  #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
1067
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1068
+  #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2)    // Y point for Z homing when homing all axes (G28).
998 1069
 #endif
999 1070
 
1000 1071
 // Homing speeds (mm/m)
1001 1072
 #define HOMING_FEEDRATE_XY (50*60)
1002 1073
 #define HOMING_FEEDRATE_Z  (4*60)
1003 1074
 
1075
+// @section calibrate
1076
+
1077
+/**
1078
+ * Bed Skew Compensation
1079
+ *
1080
+ * This feature corrects for misalignment in the XYZ axes.
1081
+ *
1082
+ * Take the following steps to get the bed skew in the XY plane:
1083
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1084
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1085
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1086
+ *  4. For XY_SIDE_AD measure the edge A to D
1087
+ *
1088
+ * Marlin automatically computes skew factors from these measurements.
1089
+ * Skew factors may also be computed and set manually:
1090
+ *
1091
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1092
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1093
+ *
1094
+ * If desired, follow the same procedure for XZ and YZ.
1095
+ * Use these diagrams for reference:
1096
+ *
1097
+ *    Y                     Z                     Z
1098
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1099
+ *    |    /       /        |    /       /        |    /       /
1100
+ *    |   /       /         |   /       /         |   /       /
1101
+ *    |  A-------D          |  A-------D          |  A-------D
1102
+ *    +-------------->X     +-------------->X     +-------------->Y
1103
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1104
+ */
1105
+//#define SKEW_CORRECTION
1106
+
1107
+#if ENABLED(SKEW_CORRECTION)
1108
+  // Input all length measurements here:
1109
+  #define XY_DIAG_AC 282.8427124746
1110
+  #define XY_DIAG_BD 282.8427124746
1111
+  #define XY_SIDE_AD 200
1112
+
1113
+  // Or, set the default skew factors directly here
1114
+  // to override the above measurements:
1115
+  #define XY_SKEW_FACTOR 0.0
1116
+
1117
+  //#define SKEW_CORRECTION_FOR_Z
1118
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1119
+    #define XZ_DIAG_AC 282.8427124746
1120
+    #define XZ_DIAG_BD 282.8427124746
1121
+    #define YZ_DIAG_AC 282.8427124746
1122
+    #define YZ_DIAG_BD 282.8427124746
1123
+    #define YZ_SIDE_AD 200
1124
+    #define XZ_SKEW_FACTOR 0.0
1125
+    #define YZ_SKEW_FACTOR 0.0
1126
+  #endif
1127
+
1128
+  // Enable this option for M852 to set skew at runtime
1129
+  //#define SKEW_CORRECTION_GCODE
1130
+#endif
1131
+
1004 1132
 //=============================================================================
1005 1133
 //============================= Additional Features ===========================
1006 1134
 //=============================================================================
@@ -1027,11 +1155,12 @@
1027 1155
 //
1028 1156
 #define HOST_KEEPALIVE_FEATURE        // Disable this if your host doesn't like keepalive messages
1029 1157
 #define DEFAULT_KEEPALIVE_INTERVAL 2  // Number of seconds between "busy" messages. Set with M113.
1158
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
1030 1159
 
1031 1160
 //
1032 1161
 // M100 Free Memory Watcher
1033 1162
 //
1034
-//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1163
+//#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
1035 1164
 
1036 1165
 //
1037 1166
 // G20/G21 Inch mode support
@@ -1179,11 +1308,11 @@
1179 1308
  *
1180 1309
  * Select the language to display on the LCD. These languages are available:
1181 1310
  *
1182
- *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
1183
- *    it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
1184
- *    zh_CN, zh_TW, test
1311
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1312
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1313
+ *    tr, uk, zh_CN, zh_TW, test
1185 1314
  *
1186
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1315
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1187 1316
  */
1188 1317
 #define LCD_LANGUAGE en
1189 1318
 
@@ -1205,7 +1334,7 @@
1205 1334
  *  - Click the controller to view the LCD menu
1206 1335
  *  - The LCD will display Japanese, Western, or Cyrillic text
1207 1336
  *
1208
- * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1337
+ * See http://marlinfw.org/docs/development/lcd_language.html
1209 1338
  *
1210 1339
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1211 1340
  */
@@ -1311,8 +1440,8 @@
1311 1440
 // Note: Test audio output with the G-Code:
1312 1441
 //  M300 S<frequency Hz> P<duration ms>
1313 1442
 //
1314
-//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
1315
-//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
1443
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
1444
+//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
1316 1445
 
1317 1446
 //
1318 1447
 // CONTROLLER TYPE: Standard
@@ -1420,11 +1549,13 @@
1420 1549
 //#define CARTESIO_UI
1421 1550
 
1422 1551
 //
1423
-// ANET_10 Controller supported displays.
1552
+// ANET and Tronxy Controller supported displays.
1424 1553
 //
1425
-//#define ANET_KEYPAD_LCD         // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1554
+//#define ZONESTAR_LCD            // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1426 1555
                                   // This LCD is known to be susceptible to electrical interference
1427 1556
                                   // which scrambles the display.  Pressing any button clears it up.
1557
+                                  // This is a LCD2004 display with 5 analog buttons.
1558
+
1428 1559
 //#define ANET_FULL_GRAPHICS_LCD  // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1429 1560
                                   // A clone of the RepRapDiscount full graphics display but with
1430 1561
                                   // different pins/wiring (see pins_ANET_10.h).
@@ -1484,11 +1615,6 @@
1484 1615
 //#define U8GLIB_SSD1306
1485 1616
 
1486 1617
 //
1487
-// TinyBoy2 128x64 OLED / Encoder Panel
1488
-//
1489
-//#define OLED_PANEL_TINYBOY2
1490
-
1491
-//
1492 1618
 // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules
1493 1619
 //
1494 1620
 //#define SAV_3DGLCD
@@ -1510,6 +1636,35 @@
1510 1636
 //
1511 1637
 //#define OLED_PANEL_TINYBOY2
1512 1638
 
1639
+//
1640
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1641
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1642
+//
1643
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1644
+
1645
+//
1646
+// MKS MINI12864 with graphic controller and SD support
1647
+// http://reprap.org/wiki/MKS_MINI_12864
1648
+//
1649
+//#define MKS_MINI_12864
1650
+
1651
+//
1652
+// Factory display for Creality CR-10
1653
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1654
+//
1655
+// This is RAMPS-compatible using a single 10-pin connector.
1656
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1657
+//
1658
+//#define CR10_STOCKDISPLAY
1659
+
1660
+//
1661
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1662
+// http://reprap.org/wiki/MKS_12864OLED
1663
+//
1664
+// Tiny, but very sharp OLED display
1665
+//
1666
+//#define MKS_12864OLED
1667
+
1513 1668
 #endif // K8200_VM8201
1514 1669
 
1515 1670
 //=============================================================================
@@ -1568,16 +1723,22 @@
1568 1723
  * Adds the M150 command to set the LED (or LED strip) color.
1569 1724
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1570 1725
  * luminance values can be set from 0 to 255.
1726
+ * For Neopixel LED an overall brightness parameter is also available.
1571 1727
  *
1572 1728
  * *** CAUTION ***
1573 1729
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1574 1730
  *  as the Arduino cannot handle the current the LEDs will require.
1575 1731
  *  Failure to follow this precaution can destroy your Arduino!
1732
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1733
+ *  more current than the Arduino 5V linear regulator can produce.
1576 1734
  * *** CAUTION ***
1577 1735
  *
1736
+ * LED Type. Enable only one of the following two options.
1737
+ *
1578 1738
  */
1579 1739
 //#define RGB_LED
1580 1740
 //#define RGBW_LED
1741
+
1581 1742
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1582 1743
   #define RGB_LED_R_PIN 34
1583 1744
   #define RGB_LED_G_PIN 43
@@ -1585,6 +1746,17 @@
1585 1746
   #define RGB_LED_W_PIN -1
1586 1747
 #endif
1587 1748
 
1749
+// Support for Adafruit Neopixel LED driver
1750
+//#define NEOPIXEL_LED
1751
+#if ENABLED(NEOPIXEL_LED)
1752
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1753
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1754
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1755
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1756
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1757
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1758
+#endif
1759
+
1588 1760
 /**
1589 1761
  * Printer Event LEDs
1590 1762
  *
@@ -1596,68 +1768,32 @@
1596 1768
  *  - Change to green once print has finished
1597 1769
  *  - Turn off after the print has finished and the user has pushed a button
1598 1770
  */
1599
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)
1771
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1600 1772
   #define PRINTER_EVENT_LEDS
1601 1773
 #endif
1602 1774
 
1603
-/*********************************************************************\
1604
-* R/C SERVO support
1605
-* Sponsored by TrinityLabs, Reworked by codexmas
1606
-**********************************************************************/
1775
+/**
1776
+ * R/C SERVO support
1777
+ * Sponsored by TrinityLabs, Reworked by codexmas
1778
+ */
1607 1779
 
1608
-// Number of servos
1609
-//
1610
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1611
-// set it manually if you have more servos than extruders and wish to manually control some
1612
-// leaving it undefined or defining as 0 will disable the servo subsystem
1613
-// If unsure, leave commented / disabled
1614
-//
1780
+/**
1781
+ * Number of servos
1782
+ *
1783
+ * For some servo-related options NUM_SERVOS will be set automatically.
1784
+ * Set this manually if there are extra servos needing manual control.
1785
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1786
+ */
1615 1787
 //#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
1616 1788
 
1617 1789
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1618 1790
 // 300ms is a good value but you can try less delay.
1619 1791
 // If the servo can't reach the requested position, increase it.
1620
-#define SERVO_DELAY 300
1792
+#define SERVO_DELAY { 300 }
1621 1793
 
1622 1794
 // Servo deactivation
1623 1795
 //
1624 1796
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1625 1797
 //#define DEACTIVATE_SERVOS_AFTER_MOVE
1626 1798
 
1627
-/**
1628
- * Filament Width Sensor
1629
- *
1630
- * Measures the filament width in real-time and adjusts
1631
- * flow rate to compensate for any irregularities.
1632
- *
1633
- * Also allows the measured filament diameter to set the
1634
- * extrusion rate, so the slicer only has to specify the
1635
- * volume.
1636
- *
1637
- * Only a single extruder is supported at this time.
1638
- *
1639
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1640
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1641
- * 301 RAMBO       : Analog input 3
1642
- *
1643
- * Note: May require analog pins to be defined for other boards.
1644
- */
1645
-//#define FILAMENT_WIDTH_SENSOR
1646
-
1647
-#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00   // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
1648
-
1649
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1650
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1651
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1652
-
1653
-  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1654
-  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1655
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1656
-
1657
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1658
-
1659
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1660
-  //#define FILAMENT_LCD_DISPLAY
1661
-#endif
1662
-
1663 1799
 #endif // CONFIGURATION_H

Marlin/example_configurations/K8200/Configuration_adv.h → Marlin/example_configurations/Velleman/K8200/Configuration_adv.h 파일 보기

@@ -41,7 +41,7 @@
41 41
 
42 42
 #ifndef CONFIGURATION_ADV_H
43 43
 #define CONFIGURATION_ADV_H
44
-#define CONFIGURATION_ADV_H_VERSION 010100
44
+#define CONFIGURATION_ADV_H_VERSION 010107
45 45
 
46 46
 // @section temperature
47 47
 
@@ -57,18 +57,20 @@
57 57
 #endif
58 58
 
59 59
 /**
60
- * Thermal Protection protects your printer from damage and fire if a
61
- * thermistor falls out or temperature sensors fail in any way.
60
+ * Thermal Protection provides additional protection to your printer from damage
61
+ * and fire. Marlin always includes safe min and max temperature ranges which
62
+ * protect against a broken or disconnected thermistor wire.
62 63
  *
63
- * The issue: If a thermistor falls out or a temperature sensor fails,
64
- * Marlin can no longer sense the actual temperature. Since a disconnected
65
- * thermistor reads as a low temperature, the firmware will keep the heater on.
64
+ * The issue: If a thermistor falls out, it will report the much lower
65
+ * temperature of the air in the room, and the the firmware will keep
66
+ * the heater on.
66 67
  *
67 68
  * The solution: Once the temperature reaches the target, start observing.
68
- * If the temperature stays too far below the target (hysteresis) for too long (period),
69
- * the firmware will halt the machine as a safety precaution.
69
+ * If the temperature stays too far below the target (hysteresis) for too
70
+ * long (period), the firmware will halt the machine as a safety precaution.
70 71
  *
71
- * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
72
+ * If you get false positives for "Thermal Runaway", increase
73
+ * THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
72 74
  */
73 75
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
74 76
   // K8200 has weak heaters/power supply by default, so you have to relax!
@@ -76,13 +78,16 @@
76 78
   #define THERMAL_PROTECTION_HYSTERESIS 8     // Degrees Celsius
77 79
 
78 80
   /**
79
-   * Whenever an M104 or M109 increases the target temperature the firmware will wait for the
80
-   * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
81
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
82
-   * but only if the current temperature is far enough below the target for a reliable test.
81
+   * Whenever an M104, M109, or M303 increases the target temperature, the
82
+   * firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
83
+   * hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
84
+   * requires a hard reset. This test restarts with any M104/M109/M303, but only
85
+   * if the current temperature is far enough below the target for a reliable
86
+   * test.
83 87
    *
84
-   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
85
-   * WATCH_TEMP_INCREASE should not be below 2.
88
+   * If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
89
+   * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
90
+   * below 2.
86 91
    */
87 92
   // K8200 has weak heaters/power supply by default, so you have to relax!
88 93
   #define WATCH_TEMP_PERIOD 30                // Seconds
@@ -93,19 +98,13 @@
93 98
  * Thermal Protection parameters for the bed are just as above for hotends.
94 99
  */
95 100
 #if ENABLED(THERMAL_PROTECTION_BED)
96
-// K8200 has weak heaters/power supply by default, so you have to relax!
97
-// the default bed is so weak, that you can hardly go over 75°C
101
+  // K8200 has weak heaters/power supply by default, so you have to relax!
102
+  // the default bed is so weak, that you can hardly go over 75°C
98 103
   #define THERMAL_PROTECTION_BED_PERIOD 60    // Seconds
99 104
   #define THERMAL_PROTECTION_BED_HYSTERESIS 10 // Degrees Celsius
100 105
 
101 106
   /**
102
-   * Whenever an M140 or M190 increases the target temperature the firmware will wait for the
103
-   * WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
104
-   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
105
-   * but only if the current temperature is far enough below the target for a reliable test.
106
-   *
107
-   * If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
108
-   * WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
107
+   * As described above, except for the bed (M140/M190/M303).
109 108
    */
110 109
   #define WATCH_BED_TEMP_PERIOD 60                // Seconds
111 110
   #define WATCH_BED_TEMP_INCREASE 2               // Degrees Celsius
@@ -136,6 +135,9 @@
136 135
   #define AUTOTEMP_OLDWEIGHT 0.98
137 136
 #endif
138 137
 
138
+// Show extra position information in M114
139
+//#define M114_DETAIL
140
+
139 141
 // Show Temperature ADC value
140 142
 // Enable for M105 to include ADC values read from temperature sensors.
141 143
 //#define SHOW_TEMP_ADC_VALUES
@@ -234,6 +236,17 @@
234 236
 #define EXTRUDER_AUTO_FAN_SPEED   255  // == full speed
235 237
 
236 238
 /**
239
+ * Part-Cooling Fan Multiplexer
240
+ *
241
+ * This feature allows you to digitally multiplex the fan output.
242
+ * The multiplexer is automatically switched at tool-change.
243
+ * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans.
244
+ */
245
+#define FANMUX0_PIN -1
246
+#define FANMUX1_PIN -1
247
+#define FANMUX2_PIN -1
248
+
249
+/**
237 250
  * M355 Case Light on-off / brightness
238 251
  */
239 252
 //#define CASE_LIGHT_ENABLE
@@ -259,48 +272,49 @@
259 272
 
260 273
 //#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
261 274
 
262
-// Dual X Steppers
263
-// Uncomment this option to drive two X axis motors.
264
-// The next unused E driver will be assigned to the second X stepper.
275
+/**
276
+ * Dual Steppers / Dual Endstops
277
+ *
278
+ * This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
279
+ *
280
+ * For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
281
+ * spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
282
+ * set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
283
+ * that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
284
+ *
285
+ * Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
286
+ * this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
287
+ * in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
288
+ */
289
+
265 290
 //#define X_DUAL_STEPPER_DRIVERS
266 291
 #if ENABLED(X_DUAL_STEPPER_DRIVERS)
267
-  // Set true if the two X motors need to rotate in opposite directions
268
-  #define INVERT_X2_VS_X_DIR true
292
+  #define INVERT_X2_VS_X_DIR true   // Set 'true' if X motors should rotate in opposite directions
293
+  //#define X_DUAL_ENDSTOPS
294
+  #if ENABLED(X_DUAL_ENDSTOPS)
295
+    #define X2_USE_ENDSTOP _XMAX_
296
+    #define X_DUAL_ENDSTOPS_ADJUSTMENT  0
297
+  #endif
269 298
 #endif
270 299
 
271
-// Dual Y Steppers
272
-// Uncomment this option to drive two Y axis motors.
273
-// The next unused E driver will be assigned to the second Y stepper.
274 300
 //#define Y_DUAL_STEPPER_DRIVERS
275 301
 #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
276
-  // Set true if the two Y motors need to rotate in opposite directions
277
-  #define INVERT_Y2_VS_Y_DIR true
302
+  #define INVERT_Y2_VS_Y_DIR true   // Set 'true' if Y motors should rotate in opposite directions
303
+  //#define Y_DUAL_ENDSTOPS
304
+  #if ENABLED(Y_DUAL_ENDSTOPS)
305
+    #define Y2_USE_ENDSTOP _YMAX_
306
+    #define Y_DUAL_ENDSTOPS_ADJUSTMENT  0
307
+  #endif
278 308
 #endif
279 309
 
280
-// A single Z stepper driver is usually used to drive 2 stepper motors.
281
-// Uncomment this option to use a separate stepper driver for each Z axis motor.
282
-// The next unused E driver will be assigned to the second Z stepper.
283 310
 //#define Z_DUAL_STEPPER_DRIVERS
284
-
285 311
 #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
286
-
287
-  // Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper.
288
-  // That way the machine is capable to align the bed during home, since both Z steppers are homed.
289
-  // There is also an implementation of M666 (software endstops adjustment) to this feature.
290
-  // After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
291
-  // One just need to home the Z axis and measure the distance difference between both Z axis and apply the math: Z adjust = Z - Z2.
292
-  // If the Z stepper axis is closer to the bed, the measure Z > Z2 (yes, it is.. think about it) and the Z adjust would be positive.
293
-  // Play a little bit with small adjustments (0.5mm) and check the behaviour.
294
-  // The M119 (endstops report) will start reporting the Z2 Endstop as well.
295
-
296 312
   //#define Z_DUAL_ENDSTOPS
297
-
298 313
   #if ENABLED(Z_DUAL_ENDSTOPS)
299 314
     #define Z2_USE_ENDSTOP _XMAX_
300
-    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0  // use M666 command to determine this value
315
+    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0
301 316
   #endif
302
-
303
-#endif // Z_DUAL_STEPPER_DRIVERS
317
+#endif
304 318
 
305 319
 // Enable this for dual x-carriage printers.
306 320
 // A dual x-carriage design has the advantage that the inactive extruder can be parked which
@@ -347,12 +361,12 @@
347 361
 
348 362
 // @section homing
349 363
 
350
-//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
364
+// Homing hits each endstop, retracts by these distances, then does a slower bump.
351 365
 #define X_HOME_BUMP_MM 5
352 366
 #define Y_HOME_BUMP_MM 5
353 367
 #define Z_HOME_BUMP_MM 2
354
-#define HOMING_BUMP_DIVISOR {4, 4, 8}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
355
-#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
368
+#define HOMING_BUMP_DIVISOR { 4, 4, 8 }  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
369
+#define QUICK_HOME                       // If homing includes X and Y, do a diagonal move initially
356 370
 
357 371
 // When G28 is called, this option will make Y home before X
358 372
 //#define HOME_Y_BEFORE_X
@@ -407,7 +421,7 @@
407 421
 // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
408 422
 // of the buffer and all stops. This should not be much greater than zero and should only be changed
409 423
 // if unwanted behavior is observed on a user's machine when running at very slow speeds.
410
-#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
424
+#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
411 425
 
412 426
 // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
413 427
 #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
@@ -436,8 +450,21 @@
436 450
 //#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 }   // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
437 451
 //#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 }    // Default drive percent - X, Y, Z, E axis
438 452
 
439
-// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
453
+// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
440 454
 //#define DIGIPOT_I2C
455
+#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
456
+  /**
457
+   * Common slave addresses:
458
+   *
459
+   *                    A   (A shifted)   B   (B shifted)  IC
460
+   * Smoothie          0x2C (0x58)       0x2D (0x5A)       MCP4451
461
+   * AZTEEG_X3_PRO     0x2C (0x58)       0x2E (0x5C)       MCP4451
462
+   * MIGHTYBOARD_REVE  0x2F (0x5E)                         MCP4018
463
+   */
464
+  #define DIGIPOT_I2C_ADDRESS_A 0x2C  // unshifted slave address for first DIGIPOT
465
+  #define DIGIPOT_I2C_ADDRESS_B 0x2D  // unshifted slave address for second DIGIPOT
466
+#endif
467
+
441 468
 //#define DIGIPOT_MCP4018          // Requires library from https://github.com/stawel/SlowSoftI2CMaster
442 469
 #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4     AZTEEG_X3_PRO: 8
443 470
 // Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
@@ -465,6 +492,26 @@
465 492
 // On the Info Screen, display XY with one decimal place when possible
466 493
 //#define LCD_DECIMAL_SMALL_XY
467 494
 
495
+// The timeout (in ms) to return to the status screen from sub-menus
496
+//#define LCD_TIMEOUT_TO_STATUS 15000
497
+
498
+/**
499
+ * LED Control Menu
500
+ * Enable this feature to add LED Control to the LCD menu
501
+ */
502
+//#define LED_CONTROL_MENU
503
+#if ENABLED(LED_CONTROL_MENU)
504
+  #define LED_COLOR_PRESETS                 // Enable the Preset Color menu option
505
+  #if ENABLED(LED_COLOR_PRESETS)
506
+    #define LED_USER_PRESET_RED        255  // User defined RED value
507
+    #define LED_USER_PRESET_GREEN      128  // User defined GREEN value
508
+    #define LED_USER_PRESET_BLUE         0  // User defined BLUE value
509
+    #define LED_USER_PRESET_WHITE      255  // User defined WHITE value
510
+    #define LED_USER_PRESET_BRIGHTNESS 255  // User defined intensity
511
+    //#define LED_USER_PRESET_STARTUP       // Have the printer display the user preset color on startup
512
+  #endif
513
+#endif // LED_CONTROL_MENU
514
+
468 515
 #if ENABLED(SDSUPPORT)
469 516
 
470 517
   // Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -474,7 +521,7 @@
474 521
   // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
475 522
   #define SD_DETECT_INVERTED
476 523
 
477
-  #define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
524
+  #define SD_FINISHED_STEPPERRELEASE true          // Disable steppers when SD Print is finished
478 525
   #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
479 526
 
480 527
   #define SDCARD_RATHERRECENTFIRST  //reverse file order of sd card menu display. Its sorted practically after the file system block order.
@@ -509,13 +556,15 @@
509 556
 
510 557
   // SD Card Sorting options
511 558
   #if ENABLED(SDCARD_SORT_ALPHA)
512
-    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256).
559
+    #define SDSORT_LIMIT       40     // Maximum number of sorted items (10-256). Costs 27 bytes each.
513 560
     #define FOLDER_SORTING     -1     // -1=above  0=none  1=below
514 561
     #define SDSORT_GCODE       false  // Allow turning sorting on/off with LCD and M34 g-code.
515 562
     #define SDSORT_USES_RAM    false  // Pre-allocate a static array for faster pre-sorting.
516 563
     #define SDSORT_USES_STACK  false  // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
517 564
     #define SDSORT_CACHE_NAMES false  // Keep sorted items in RAM longer for speedy performance. Most expensive option.
518 565
     #define SDSORT_DYNAMIC_RAM false  // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
566
+    #define SDSORT_CACHE_VFATS 2      // Maximum number of 13-byte VFAT entries to use for sorting.
567
+                                      // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
519 568
   #endif
520 569
 
521 570
   // Show a progress bar on HD44780 LCDs for SD printing
@@ -534,14 +583,29 @@
534 583
     //#define LCD_PROGRESS_BAR_TEST
535 584
   #endif
536 585
 
586
+  // Add an 'M73' G-code to set the current percentage
587
+  //#define LCD_SET_PROGRESS_MANUALLY
588
+
537 589
   // This allows hosts to request long names for files and folders with M33
538 590
   #define LONG_FILENAME_HOST_SUPPORT
539 591
 
540
-  // This option allows you to abort SD printing when any endstop is triggered.
541
-  // This feature must be enabled with "M540 S1" or from the LCD menu.
542
-  // To have any effect, endstops must be enabled during SD printing.
592
+  // Enable this option to scroll long filenames in the SD card menu
593
+  //#define SCROLL_LONG_FILENAMES
594
+
595
+  /**
596
+   * This option allows you to abort SD printing when any endstop is triggered.
597
+   * This feature must be enabled with "M540 S1" or from the LCD menu.
598
+   * To have any effect, endstops must be enabled during SD printing.
599
+   */
543 600
   //#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
544 601
 
602
+  /**
603
+   * This option makes it easier to print the same SD Card file again.
604
+   * On print completion the LCD Menu will open with the file selected.
605
+   * You can just click to start the print, or navigate elsewhere.
606
+   */
607
+  //#define SD_REPRINT_LAST_SELECTED_FILE
608
+
545 609
 #endif // SDSUPPORT
546 610
 
547 611
 /**
@@ -574,6 +638,10 @@
574 638
   // Enable this option and reduce the value to optimize screen updates.
575 639
   // The normal delay is 10µs. Use the lowest value that still gives a reliable display.
576 640
   //#define DOGM_SPI_DELAY_US 5
641
+
642
+  // Swap the CW/CCW indicators in the graphics overlay
643
+  //#define OVERLAY_GFX_REVERSE
644
+
577 645
 #endif // DOGLCD
578 646
 
579 647
 // @section safety
@@ -600,31 +668,18 @@
600 668
  */
601 669
 #define BABYSTEPPING
602 670
 #if ENABLED(BABYSTEPPING)
603
-  #define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
604
-  #define BABYSTEP_INVERT_Z false  // Change if Z babysteps should go the other way
605
-  #define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
606
-  //#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
671
+  //#define BABYSTEP_XY              // Also enable X/Y Babystepping. Not supported on DELTA!
672
+  #define BABYSTEP_INVERT_Z false    // Change if Z babysteps should go the other way
673
+  #define BABYSTEP_MULTIPLICATOR 1   // Babysteps are very small. Increase for faster motion.
674
+  //#define BABYSTEP_ZPROBE_OFFSET   // Enable to combine M851 and Babystepping
607 675
   //#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
608 676
   #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
609 677
                                         // Note: Extra time may be added to mitigate controller latency.
678
+  //#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
610 679
 #endif
611 680
 
612 681
 // @section extruder
613 682
 
614
-// extruder advance constant (s2/mm3)
615
-//
616
-// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
617
-//
618
-// Hooke's law says:    force = k * distance
619
-// Bernoulli's principle says:  v ^ 2 / 2 + g . h + pressure / density = constant
620
-// so: v ^ 2 is proportional to number of steps we advance the extruder
621
-//#define ADVANCE
622
-
623
-#if ENABLED(ADVANCE)
624
-  #define EXTRUDER_ADVANCE_K .0
625
-  #define D_FILAMENT 2.85
626
-#endif
627
-
628 683
 /**
629 684
  * Implementation of linear pressure control
630 685
  *
@@ -658,7 +713,7 @@
658 713
    *
659 714
    * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
660 715
    *
661
-   * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode.
716
+   * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
662 717
    * Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
663 718
    */
664 719
   #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
@@ -667,19 +722,18 @@
667 722
 
668 723
 // @section leveling
669 724
 
670
-// Default mesh area is an area with an inset margin on the print area.
671
-// Below are the macros that are used to define the borders for the mesh area,
672
-// made available here for specialized needs, ie dual extruder setup.
673
-#if ENABLED(MESH_BED_LEVELING)
674
-  #define MESH_MIN_X (X_MIN_POS + MESH_INSET)
675
-  #define MESH_MAX_X (X_MAX_POS - (MESH_INSET))
676
-  #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET)
677
-  #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET))
678
-#elif ENABLED(AUTO_BED_LEVELING_UBL)
679
-  #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET)
680
-  #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET))
681
-  #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET)
682
-  #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET))
725
+#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
726
+  #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
727
+#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
728
+  #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
729
+#endif
730
+
731
+#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
732
+  // Override the mesh area if the automatic (max) area is too large
733
+  //#define MESH_MIN_X MESH_INSET
734
+  //#define MESH_MIN_Y MESH_INSET
735
+  //#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
736
+  //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
683 737
 #endif
684 738
 
685 739
 // @section extras
@@ -699,7 +753,7 @@
699 753
 //#define BEZIER_CURVE_SUPPORT
700 754
 
701 755
 // G38.2 and G38.3 Probe Target
702
-// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
756
+// Set MULTIPLE_PROBING if you want G38 to double touch
703 757
 //#define G38_PROBE_TARGET
704 758
 #if ENABLED(G38_PROBE_TARGET)
705 759
   #define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
@@ -724,7 +778,7 @@
724 778
 // @section hidden
725 779
 
726 780
 // The number of linear motions that can be in the plan at any give time.
727
-// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
781
+// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
728 782
 #if ENABLED(SDSUPPORT)
729 783
   #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
730 784
 #else
@@ -737,7 +791,7 @@
737 791
 #define MAX_CMD_SIZE 96
738 792
 #define BUFSIZE 4
739 793
 
740
-// Transfer Buffer Size
794
+// Transmission to Host Buffer Size
741 795
 // To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0.
742 796
 // To buffer a simple "ok" you need 4 bytes.
743 797
 // For ADVANCED_OK (M105) you need 32 bytes.
@@ -746,6 +800,28 @@
746 800
 // :[0, 2, 4, 8, 16, 32, 64, 128, 256]
747 801
 #define TX_BUFFER_SIZE 128
748 802
 
803
+// Host Receive Buffer Size
804
+// Without XON/XOFF flow control (see SERIAL_XON_XOFF below) 32 bytes should be enough.
805
+// To use flow control, set this buffer size to at least 1024 bytes.
806
+// :[0, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048]
807
+//#define RX_BUFFER_SIZE 1024
808
+
809
+#if RX_BUFFER_SIZE >= 1024
810
+  // Enable to have the controller send XON/XOFF control characters to
811
+  // the host to signal the RX buffer is becoming full.
812
+  //#define SERIAL_XON_XOFF
813
+#endif
814
+
815
+#if ENABLED(SDSUPPORT)
816
+  // Enable this option to collect and display the maximum
817
+  // RX queue usage after transferring a file to SD.
818
+  //#define SERIAL_STATS_MAX_RX_QUEUED
819
+
820
+  // Enable this option to collect and display the number
821
+  // of dropped bytes after a file transfer to SD.
822
+  //#define SERIAL_STATS_DROPPED_RX
823
+#endif
824
+
749 825
 // Enable an emergency-command parser to intercept certain commands as they
750 826
 // enter the serial receive buffer, so they cannot be blocked.
751 827
 // Currently handles M108, M112, M410
@@ -761,27 +837,47 @@
761 837
 // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary.
762 838
 //#define ADVANCED_OK
763 839
 
764
-// @section fwretract
765
-
766
-// Firmware based and LCD controlled retract
767
-// M207 and M208 can be used to define parameters for the retraction.
768
-// The retraction can be called by the slicer using G10 and G11
769
-// until then, intended retractions can be detected by moves that only extrude and the direction.
770
-// the moves are than replaced by the firmware controlled ones.
840
+// @section extras
771 841
 
772
-//#define FWRETRACT  //ONLY PARTIALLY TESTED
842
+/**
843
+ * Firmware-based and LCD-controlled retract
844
+ *
845
+ * Add G10 / G11 commands for automatic firmware-based retract / recover.
846
+ * Use M207 and M208 to define parameters for retract / recover.
847
+ *
848
+ * Use M209 to enable or disable auto-retract.
849
+ * With auto-retract enabled, all G1 E moves within the set range
850
+ * will be converted to firmware-based retract/recover moves.
851
+ *
852
+ * Be sure to turn off auto-retract during filament change.
853
+ *
854
+ * Note that M207 / M208 / M209 settings are saved to EEPROM.
855
+ *
856
+ */
857
+//#define FWRETRACT  // ONLY PARTIALLY TESTED
773 858
 #if ENABLED(FWRETRACT)
774
-  #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
775
-  #define RETRACT_LENGTH 3               //default retract length (positive mm)
776
-  #define RETRACT_LENGTH_SWAP 13         //default swap retract length (positive mm), for extruder change
777
-  #define RETRACT_FEEDRATE 45            //default feedrate for retracting (mm/s)
778
-  #define RETRACT_ZLIFT 0                //default retract Z-lift
779
-  #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
780
-  #define RETRACT_RECOVER_LENGTH_SWAP 0  //default additional swap recover length (mm, added to retract length when recovering from extruder change)
781
-  #define RETRACT_RECOVER_FEEDRATE 8     //default feedrate for recovering from retraction (mm/s)
859
+  #define MIN_AUTORETRACT 0.1             // When auto-retract is on, convert E moves of this length and over
860
+  #define MAX_AUTORETRACT 10.0            // Upper limit for auto-retract conversion
861
+  #define RETRACT_LENGTH 3                // Default retract length (positive mm)
862
+  #define RETRACT_LENGTH_SWAP 13          // Default swap retract length (positive mm), for extruder change
863
+  #define RETRACT_FEEDRATE 45             // Default feedrate for retracting (mm/s)
864
+  #define RETRACT_ZLIFT 0                 // Default retract Z-lift
865
+  #define RETRACT_RECOVER_LENGTH 0        // Default additional recover length (mm, added to retract length when recovering)
866
+  #define RETRACT_RECOVER_LENGTH_SWAP 0   // Default additional swap recover length (mm, added to retract length when recovering from extruder change)
867
+  #define RETRACT_RECOVER_FEEDRATE 8      // Default feedrate for recovering from retraction (mm/s)
868
+  #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
782 869
 #endif
783 870
 
784 871
 /**
872
+ * Extra Fan Speed
873
+ * Adds a secondary fan speed for each print-cooling fan.
874
+ *   'M106 P<fan> T3-255' : Set a secondary speed for <fan>
875
+ *   'M106 P<fan> T2'     : Use the set secondary speed
876
+ *   'M106 P<fan> T1'     : Restore the previous fan speed
877
+ */
878
+//#define EXTRA_FAN_SPEED
879
+
880
+/**
785 881
  * Advanced Pause
786 882
  * Experimental feature for filament change support and for parking the nozzle when paused.
787 883
  * Adds the GCode M600 for initiating filament change.
@@ -891,7 +987,7 @@
891 987
 
892 988
 #endif
893 989
 
894
-// @section TMC2130
990
+// @section TMC2130, TMC2208
895 991
 
896 992
 /**
897 993
  * Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
@@ -905,7 +1001,19 @@
905 1001
  */
906 1002
 //#define HAVE_TMC2130
907 1003
 
908
-#if ENABLED(HAVE_TMC2130)
1004
+/**
1005
+ * Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
1006
+ * Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
1007
+ * To use the reading capabilities, also connect #_SERIAL_RX_PIN
1008
+ * to #_SERIAL_TX_PIN with a 1K resistor.
1009
+ * The drivers can also be used with hardware serial.
1010
+ *
1011
+ * You'll also need the TMC2208Stepper Arduino library
1012
+ * (https://github.com/teemuatlut/TMC2208Stepper).
1013
+ */
1014
+//#define HAVE_TMC2208
1015
+
1016
+#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
909 1017
 
910 1018
   // CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
911 1019
   //#define X_IS_TMC2130
@@ -920,46 +1028,58 @@
920 1028
   //#define E3_IS_TMC2130
921 1029
   //#define E4_IS_TMC2130
922 1030
 
1031
+  //#define X_IS_TMC2208
1032
+  //#define X2_IS_TMC2208
1033
+  //#define Y_IS_TMC2208
1034
+  //#define Y2_IS_TMC2208
1035
+  //#define Z_IS_TMC2208
1036
+  //#define Z2_IS_TMC2208
1037
+  //#define E0_IS_TMC2208
1038
+  //#define E1_IS_TMC2208
1039
+  //#define E2_IS_TMC2208
1040
+  //#define E3_IS_TMC2208
1041
+  //#define E4_IS_TMC2208
1042
+
923 1043
   /**
924 1044
    * Stepper driver settings
925 1045
    */
926 1046
 
927 1047
   #define R_SENSE           0.11  // R_sense resistor for SilentStepStick2130
928 1048
   #define HOLD_MULTIPLIER    0.5  // Scales down the holding current from run current
929
-  #define INTERPOLATE          1  // Interpolate X/Y/Z_MICROSTEPS to 256
1049
+  #define INTERPOLATE       true  // Interpolate X/Y/Z_MICROSTEPS to 256
930 1050
 
931
-  #define X_CURRENT         1000  // rms current in mA. Multiply by 1.41 for peak current.
1051
+  #define X_CURRENT          800  // rms current in mA. Multiply by 1.41 for peak current.
932 1052
   #define X_MICROSTEPS        16  // 0..256
933 1053
 
934
-  #define Y_CURRENT         1000
1054
+  #define Y_CURRENT          800
935 1055
   #define Y_MICROSTEPS        16
936 1056
 
937
-  #define Z_CURRENT         1000
1057
+  #define Z_CURRENT          800
938 1058
   #define Z_MICROSTEPS        16
939 1059
 
940
-  //#define X2_CURRENT      1000
941
-  //#define X2_MICROSTEPS     16
1060
+  #define X2_CURRENT         800
1061
+  #define X2_MICROSTEPS       16
942 1062
 
943
-  //#define Y2_CURRENT      1000
944
-  //#define Y2_MICROSTEPS     16
1063
+  #define Y2_CURRENT         800
1064
+  #define Y2_MICROSTEPS       16
945 1065
 
946
-  //#define Z2_CURRENT      1000
947
-  //#define Z2_MICROSTEPS     16
1066
+  #define Z2_CURRENT         800
1067
+  #define Z2_MICROSTEPS       16
948 1068
 
949
-  //#define E0_CURRENT      1000
950
-  //#define E0_MICROSTEPS     16
1069
+  #define E0_CURRENT         800
1070
+  #define E0_MICROSTEPS       16
951 1071
 
952
-  //#define E1_CURRENT      1000
953
-  //#define E1_MICROSTEPS     16
1072
+  #define E1_CURRENT         800
1073
+  #define E1_MICROSTEPS       16
954 1074
 
955
-  //#define E2_CURRENT      1000
956
-  //#define E2_MICROSTEPS     16
1075
+  #define E2_CURRENT         800
1076
+  #define E2_MICROSTEPS       16
957 1077
 
958
-  //#define E3_CURRENT      1000
959
-  //#define E3_MICROSTEPS     16
1078
+  #define E3_CURRENT         800
1079
+  #define E3_MICROSTEPS       16
960 1080
 
961
-  //#define E4_CURRENT      1000
962
-  //#define E4_MICROSTEPS     16
1081
+  #define E4_CURRENT         800
1082
+  #define E4_MICROSTEPS       16
963 1083
 
964 1084
   /**
965 1085
    * Use Trinamic's ultra quiet stepping mode.
@@ -968,24 +1088,22 @@
968 1088
   #define STEALTHCHOP
969 1089
 
970 1090
   /**
971
-   * Let Marlin automatically control stepper current.
972
-   * This is still an experimental feature.
973
-   * Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
974
-   * then decrease current by CURRENT_STEP until temperature prewarn is cleared.
975
-   * Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
1091
+   * Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
1092
+   * like overtemperature and short to ground. TMC2208 requires hardware serial.
1093
+   * In the case of overtemperature Marlin can decrease the driver current until error condition clears.
1094
+   * Other detected conditions can be used to stop the current print.
976 1095
    * Relevant g-codes:
977 1096
    * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
978
-   * M906 S1 - Start adjusting current
979
-   * M906 S0 - Stop adjusting current
980 1097
    * M911 - Report stepper driver overtemperature pre-warn condition.
981 1098
    * M912 - Clear stepper driver overtemperature pre-warn condition flag.
1099
+   * M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
982 1100
    */
983
-  //#define AUTOMATIC_CURRENT_CONTROL
1101
+  //#define MONITOR_DRIVER_STATUS
984 1102
 
985
-  #if ENABLED(AUTOMATIC_CURRENT_CONTROL)
986
-    #define CURRENT_STEP          50  // [mA]
987
-    #define AUTO_ADJUST_MAX     1300  // [mA], 1300mA_rms = 1840mA_peak
1103
+  #if ENABLED(MONITOR_DRIVER_STATUS)
1104
+    #define CURRENT_STEP_DOWN     50  // [mA]
988 1105
     #define REPORT_CURRENT_CHANGE
1106
+    #define STOP_ON_ERROR
989 1107
   #endif
990 1108
 
991 1109
   /**
@@ -1000,8 +1118,8 @@
1000 1118
   #define X2_HYBRID_THRESHOLD    100
1001 1119
   #define Y_HYBRID_THRESHOLD     100
1002 1120
   #define Y2_HYBRID_THRESHOLD    100
1003
-  #define Z_HYBRID_THRESHOLD       4
1004
-  #define Z2_HYBRID_THRESHOLD      4
1121
+  #define Z_HYBRID_THRESHOLD       3
1122
+  #define Z2_HYBRID_THRESHOLD      3
1005 1123
   #define E0_HYBRID_THRESHOLD     30
1006 1124
   #define E1_HYBRID_THRESHOLD     30
1007 1125
   #define E2_HYBRID_THRESHOLD     30
@@ -1011,7 +1129,7 @@
1011 1129
   /**
1012 1130
    * Use stallGuard2 to sense an obstacle and trigger an endstop.
1013 1131
    * You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
1014
-   * If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
1132
+   * X and Y homing will always be done in spreadCycle mode.
1015 1133
    *
1016 1134
    * X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
1017 1135
    * Higher values make the system LESS sensitive.
@@ -1020,27 +1138,34 @@
1020 1138
    * It is advised to set X/Y_HOME_BUMP_MM to 0.
1021 1139
    * M914 X/Y to live tune the setting
1022 1140
    */
1023
-  //#define SENSORLESS_HOMING
1141
+  //#define SENSORLESS_HOMING // TMC2130 only
1024 1142
 
1025 1143
   #if ENABLED(SENSORLESS_HOMING)
1026
-    #define X_HOMING_SENSITIVITY  19
1027
-    #define Y_HOMING_SENSITIVITY  19
1144
+    #define X_HOMING_SENSITIVITY  8
1145
+    #define Y_HOMING_SENSITIVITY  8
1028 1146
   #endif
1029 1147
 
1030 1148
   /**
1149
+   * Enable M122 debugging command for TMC stepper drivers.
1150
+   * M122 S0/1 will enable continous reporting.
1151
+   */
1152
+  //#define TMC_DEBUG
1153
+
1154
+  /**
1031 1155
    * You can set your own advanced settings by filling in predefined functions.
1032 1156
    * A list of available functions can be found on the library github page
1033 1157
    * https://github.com/teemuatlut/TMC2130Stepper
1158
+   * https://github.com/teemuatlut/TMC2208Stepper
1034 1159
    *
1035 1160
    * Example:
1036
-   * #define TMC2130_ADV() { \
1161
+   * #define TMC_ADV() { \
1037 1162
    *   stepperX.diag0_temp_prewarn(1); \
1038
-   *   stepperX.interpolate(0); \
1163
+   *   stepperY.interpolate(0); \
1039 1164
    * }
1040 1165
    */
1041
-  #define  TMC2130_ADV() {  }
1166
+  #define  TMC_ADV() {  }
1042 1167
 
1043
-#endif // HAVE_TMC2130
1168
+#endif // TMC2130 || TMC2208
1044 1169
 
1045 1170
 // @section L6470
1046 1171
 
@@ -1205,6 +1330,48 @@
1205 1330
 #endif
1206 1331
 
1207 1332
 /**
1333
+ * Filament Width Sensor
1334
+ *
1335
+ * Measures the filament width in real-time and adjusts
1336
+ * flow rate to compensate for any irregularities.
1337
+ *
1338
+ * Also allows the measured filament diameter to set the
1339
+ * extrusion rate, so the slicer only has to specify the
1340
+ * volume.
1341
+ *
1342
+ * Only a single extruder is supported at this time.
1343
+ *
1344
+ *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1345
+ *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1346
+ * 301 RAMBO       : Analog input 3
1347
+ *
1348
+ * Note: May require analog pins to be defined for other boards.
1349
+ */
1350
+//#define FILAMENT_WIDTH_SENSOR
1351
+
1352
+#if ENABLED(FILAMENT_WIDTH_SENSOR)
1353
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
1354
+  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1355
+
1356
+  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1357
+  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1358
+  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1359
+
1360
+  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1361
+
1362
+  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1363
+  //#define FILAMENT_LCD_DISPLAY
1364
+#endif
1365
+
1366
+/**
1367
+ * CNC Coordinate Systems
1368
+ *
1369
+ * Enables G53 and G54-G59.3 commands to select coordinate systems
1370
+ * and G92.1 to reset the workspace to native machine space.
1371
+ */
1372
+//#define CNC_COORDINATE_SYSTEMS
1373
+
1374
+/**
1208 1375
  * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
1209 1376
  */
1210 1377
 //#define PINS_DEBUGGING
@@ -1257,6 +1424,8 @@
1257 1424
 //#define CUSTOM_USER_MENUS
1258 1425
 #if ENABLED(CUSTOM_USER_MENUS)
1259 1426
   #define USER_SCRIPT_DONE "M117 User Script Done"
1427
+  #define USER_SCRIPT_AUDIBLE_FEEDBACK
1428
+  //#define USER_SCRIPT_RETURN  // Return to status screen after a script
1260 1429
 
1261 1430
   #define USER_DESC_1 "Home & UBL Info"
1262 1431
   #define USER_GCODE_1 "G28\nG29 W"
@@ -1284,6 +1453,7 @@
1284 1453
 //===========================================================================
1285 1454
 //====================== I2C Position Encoder Settings ======================
1286 1455
 //===========================================================================
1456
+
1287 1457
 /**
1288 1458
  *  I2C position encoders for closed loop control.
1289 1459
  *  Developed by Chris Barr at Aus3D.
@@ -1364,4 +1534,45 @@
1364 1534
 
1365 1535
 #endif // I2C_POSITION_ENCODERS
1366 1536
 
1537
+/**
1538
+ * MAX7219 Debug Matrix
1539
+ *
1540
+ * Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
1541
+ * display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
1542
+ *
1543
+ * Fully assembled MAX7219 boards can be found on the internet for under $2(US).
1544
+ * For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
1545
+ */
1546
+//#define MAX7219_DEBUG
1547
+#if ENABLED(MAX7219_DEBUG)
1548
+  #define MAX7219_CLK_PIN   64  // 77 on Re-ARM       // Configuration of the 3 pins to control the display
1549
+  #define MAX7219_DIN_PIN   57  // 78 on Re-ARM
1550
+  #define MAX7219_LOAD_PIN  44  // 79 on Re-ARM
1551
+
1552
+  /**
1553
+   * Sample debug features
1554
+   * If you add more debug displays, be careful to avoid conflicts!
1555
+   */
1556
+  #define MAX7219_DEBUG_PRINTER_ALIVE    // Blink corner LED of 8x8 matrix to show that the firmware is functioning
1557
+  #define MAX7219_DEBUG_STEPPER_HEAD  3  // Show the stepper queue head position on this and the next LED matrix row
1558
+  #define MAX7219_DEBUG_STEPPER_TAIL  5  // Show the stepper queue tail position on this and the next LED matrix row
1559
+
1560
+  #define MAX7219_DEBUG_STEPPER_QUEUE 0  // Show the current stepper queue depth on this and the next LED matrix row
1561
+                                         // If you experience stuttering, reboots, etc. this option can reveal how
1562
+                                         // tweaks made to the configuration are affecting the printer in real-time.
1563
+#endif
1564
+
1565
+/**
1566
+ * NanoDLP Sync support
1567
+ *
1568
+ * Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
1569
+ * string to enable synchronization with DLP projector exposure. This change will allow to use
1570
+ * [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
1571
+ */
1572
+//#define NANODLP_Z_SYNC
1573
+#if ENABLED(NANODLP_Z_SYNC)
1574
+  //#define NANODLP_ALL_AXIS  // Enables "Z_move_comp" output on any axis move.
1575
+                              // Default behaviour is limited to Z axis only.
1576
+#endif
1577
+
1367 1578
 #endif // CONFIGURATION_ADV_H

Marlin/example_configurations/K8200/README.md → Marlin/example_configurations/Velleman/K8200/README.md 파일 보기


Marlin/example_configurations/K8400/Configuration.h → Marlin/example_configurations/Velleman/K8400/Configuration.h 파일 보기

@@ -37,7 +37,7 @@
37 37
  */
38 38
 #ifndef CONFIGURATION_H
39 39
 #define CONFIGURATION_H
40
-#define CONFIGURATION_H_VERSION 010100
40
+#define CONFIGURATION_H_VERSION 010107
41 41
 
42 42
 //===========================================================================
43 43
 //============================= Getting Started =============================
@@ -107,8 +107,9 @@
107 107
  *
108 108
  * 250000 works in most cases, but you might try a lower speed if
109 109
  * you commonly experience drop-outs during host printing.
110
+ * You may try up to 1000000 to speed up SD file transfer.
110 111
  *
111
- * :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
112
+ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
112 113
  */
113 114
 #define BAUDRATE 250000
114 115
 
@@ -135,6 +136,9 @@
135 136
 // :[1, 2, 3, 4, 5]
136 137
 #define EXTRUDERS 1
137 138
 
139
+// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
140
+#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
141
+
138 142
 // For Cyclops or any "multi-extruder" that shares a single nozzle.
139 143
 //#define SINGLENOZZLE
140 144
 
@@ -161,7 +165,10 @@
161 165
 //#define SWITCHING_EXTRUDER
162 166
 #if ENABLED(SWITCHING_EXTRUDER)
163 167
   #define SWITCHING_EXTRUDER_SERVO_NR 0
164
-  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1
168
+  #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3]
169
+  #if EXTRUDERS > 3
170
+    #define SWITCHING_EXTRUDER_E23_SERVO_NR 1
171
+  #endif
165 172
 #endif
166 173
 
167 174
 // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles
@@ -173,6 +180,21 @@
173 180
 #endif
174 181
 
175 182
 /**
183
+ * Two separate X-carriages with extruders that connect to a moving part
184
+ * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN.
185
+ */
186
+//#define PARKING_EXTRUDER
187
+#if ENABLED(PARKING_EXTRUDER)
188
+  #define PARKING_EXTRUDER_SOLENOIDS_INVERT           // If enabled, the solenoid is NOT magnetized with applied voltage
189
+  #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW  // LOW or HIGH pin signal energizes the coil
190
+  #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250        // Delay (ms) for magnetic field. No delay if 0 or not defined.
191
+  #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
192
+  #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // mm to move beyond the parking point to grab the extruder
193
+  #define PARKING_EXTRUDER_SECURITY_RAISE 5           // Z-raise before parking
194
+  #define HOTEND_OFFSET_Z { 0.0, 1.3 }                // Z-offsets of the two hotends. The first must be 0.
195
+#endif
196
+
197
+/**
176 198
  * "Mixing Extruder"
177 199
  *   - Adds a new code, M165, to set the current mix factors.
178 200
  *   - Extends the stepping routines to move multiple steppers in proportion to the mix.
@@ -317,8 +339,9 @@
317 339
 
318 340
 // Comment the following line to disable PID and enable bang-bang.
319 341
 #define PIDTEMP
320
-#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
321
-#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
342
+#define BANG_MAX 255     // Limits current to nozzle while in bang-bang mode; 255=full current
343
+#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
344
+#define PID_K1 0.95      // Smoothing factor within the PID
322 345
 #if ENABLED(PIDTEMP)
323 346
   //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
324 347
   //#define PID_DEBUG // Sends debug data to the serial port.
@@ -328,7 +351,6 @@
328 351
                                   // Set/get with gcode: M301 E[extruder number, 0-2]
329 352
   #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
330 353
                                   // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
331
-  #define K1 0.95 //smoothing factor within the PID
332 354
 
333 355
   // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
334 356
 
@@ -409,12 +431,13 @@
409 431
 //===========================================================================
410 432
 
411 433
 /**
412
- * Thermal Protection protects your printer from damage and fire if a
413
- * thermistor falls out or temperature sensors fail in any way.
434
+ * Thermal Protection provides additional protection to your printer from damage
435
+ * and fire. Marlin always includes safe min and max temperature ranges which
436
+ * protect against a broken or disconnected thermistor wire.
414 437
  *
415
- * The issue: If a thermistor falls out or a temperature sensor fails,
416
- * Marlin can no longer sense the actual temperature. Since a disconnected
417
- * thermistor reads as a low temperature, the firmware will keep the heater on.
438
+ * The issue: If a thermistor falls out, it will report the much lower
439
+ * temperature of the air in the room, and the the firmware will keep
440
+ * the heater on.
418 441
  *
419 442
  * If you get "Thermal Runaway" or "Heating failed" errors the
420 443
  * details can be tuned in Configuration_adv.h
@@ -554,7 +577,7 @@
554 577
 // @section probes
555 578
 
556 579
 //
557
-// See http://marlinfw.org/configuration/probes.html
580
+// See http://marlinfw.org/docs/configuration/probes.html
558 581
 //
559 582
 
560 583
 /**
@@ -620,14 +643,15 @@
620 643
 #endif
621 644
 
622 645
 /**
623
- * Enable if probing seems unreliable. Heaters and/or fans - consistent with the
624
- * options selected below - will be disabled during probing so as to minimize
625
- * potential EM interference by quieting/silencing the source of the 'noise' (the change
626
- * in current flowing through the wires).  This is likely most useful to users of the
627
- * BLTouch probe, but may also help those with inductive or other probe types.
646
+ * Enable one or more of the following if probing seems unreliable.
647
+ * Heaters and/or fans can be disabled during probing to minimize electrical
648
+ * noise. A delay can also be added to allow noise and vibration to settle.
649
+ * These options are most useful for the BLTouch probe, but may also improve
650
+ * readings with inductive probes and piezo sensors.
628 651
  */
629 652
 //#define PROBING_HEATERS_OFF       // Turn heaters off when probing
630 653
 //#define PROBING_FANS_OFF          // Turn fans off when probing
654
+//#define DELAY_BEFORE_PROBING 200  // (ms) To prevent vibrations from triggering piezo sensors
631 655
 
632 656
 // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN)
633 657
 //#define SOLENOID_PROBE
@@ -666,14 +690,16 @@
666 690
 // X and Y axis travel speed (mm/m) between probes
667 691
 #define XY_PROBE_SPEED 8000
668 692
 
669
-// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
693
+// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
670 694
 #define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
671 695
 
672 696
 // Speed for the "accurate" probe of each point
673 697
 #define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
674 698
 
675
-// Use double touch for probing
676
-//#define PROBE_DOUBLE_TOUCH
699
+// The number of probes to perform at each point.
700
+//   Set to 2 for a fast/slow probe, using the second probe result.
701
+//   Set to 3 or more for slow probes, averaging the results.
702
+//#define MULTIPLE_PROBING 2
677 703
 
678 704
 /**
679 705
  * Z probes require clearance when deploying, stowing, and moving between
@@ -740,6 +766,8 @@
740 766
 
741 767
 // @section homing
742 768
 
769
+//#define NO_MOTION_BEFORE_HOMING  // Inhibit movement until all axes have been homed
770
+
743 771
 //#define Z_HOMING_HEIGHT 4  // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
744 772
                              // Be sure you have this distance over your Z_MAX_POS in case.
745 773
 
@@ -751,18 +779,42 @@
751 779
 
752 780
 // @section machine
753 781
 
754
-// Travel limits after homing (units are in mm)
782
+// The size of the print bed
783
+#define X_BED_SIZE 200
784
+#define Y_BED_SIZE 200
785
+
786
+// Travel limits (mm) after homing, corresponding to endstop positions.
755 787
 #define X_MIN_POS 0
756 788
 #define Y_MIN_POS 20
757 789
 #define Z_MIN_POS 0
758
-#define X_MAX_POS 200
759
-#define Y_MAX_POS 200
790
+#define X_MAX_POS X_BED_SIZE
791
+#define Y_MAX_POS Y_BED_SIZE
760 792
 #define Z_MAX_POS 190
761 793
 
762
-// If enabled, axes won't move below MIN_POS in response to movement commands.
794
+/**
795
+ * Software Endstops
796
+ *
797
+ * - Prevent moves outside the set machine bounds.
798
+ * - Individual axes can be disabled, if desired.
799
+ * - X and Y only apply to Cartesian robots.
800
+ * - Use 'M211' to set software endstops on/off or report current state
801
+ */
802
+
803
+// Min software endstops curtail movement below minimum coordinate bounds
763 804
 #define MIN_SOFTWARE_ENDSTOPS
764
-// If enabled, axes won't move above MAX_POS in response to movement commands.
805
+#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
806
+  #define MIN_SOFTWARE_ENDSTOP_X
807
+  #define MIN_SOFTWARE_ENDSTOP_Y
808
+  #define MIN_SOFTWARE_ENDSTOP_Z
809
+#endif
810
+
811
+// Max software endstops curtail movement above maximum coordinate bounds
765 812
 #define MAX_SOFTWARE_ENDSTOPS
813
+#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
814
+  #define MAX_SOFTWARE_ENDSTOP_X
815
+  #define MAX_SOFTWARE_ENDSTOP_Y
816
+  #define MAX_SOFTWARE_ENDSTOP_Z
817
+#endif
766 818
 
767 819
 /**
768 820
  * Filament Runout Sensor
@@ -782,7 +834,7 @@
782 834
 //===========================================================================
783 835
 //=============================== Bed Leveling ==============================
784 836
 //===========================================================================
785
-// @section bedlevel
837
+// @section calibrate
786 838
 
787 839
 /**
788 840
  * Choose one of the options below to enable G29 Bed Leveling. The parameters
@@ -808,12 +860,7 @@
808 860
  * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
809 861
  *   A comprehensive bed leveling system combining the features and benefits
810 862
  *   of other systems. UBL also includes integrated Mesh Generation, Mesh
811
- *   Validation and Mesh Editing systems. Currently, UBL is only checked out
812
- *   for Cartesian Printers. That said, it was primarily designed to correct
813
- *   poor quality Delta Printers. If you feel adventurous and have a Delta,
814
- *   please post an issue if something doesn't work correctly. Initially,
815
- *   you will need to set a reduced bed size so you have a rectangular area
816
- *   to test on.
863
+ *   Validation and Mesh Editing systems.
817 864
  *
818 865
  * - MESH_BED_LEVELING
819 866
  *   Probe a grid manually
@@ -840,6 +887,24 @@
840 887
   // at which point movement will be level to the machine's XY plane.
841 888
   // The height can be set with M420 Z<height>
842 889
   #define ENABLE_LEVELING_FADE_HEIGHT
890
+
891
+  // For Cartesian machines, instead of dividing moves on mesh boundaries,
892
+  // split up moves into short segments like a Delta. This follows the
893
+  // contours of the bed more closely than edge-to-edge straight moves.
894
+  #define SEGMENT_LEVELED_MOVES
895
+  #define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
896
+
897
+  /**
898
+   * Enable the G26 Mesh Validation Pattern tool.
899
+   */
900
+  //#define G26_MESH_VALIDATION   // Enable G26 mesh validation
901
+  #if ENABLED(G26_MESH_VALIDATION)
902
+    #define MESH_TEST_NOZZLE_SIZE     0.4   // (mm) Diameter of primary nozzle.
903
+    #define MESH_TEST_LAYER_HEIGHT    0.2   // (mm) Default layer height for the G26 Mesh Validation Tool.
904
+    #define MESH_TEST_HOTEND_TEMP   205.0   // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
905
+    #define MESH_TEST_BED_TEMP       60.0   // (°C) Default bed temperature for the G26 Mesh Validation Tool.
906
+  #endif
907
+
843 908
 #endif
844 909
 
845 910
 #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -895,7 +960,9 @@
895 960
   //========================= Unified Bed Leveling ============================
896 961
   //===========================================================================
897 962
 
898
-  #define UBL_MESH_INSET 1          // Mesh inset margin on print area
963
+  //#define MESH_EDIT_GFX_OVERLAY   // Display a graphics overlay while editing the mesh
964
+
965
+  #define MESH_INSET 1              // Mesh inset margin on print area
899 966
   #define GRID_MAX_POINTS_X 10      // Don't use more than 15 points per axis, implementation limited.
900 967
   #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
901 968
 
@@ -906,8 +973,8 @@
906 973
   #define UBL_PROBE_PT_3_X 180
907 974
   #define UBL_PROBE_PT_3_Y 20
908 975
 
909
-  #define UBL_G26_MESH_VALIDATION   // Enable G26 mesh validation
910 976
   #define UBL_MESH_EDIT_MOVES_Z     // Sophisticated users prefer no movement of nozzle
977
+  #define UBL_SAVE_ACTIVE_ON_M500   // Save the currently active mesh in the current slot on M500
911 978
 
912 979
 #elif ENABLED(MESH_BED_LEVELING)
913 980
 
@@ -934,6 +1001,9 @@
934 1001
   #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment
935 1002
 #endif
936 1003
 
1004
+// Add a menu item to move between bed corners for manual bed adjustment
1005
+//#define LEVEL_BED_CORNERS
1006
+
937 1007
 /**
938 1008
  * Commands to execute at the end of G29 probing.
939 1009
  * Useful to retract or move the Z probe out of the way.
@@ -964,14 +1034,71 @@
964 1034
 //#define Z_SAFE_HOMING
965 1035
 
966 1036
 #if ENABLED(Z_SAFE_HOMING)
967
-  #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
968
-  #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
1037
+  #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2)    // X point for Z homing when homing all axes (G28).
1038
+  #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2)    // Y point for Z homing when homing all axes (G28).
969 1039
 #endif
970 1040
 
971 1041
 // Homing speeds (mm/m)
972 1042
 #define HOMING_FEEDRATE_XY (50*60)
973 1043
 #define HOMING_FEEDRATE_Z  (8*60)
974 1044
 
1045
+// @section calibrate
1046
+
1047
+/**
1048
+ * Bed Skew Compensation
1049
+ *
1050
+ * This feature corrects for misalignment in the XYZ axes.
1051
+ *
1052
+ * Take the following steps to get the bed skew in the XY plane:
1053
+ *  1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
1054
+ *  2. For XY_DIAG_AC measure the diagonal A to C
1055
+ *  3. For XY_DIAG_BD measure the diagonal B to D
1056
+ *  4. For XY_SIDE_AD measure the edge A to D
1057
+ *
1058
+ * Marlin automatically computes skew factors from these measurements.
1059
+ * Skew factors may also be computed and set manually:
1060
+ *
1061
+ *  - Compute AB     : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
1062
+ *  - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
1063
+ *
1064
+ * If desired, follow the same procedure for XZ and YZ.
1065
+ * Use these diagrams for reference:
1066
+ *
1067
+ *    Y                     Z                     Z
1068
+ *    ^     B-------C       ^     B-------C       ^     B-------C
1069
+ *    |    /       /        |    /       /        |    /       /
1070
+ *    |   /       /         |   /       /         |   /       /
1071
+ *    |  A-------D          |  A-------D          |  A-------D
1072
+ *    +-------------->X     +-------------->X     +-------------->Y
1073
+ *     XY_SKEW_FACTOR        XZ_SKEW_FACTOR        YZ_SKEW_FACTOR
1074
+ */
1075
+//#define SKEW_CORRECTION
1076
+
1077
+#if ENABLED(SKEW_CORRECTION)
1078
+  // Input all length measurements here:
1079
+  #define XY_DIAG_AC 282.8427124746
1080
+  #define XY_DIAG_BD 282.8427124746
1081
+  #define XY_SIDE_AD 200
1082
+
1083
+  // Or, set the default skew factors directly here
1084
+  // to override the above measurements:
1085
+  #define XY_SKEW_FACTOR 0.0
1086
+
1087
+  //#define SKEW_CORRECTION_FOR_Z
1088
+  #if ENABLED(SKEW_CORRECTION_FOR_Z)
1089
+    #define XZ_DIAG_AC 282.8427124746
1090
+    #define XZ_DIAG_BD 282.8427124746
1091
+    #define YZ_DIAG_AC 282.8427124746
1092
+    #define YZ_DIAG_BD 282.8427124746
1093
+    #define YZ_SIDE_AD 200
1094
+    #define XZ_SKEW_FACTOR 0.0
1095
+    #define YZ_SKEW_FACTOR 0.0
1096
+  #endif
1097
+
1098
+  // Enable this option for M852 to set skew at runtime
1099
+  //#define SKEW_CORRECTION_GCODE
1100
+#endif
1101
+
975 1102
 //=============================================================================
976 1103
 //============================= Additional Features ===========================
977 1104
 //=============================================================================
@@ -998,11 +1125,12 @@
998 1125
 //
999 1126
 #define HOST_KEEPALIVE_FEATURE        // Disable this if your host doesn't like keepalive messages
1000 1127
 #define DEFAULT_KEEPALIVE_INTERVAL 2  // Number of seconds between "busy" messages. Set with M113.
1128
+#define BUSY_WHILE_HEATING            // Some hosts require "busy" messages even during heating
1001 1129
 
1002 1130
 //
1003 1131
 // M100 Free Memory Watcher
1004 1132
 //
1005
-//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
1133
+//#define M100_FREE_MEMORY_WATCHER    // Add M100 (Free Memory Watcher) to debug memory usage
1006 1134
 
1007 1135
 //
1008 1136
 // G20/G21 Inch mode support
@@ -1147,11 +1275,11 @@
1147 1275
  *
1148 1276
  * Select the language to display on the LCD. These languages are available:
1149 1277
  *
1150
- *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
1151
- *    it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
1152
- *    zh_CN, zh_TW, test
1278
+ *    en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
1279
+ *    hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
1280
+ *    tr, uk, zh_CN, zh_TW, test
1153 1281
  *
1154
- * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1282
+ * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
1155 1283
  */
1156 1284
 #define LCD_LANGUAGE en
1157 1285
 
@@ -1173,7 +1301,7 @@
1173 1301
  *  - Click the controller to view the LCD menu
1174 1302
  *  - The LCD will display Japanese, Western, or Cyrillic text
1175 1303
  *
1176
- * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
1304
+ * See http://marlinfw.org/docs/development/lcd_language.html
1177 1305
  *
1178 1306
  * :['JAPANESE', 'WESTERN', 'CYRILLIC']
1179 1307
  */
@@ -1279,8 +1407,8 @@
1279 1407
 // Note: Test audio output with the G-Code:
1280 1408
 //  M300 S<frequency Hz> P<duration ms>
1281 1409
 //
1282
-//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
1283
-//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
1410
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
1411
+//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
1284 1412
 
1285 1413
 //
1286 1414
 // CONTROLLER TYPE: Standard
@@ -1388,11 +1516,13 @@
1388 1516
 //#define CARTESIO_UI
1389 1517
 
1390 1518
 //
1391
-// ANET_10 Controller supported displays.
1519
+// ANET and Tronxy Controller supported displays.
1392 1520
 //
1393
-//#define ANET_KEYPAD_LCD         // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1521
+//#define ZONESTAR_LCD            // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
1394 1522
                                   // This LCD is known to be susceptible to electrical interference
1395 1523
                                   // which scrambles the display.  Pressing any button clears it up.
1524
+                                  // This is a LCD2004 display with 5 analog buttons.
1525
+
1396 1526
 //#define ANET_FULL_GRAPHICS_LCD  // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
1397 1527
                                   // A clone of the RepRapDiscount full graphics display but with
1398 1528
                                   // different pins/wiring (see pins_ANET_10.h).
@@ -1452,11 +1582,6 @@
1452 1582
 //#define U8GLIB_SSD1306
1453 1583
 
1454 1584
 //
1455
-// TinyBoy2 128x64 OLED / Encoder Panel
1456
-//
1457
-//#define OLED_PANEL_TINYBOY2
1458
-
1459
-//
1460 1585
 // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules
1461 1586
 //
1462 1587
 //#define SAV_3DGLCD
@@ -1473,6 +1598,45 @@
1473 1598
 //
1474 1599
 //#define SAV_3DLCD
1475 1600
 
1601
+//
1602
+// TinyBoy2 128x64 OLED / Encoder Panel
1603
+//
1604
+//#define OLED_PANEL_TINYBOY2
1605
+
1606
+//
1607
+// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
1608
+// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
1609
+//
1610
+//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
1611
+
1612
+//
1613
+// MKS MINI12864 with graphic controller and SD support
1614
+// http://reprap.org/wiki/MKS_MINI_12864
1615
+//
1616
+//#define MKS_MINI_12864
1617
+
1618
+//
1619
+// Factory display for Creality CR-10
1620
+// https://www.aliexpress.com/item/Universal-LCD-12864-3D-Printer-Display-Screen-With-Encoder-For-CR-10-CR-7-Model/32833148327.html
1621
+//
1622
+// This is RAMPS-compatible using a single 10-pin connector.
1623
+// (For CR-10 owners who want to replace the Melzi Creality board but retain the display)
1624
+//
1625
+//#define CR10_STOCKDISPLAY
1626
+
1627
+//
1628
+// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
1629
+// http://reprap.org/wiki/MKS_12864OLED
1630
+//
1631
+// Tiny, but very sharp OLED display
1632
+//
1633
+//#define MKS_12864OLED
1634
+
1635
+// Silvergate GLCD controller
1636
+// http://github.com/android444/Silvergate
1637
+//
1638
+//#define SILVER_GATE_GLCD_CONTROLLER
1639
+
1476 1640
 //=============================================================================
1477 1641
 //=============================== Extra Features ==============================
1478 1642
 //=============================================================================
@@ -1529,16 +1693,22 @@
1529 1693
  * Adds the M150 command to set the LED (or LED strip) color.
1530 1694
  * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
1531 1695
  * luminance values can be set from 0 to 255.
1696
+ * For Neopixel LED an overall brightness parameter is also available.
1532 1697
  *
1533 1698
  * *** CAUTION ***
1534 1699
  *  LED Strips require a MOFSET Chip between PWM lines and LEDs,
1535 1700
  *  as the Arduino cannot handle the current the LEDs will require.
1536 1701
  *  Failure to follow this precaution can destroy your Arduino!
1702
+ *  NOTE: A separate 5V power supply is required! The Neopixel LED needs
1703
+ *  more current than the Arduino 5V linear regulator can produce.
1537 1704
  * *** CAUTION ***
1538 1705
  *
1706
+ * LED Type. Enable only one of the following two options.
1707
+ *
1539 1708
  */
1540 1709
 //#define RGB_LED
1541 1710
 //#define RGBW_LED
1711
+
1542 1712
 #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
1543 1713
   #define RGB_LED_R_PIN 34
1544 1714
   #define RGB_LED_G_PIN 43
@@ -1546,6 +1716,17 @@
1546 1716
   #define RGB_LED_W_PIN -1
1547 1717
 #endif
1548 1718
 
1719
+// Support for Adafruit Neopixel LED driver
1720
+//#define NEOPIXEL_LED
1721
+#if ENABLED(NEOPIXEL_LED)
1722
+  #define NEOPIXEL_TYPE   NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
1723
+  #define NEOPIXEL_PIN    4        // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
1724
+  #define NEOPIXEL_PIXELS 30       // Number of LEDs in the strip
1725
+  #define NEOPIXEL_IS_SEQUENTIAL   // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
1726
+  #define NEOPIXEL_BRIGHTNESS 127  // Initial brightness (0-255)
1727
+  //#define NEOPIXEL_STARTUP_TEST  // Cycle through colors at startup
1728
+#endif
1729
+
1549 1730
 /**
1550 1731
  * Printer Event LEDs
1551 1732
  *
@@ -1557,68 +1738,32 @@
1557 1738
  *  - Change to green once print has finished
1558 1739
  *  - Turn off after the print has finished and the user has pushed a button
1559 1740
  */
1560
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)
1741
+#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
1561 1742
   #define PRINTER_EVENT_LEDS
1562 1743
 #endif
1563 1744
 
1564
-/*********************************************************************\
1565
-* R/C SERVO support
1566
-* Sponsored by TrinityLabs, Reworked by codexmas
1567
-**********************************************************************/
1745
+/**
1746
+ * R/C SERVO support
1747
+ * Sponsored by TrinityLabs, Reworked by codexmas
1748
+ */
1568 1749
 
1569
-// Number of servos
1570
-//
1571
-// If you select a configuration below, this will receive a default value and does not need to be set manually
1572
-// set it manually if you have more servos than extruders and wish to manually control some
1573
-// leaving it undefined or defining as 0 will disable the servo subsystem
1574
-// If unsure, leave commented / disabled
1575
-//
1750
+/**
1751
+ * Number of servos
1752
+ *
1753
+ * For some servo-related options NUM_SERVOS will be set automatically.
1754
+ * Set this manually if there are extra servos needing manual control.
1755
+ * Leave undefined or set to 0 to entirely disable the servo subsystem.
1756
+ */
1576 1757
 //#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
1577 1758
 
1578 1759
 // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
1579 1760
 // 300ms is a good value but you can try less delay.
1580 1761
 // If the servo can't reach the requested position, increase it.
1581
-#define SERVO_DELAY 300
1762
+#define SERVO_DELAY { 300 }
1582 1763
 
1583 1764
 // Servo deactivation
1584 1765
 //
1585 1766
 // With this option servos are powered only during movement, then turned off to prevent jitter.
1586 1767
 //#define DEACTIVATE_SERVOS_AFTER_MOVE
1587 1768
 
1588
-/**
1589
- * Filament Width Sensor
1590
- *
1591
- * Measures the filament width in real-time and adjusts
1592
- * flow rate to compensate for any irregularities.
1593
- *
1594
- * Also allows the measured filament diameter to set the
1595
- * extrusion rate, so the slicer only has to specify the
1596
- * volume.
1597
- *
1598
- * Only a single extruder is supported at this time.
1599
- *
1600
- *  34 RAMPS_14    : Analog input 5 on the AUX2 connector
1601
- *  81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
1602
- * 301 RAMBO       : Analog input 3
1603
- *
1604
- * Note: May require analog pins to be defined for other boards.
1605
- */
1606
-//#define FILAMENT_WIDTH_SENSOR
1607
-
1608
-#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00   // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
1609
-
1610
-#if ENABLED(FILAMENT_WIDTH_SENSOR)
1611
-  #define FILAMENT_SENSOR_EXTRUDER_NUM 0    // Index of the extruder that has the filament sensor (0,1,2,3)
1612
-  #define MEASUREMENT_DELAY_CM        14    // (cm) The distance from the filament sensor to the melting chamber
1613
-
1614
-  #define MEASURED_UPPER_LIMIT         3.30 // (mm) Upper limit used to validate sensor reading
1615
-  #define MEASURED_LOWER_LIMIT         1.90 // (mm) Lower limit used to validate sensor reading
1616
-  #define MAX_MEASUREMENT_DELAY       20    // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
1617
-
1618
-  #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
1619
-
1620
-  // Display filament width on the LCD status line. Status messages will expire after 5 seconds.
1621
-  //#define FILAMENT_LCD_DISPLAY
1622
-#endif
1623
-
1624 1769
 #endif // CONFIGURATION_H

Marlin/example_configurations/K8400/Configuration_adv.h → Marlin/example_configurations/Velleman/K8400/Configuration_adv.h 파일 보기


이 변경점에서 너무 많은 파일들이 변경되어 몇몇 파일들은 표시되지 않았습니다.

Loading…
취소
저장