Selaa lähdekoodia

Merge branch 'Release-1.1.0-RC4' into RC

Scott Lahteine 9 vuotta sitten
vanhempi
commit
dd4d860ad7
100 muutettua tiedostoa jossa 7693 lisäystä ja 7121 poistoa
  1. 3
    0
      .gitignore
  2. 98
    142
      .travis.yml
  3. 1
    1
      ArduinoAddons/Arduino_1.6.x/hardware/marlin/avr/boards.txt
  4. 4
    0
      LinuxAddons/bin/build_marlin
  5. 5
    0
      LinuxAddons/bin/opt_disable
  6. 5
    0
      LinuxAddons/bin/opt_enable
  7. 5
    0
      LinuxAddons/bin/opt_enable_adv
  8. 3
    0
      LinuxAddons/bin/opt_set
  9. 3
    0
      LinuxAddons/bin/opt_set_adv
  10. 3
    0
      LinuxAddons/bin/pins_set
  11. 5
    0
      LinuxAddons/bin/restore_configs
  12. 3
    0
      LinuxAddons/bin/use_example_configs
  13. 111
    20
      Marlin/Conditionals.h
  14. 153
    104
      Marlin/Configuration.h
  15. 102
    75
      Marlin/Configuration_adv.h
  16. 4
    4
      Marlin/Default_Version.h
  17. 9
    6
      Marlin/Makefile
  18. 36
    27
      Marlin/Marlin.h
  19. 4
    0
      Marlin/Marlin.ino
  20. 40
    31
      Marlin/MarlinSerial.cpp
  21. 34
    16
      Marlin/MarlinSerial.h
  22. 949
    571
      Marlin/Marlin_main.cpp
  23. 63
    16
      Marlin/SanityCheck.h
  24. 6
    2
      Marlin/Sd2Card.cpp
  25. 4
    4
      Marlin/Sd2PinMap.h
  26. 8
    9
      Marlin/SdBaseFile.cpp
  27. 5
    5
      Marlin/SdBaseFile.h
  28. 2
    2
      Marlin/SdVolume.cpp
  29. 3
    0
      Marlin/boards.h
  30. 13
    12
      Marlin/cardreader.cpp
  31. 1
    0
      Marlin/cardreader.h
  32. 99
    75
      Marlin/configuration_store.cpp
  33. 0
    1
      Marlin/configurator/config/_htaccess
  34. 0
    64
      Marlin/configurator/config/boards.h
  35. 0
    228
      Marlin/configurator/config/language.h
  36. 0
    344
      Marlin/configurator/css/configurator.css
  37. BIN
      Marlin/configurator/css/logo.png
  38. 0
    129
      Marlin/configurator/index.html
  39. 0
    2
      Marlin/configurator/js/FileSaver.min.js
  40. 0
    79
      Marlin/configurator/js/binaryfileuploader.js
  41. 0
    168
      Marlin/configurator/js/binarystring.js
  42. 0
    1432
      Marlin/configurator/js/configurator.js
  43. 0
    524
      Marlin/configurator/js/jcanvas.js
  44. 0
    4
      Marlin/configurator/js/jquery-2.1.3.min.js
  45. 0
    220
      Marlin/configurator/js/jstepper.js
  46. 0
    14
      Marlin/configurator/js/jszip.min.js
  47. 115
    0
      Marlin/dac_mcp4728.cpp
  48. 44
    0
      Marlin/dac_mcp4728.h
  49. 75
    43
      Marlin/dogm_lcd_implementation.h
  50. 152
    102
      Marlin/example_configurations/Felix/Configuration.h
  51. 200
    117
      Marlin/example_configurations/Felix/Configuration_DUAL.h
  52. 83
    58
      Marlin/example_configurations/Felix/Configuration_adv.h
  53. 156
    103
      Marlin/example_configurations/Hephestos/Configuration.h
  54. 85
    60
      Marlin/example_configurations/Hephestos/Configuration_adv.h
  55. 210
    163
      Marlin/example_configurations/Hephestos_2/Configuration.h
  56. 630
    0
      Marlin/example_configurations/Hephestos_2/Configuration_adv.h
  57. 8
    0
      Marlin/example_configurations/Hephestos_2/readme.md
  58. 192
    115
      Marlin/example_configurations/K8200/Configuration.h
  59. 101
    71
      Marlin/example_configurations/K8200/Configuration_adv.h
  60. 152
    102
      Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h
  61. 164
    102
      Marlin/example_configurations/RigidBot/Configuration.h
  62. 81
    51
      Marlin/example_configurations/RigidBot/Configuration_adv.h
  63. 159
    109
      Marlin/example_configurations/SCARA/Configuration.h
  64. 83
    58
      Marlin/example_configurations/SCARA/Configuration_adv.h
  65. 158
    106
      Marlin/example_configurations/TAZ4/Configuration.h
  66. 71
    41
      Marlin/example_configurations/TAZ4/Configuration_adv.h
  67. 153
    102
      Marlin/example_configurations/WITBOX/Configuration.h
  68. 85
    60
      Marlin/example_configurations/WITBOX/Configuration_adv.h
  69. 153
    103
      Marlin/example_configurations/adafruit/ST7565/Configuration.h
  70. 158
    104
      Marlin/example_configurations/delta/biv2.5/Configuration.h
  71. 85
    59
      Marlin/example_configurations/delta/biv2.5/Configuration_adv.h
  72. 161
    112
      Marlin/example_configurations/delta/generic/Configuration.h
  73. 83
    58
      Marlin/example_configurations/delta/generic/Configuration_adv.h
  74. 160
    107
      Marlin/example_configurations/delta/kossel_mini/Configuration.h
  75. 83
    58
      Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h
  76. 163
    109
      Marlin/example_configurations/delta/kossel_pro/Configuration.h
  77. 83
    58
      Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h
  78. 944
    0
      Marlin/example_configurations/delta/kossel_xl/Configuration.h
  79. 102
    74
      Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h
  80. 21
    0
      Marlin/example_configurations/delta/kossel_xl/README.md
  81. 153
    102
      Marlin/example_configurations/makibox/Configuration.h
  82. 88
    62
      Marlin/example_configurations/makibox/Configuration_adv.h
  83. 152
    103
      Marlin/example_configurations/tvrrug/Round2/Configuration.h
  84. 83
    58
      Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h
  85. 47
    44
      Marlin/language.h
  86. 2
    1
      Marlin/language_an.h
  87. 2
    1
      Marlin/language_bg.h
  88. 2
    1
      Marlin/language_ca.h
  89. 3
    2
      Marlin/language_cn.h
  90. 2
    1
      Marlin/language_cz.h
  91. 2
    1
      Marlin/language_da.h
  92. 2
    1
      Marlin/language_de.h
  93. 5
    2
      Marlin/language_en.h
  94. 3
    1
      Marlin/language_es.h
  95. 2
    1
      Marlin/language_eu.h
  96. 2
    1
      Marlin/language_fi.h
  97. 2
    1
      Marlin/language_fr.h
  98. 1
    1
      Marlin/language_gl.h
  99. 3
    1
      Marlin/language_it.h
  100. 0
    0
      Marlin/language_kana.h

+ 3
- 0
.gitignore Näytä tiedosto

@@ -15,3 +15,6 @@ applet/
15 15
 *.bak
16 16
 *.DS_Store
17 17
 *.idea
18
+*.s
19
+*.i
20
+*.ii

+ 98
- 142
.travis.yml Näytä tiedosto

@@ -26,188 +26,144 @@ install:
26 26
   - mv LiquidCrystal_I2C/LiquidCrystal_I2C /usr/local/share/arduino/libraries/LiquidCrystal_I2C
27 27
   - git clone https://github.com/lincomatic/LiquidTWI2.git
28 28
   - mv LiquidTWI2 /usr/local/share/arduino/libraries/LiquidTWI2
29
-  # Install astyle
30
-  - wget https://github.com/timonwong/astyle-mirror/archive/master.zip
31
-  - unzip master.zip
32
-  - cd astyle-mirror-master/build/gcc/
33
-  - make prefix=$HOME astyle install
34 29
 before_script:
35 30
   # arduino requires an X server even with command line
36 31
   # https://github.com/arduino/Arduino/issues/1981
37 32
   - Xvfb :1 -screen 0 1024x768x16 &> xvfb.log &
38 33
   # change back to home directory for compiling
39 34
   - cd $TRAVIS_BUILD_DIR
40
-  # Check style
41
-  # ~/bin/astyle --recursive --options=.astylerc "Marlin/*.h" "Marlin/*.cpp"
42 35
 script:
43
-  # Abort on style errors
44
-  # if [ "0" != `find . -name "*.orig" | wc -l` ] ; then echo "Improperly styled source -- run astyle" ; exit -999; fi
45
-  # Relaxed Travis check
46
-  # if [ "0" != `find . -name "*.orig" | wc -l` ] ; then echo "Improperly styled source -- run astyle" ; fi
47 36
   # build default config
48
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
49
-  # backup configuration.h
37
+  - build_marlin
38
+  # Backup Configuration.h, Configuration_adv.h, and pins_RAMPS_14.h
50 39
   - cp Marlin/Configuration.h Marlin/Configuration.h.backup
51 40
   - cp Marlin/Configuration_adv.h Marlin/Configuration_adv.h.backup
52
-  - cp Marlin/pins_RAMPS_13.h Marlin/pins_RAMPS_13.h.backup
41
+  - cp Marlin/pins_RAMPS_14.h Marlin/pins_RAMPS_14.h.backup
53 42
   # add sensor for bed
54
-  - sed -i 's/#define TEMP_SENSOR_BED 0/#define TEMP_SENSOR_BED 1/g' Marlin/Configuration.h
55
-  - rm -rf .build/
56
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
43
+  - opt_set TEMP_SENSOR_BED 1
44
+  - build_marlin
57 45
   # change extruder numbers from 1 to 2
58
-  - sed -i 's/#define MOTHERBOARD BOARD_RAMPS_13_EFB/#define MOTHERBOARD BOARD_RAMPS_13_EEB/g' Marlin/Configuration.h
59
-  - sed -i 's/#define EXTRUDERS 1/#define EXTRUDERS 2/g' Marlin/Configuration.h
60
-  - sed -i 's/#define TEMP_SENSOR_1 0/#define TEMP_SENSOR_1 1/g' Marlin/Configuration.h
46
+  - opt_set MOTHERBOARD BOARD_RAMPS_14_EEB
47
+  - opt_set EXTRUDERS 2
48
+  - opt_set TEMP_SENSOR_1 1
61 49
   #- cat Marlin/Configuration.h
62
-  - rm -rf .build/
63
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
50
+  - build_marlin
64 51
   # change extruder numbers from 2 to 3, needs to be a board with 3 extruders defined in pins.h 
65
-  - sed -i 's/#define MOTHERBOARD BOARD_RAMPS_13_EEB/#define MOTHERBOARD BOARD_RUMBA/g' Marlin/Configuration.h
66
-  - sed -i 's/#define EXTRUDERS 2/#define EXTRUDERS 3/g' Marlin/Configuration.h
67
-  - sed -i 's/#define TEMP_SENSOR_2 0/#define TEMP_SENSOR_2 1/g' Marlin/Configuration.h
68
-  - rm -rf .build/
69
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
52
+  - opt_set MOTHERBOARD BOARD_RUMBA
53
+  - opt_set EXTRUDERS 3
54
+  - opt_set TEMP_SENSOR_2 1
55
+  - build_marlin
70 56
   # enable PIDTEMPBED 
71
-  - cp Marlin/Configuration.h.backup Marlin/Configuration.h
72
-  - sed -i 's/\/\/#define PIDTEMPBED/#define PIDTEMPBED/g' Marlin/Configuration.h
73
-  - rm -rf .build/
74
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
57
+  - restore_configs
58
+  - opt_enable PIDTEMPBED
59
+  - build_marlin
75 60
   # enable AUTO_BED_LEVELING
76
-  - cp Marlin/Configuration.h.backup Marlin/Configuration.h
77
-  - sed -i 's/\/\/#define ENABLE_AUTO_BED_LEVELING/#define ENABLE_AUTO_BED_LEVELING/g' Marlin/Configuration.h
78
-  - rm -rf .build/
79
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
61
+  - restore_configs
62
+  - opt_enable ENABLE_AUTO_BED_LEVELING
63
+  - build_marlin
80 64
   # enable AUTO_BED_LEVELING with servos
81
-  - cp Marlin/Configuration.h.backup Marlin/Configuration.h
82
-  - sed -i 's/\/\/#define ENABLE_AUTO_BED_LEVELING/#define ENABLE_AUTO_BED_LEVELING/g' Marlin/Configuration.h
83
-  - sed -i 's/\/\/#define NUM_SERVOS/#define NUM_SERVOS/g' Marlin/Configuration.h
84
-  - sed -i 's/\/\/#define Z_ENDSTOP_SERVO_NR/#define Z_ENDSTOP_SERVO_NR/g' Marlin/Configuration.h
85
-  - sed -i 's/\/\/#define SERVO_ENDSTOP_ANGLES/#define SERVO_ENDSTOP_ANGLES/g' Marlin/Configuration.h
86
-  - sed -i 's/\/\/#define DEACTIVATE_SERVOS_AFTER_MOVE/#define DEACTIVATE_SERVOS_AFTER_MOVE/g' Marlin/Configuration.h
87
-  - rm -rf .build/
88
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
65
+  - restore_configs
66
+  - opt_enable ENABLE_AUTO_BED_LEVELING NUM_SERVOS Z_ENDSTOP_SERVO_NR SERVO_ENDSTOP_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE
67
+  - build_marlin
89 68
   # enable EEPROM_SETTINGS & EEPROM_CHITCHAT
90
-  - cp Marlin/Configuration.h.backup Marlin/Configuration.h
91
-  - sed -i 's/\/\/#define EEPROM_SETTINGS/#define EEPROM_SETTINGS/g' Marlin/Configuration.h
92
-  - sed -i 's/\/\/#define EEPROM_CHITCHAT/#define EEPROM_CHITCHAT/g' Marlin/Configuration.h
93
-  - rm -rf .build/
94
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
69
+  - restore_configs
70
+  - opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT
71
+  - build_marlin
95 72
   ### LCDS ###
96 73
   # ULTIMAKERCONTROLLER
97
-  - cp Marlin/Configuration.h.backup Marlin/Configuration.h
98
-  - sed -i 's/\/\/#define ULTIMAKERCONTROLLER/#define ULTIMAKERCONTROLLER/g' Marlin/Configuration.h
99
-  - rm -rf .build/
100
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
74
+  - restore_configs
75
+  - opt_enable ULTIMAKERCONTROLLER
76
+  - build_marlin
101 77
   # MAKRPANEL
102 78
   # Needs to use melzi and sanguino hardware
103
-  #- cp Marlin/Configuration.h.backup Marlin/Configuration.h
104
-  #- sed -i 's/\/\/#define MAKRPANEL/#define MAKRPANEL/g' Marlin/Configuration.h
105
-  #- rm -rf .build/
106
-  #- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
79
+  #- restore_configs
80
+  #- opt_enable MAKRPANEL
81
+  #- build_marlin
107 82
   # REPRAP_DISCOUNT_SMART_CONTROLLER
108
-  - cp Marlin/Configuration.h.backup Marlin/Configuration.h
109
-  - sed -i 's/\/\/#define REPRAP_DISCOUNT_SMART_CONTROLLER/#define REPRAP_DISCOUNT_SMART_CONTROLLER/g' Marlin/Configuration.h
110
-  - rm -rf .build/
111
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
112
-  # G3D_PANE
113
-  - cp Marlin/Configuration.h.backup Marlin/Configuration.h
114
-  - sed -i 's/\/\/#define G3D_PANEL/#define G3D_PANEL/g' Marlin/Configuration.h
115
-  - rm -rf .build/
116
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
83
+  - restore_configs
84
+  - opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT
85
+  - build_marlin
86
+  # G3D_PANEL
87
+  - restore_configs
88
+  - opt_enable G3D_PANEL SDSUPPORT
89
+  - build_marlin
117 90
   # REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
118
-  - cp Marlin/Configuration.h.backup Marlin/Configuration.h
119
-  - sed -i 's/\/\/#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER/#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER/g' Marlin/Configuration.h
120
-  - rm -rf .build/
121
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
122
-  # REPRAPWORLD_KEYPAD 
91
+  - restore_configs
92
+  - opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
93
+  - build_marlin
94
+  # REPRAPWORLD_KEYPAD
123 95
   # Cant find configuration details to get it to compile
124
-  #- cp Marlin/Configuration.h.backup Marlin/Configuration.h
125
-  #- sed -i 's/\/\/#define ULTRA_LCD/#define ULTRA_LCD/g' Marlin/Configuration.h
126
-  #- sed -i 's/\/\/#define REPRAPWORLD_KEYPAD/#define REPRAPWORLD_KEYPAD/g' Marlin/Configuration.h
127
-  #- sed -i 's/\/\/#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0/#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0/g' Marlin/Configuration.h
128
-  #- rm -rf .build/
129
-  #- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
96
+  #- restore_configs
97
+  #- opt_enable ULTRA_LCD REPRAPWORLD_KEYPAD REPRAPWORLD_KEYPAD_MOVE_STEP
98
+  #- build_marlin
130 99
   # RA_CONTROL_PANEL
131
-  - cp Marlin/Configuration.h.backup Marlin/Configuration.h
132
-  - sed -i 's/\/\/#define RA_CONTROL_PANEL/#define RA_CONTROL_PANEL/g' Marlin/Configuration.h
133
-  - rm -rf .build/
134
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
100
+  - restore_configs
101
+  - opt_enable RA_CONTROL_PANEL
102
+  - build_marlin
135 103
   ### I2C PANELS ###
136 104
   # LCD_I2C_SAINSMART_YWROBOT
137 105
   # Failing at the moment needs different library 
138
-  #- cp Marlin/Configuration.h.backup Marlin/Configuration.h
139
-  #- sed -i 's/\/\/#define LCD_I2C_SAINSMART_YWROBOT/#define LCD_I2C_SAINSMART_YWROBOT/g' Marlin/Configuration.h
140
-  #- rm -rf .build/
141
-  #- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
106
+  #- restore_configs
107
+  #- opt_enable LCD_I2C_SAINSMART_YWROBOT
108
+  #- build_marlin
142 109
   # LCD_I2C_PANELOLU2
143
-  - cp Marlin/Configuration.h.backup Marlin/Configuration.h
144
-  - sed -i 's/\/\/#define LCD_I2C_PANELOLU2/#define LCD_I2C_PANELOLU2/g' Marlin/Configuration.h
145
-  - rm -rf .build/
146
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
110
+  - restore_configs
111
+  - opt_enable LCD_I2C_PANELOLU2
112
+  - build_marlin
147 113
   # LCD_I2C_VIKI
148
-  - cp Marlin/Configuration.h.backup Marlin/Configuration.h
149
-  - sed -i 's/\/\/#define LCD_I2C_VIKI/#define LCD_I2C_VIKI/g' Marlin/Configuration.h
150
-  - rm -rf .build/
151
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
114
+  - restore_configs
115
+  - opt_enable LCD_I2C_VIKI
116
+  - build_marlin
117
+  # LCM1602
118
+  - restore_configs
119
+  - opt_enable LCM1602
120
+  - build_marlin
121
+  # Enable FILAMENTCHANGEENABLE
122
+  - restore_configs
123
+  - opt_enable FILAMENTCHANGEENABLE
124
+  - build_marlin
152 125
   # Enable filament sensor
153
-  - cp Marlin/Configuration.h.backup Marlin/Configuration.h
154
-  - sed -i 's/\/\/#define FILAMENT_SENSOR/#define FILAMENT_SENSOR/g' Marlin/Configuration.h
155
-  - rm -rf .build/
156
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
157
-   # Enable filament sensor with LCD display
158
-  - cp Marlin/Configuration.h.backup Marlin/Configuration.h
159
-  - sed -i 's/\/\/#define ULTIMAKERCONTROLLER/#define ULTIMAKERCONTROLLER/g' Marlin/Configuration.h
160
-  - sed -i 's/\/\/#define FILAMENT_SENSOR/#define FILAMENT_SENSOR/g' Marlin/Configuration.h
161
-  - sed -i 's/\/\/#define FILAMENT_LCD_DISPLAY/#define FILAMENT_LCD_DISPLAY/g' Marlin/Configuration.h
162
-  - rm -rf .build/
163
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
126
+  - restore_configs
127
+  - opt_enable FILAMENT_SENSOR
128
+  - build_marlin
129
+  # Enable filament sensor with LCD display
130
+  - restore_configs
131
+  - opt_enable ULTIMAKERCONTROLLER FILAMENT_SENSOR FILAMENT_LCD_DISPLAY
132
+  - build_marlin
164 133
   # Enable COREXY
165
-  - cp Marlin/Configuration.h.backup Marlin/Configuration.h
166
-  - sed -i 's/\/\/#define COREXY/#define COREXY/g' Marlin/Configuration.h
167
-  - rm -rf .build/
168
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
134
+  - restore_configs
135
+  - opt_enable COREXY
136
+  - build_marlin
169 137
   # Enable COREXZ
170
-  - cp Marlin/Configuration.h.backup Marlin/Configuration.h
171
-  - sed -i 's/\/\/#define COREXZ/#define COREXZ/g' Marlin/Configuration.h
172
-  - rm -rf .build/
173
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
138
+  - restore_configs
139
+  - opt_enable COREXZ
140
+  - build_marlin
174 141
   # Enable Z_DUAL_STEPPER_DRIVERS, Z_DUAL_ENDSTOPS
175
-  - cp Marlin/Configuration.h.backup Marlin/Configuration.h
176
-  - sed -i 's/\/\/#define Z_DUAL_STEPPER_DRIVERS/#define Z_DUAL_STEPPER_DRIVERS/g' Marlin/Configuration_adv.h
177
-  - sed -i 's/\ \ \/\/\ \#define Z_DUAL_ENDSTOPS/#define Z_DUAL_ENDSTOPS/g' Marlin/Configuration_adv.h
178
-  - sed -i 's/#define X_MAX_PIN           2/#define X_MAX_PIN          -1/g' Marlin/pins_RAMPS_13.h
179
-  - sed -i 's/\ \ \ \ \#define Z2_MAX_PIN 36/#define Z2_MAX_PIN  2/g' Marlin/Configuration_adv.h
180
-  - rm -rf .build/
181
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
182
-  - cp Marlin/Configuration.h.backup Marlin/Configuration.h
183
-  - cp Marlin/Configuration_adv.h.backup Marlin/Configuration_adv.h
184
-  - cp Marlin/pins_RAMPS_13.h.backup Marlin/pins_RAMPS_13.h
142
+  - restore_configs
143
+  - opt_enable_adv Z_DUAL_STEPPER_DRIVERS Z_DUAL_ENDSTOPS
144
+  - pins_set RAMPS_14 X_MAX_PIN -1
145
+  - opt_set_adv Z2_MAX_PIN 2
146
+  - build_marlin
147
+  - restore_configs
185 148
   ######## Example Configurations ##############
186 149
   # Delta Config (generic)
187
-  - cp Marlin/example_configurations/delta/generic/Configuration* Marlin/
188
-  - rm -rf .build/
189
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
150
+  - use_example_configs delta/generic
151
+  - build_marlin
190 152
   # Delta Config (generic) + ABL + ALLEN_KEY
191
-  - cp Marlin/example_configurations/delta/generic/Configuration* Marlin/
192
-  - sed -i 's/#define DISABLE_MIN_ENDSTOPS/\/\/#define DISABLE_MIN_ENDSTOPS/g' Marlin/Configuration.h
193
-  - sed -i 's/\/\/#define AUTO_BED_LEVELING_FEATURE/#define AUTO_BED_LEVELING_FEATURE/g' Marlin/Configuration.h
194
-  - sed -i 's/\/\/#define Z_PROBE_ALLEN_KEY/#define Z_PROBE_ALLEN_KEY/g' Marlin/Configuration.h
195
-  - rm -rf .build/
196
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
153
+  - use_example_configs delta/generic
154
+  - opt_disable DISABLE_MIN_ENDSTOPS
155
+  - opt_enable AUTO_BED_LEVELING_FEATURE Z_PROBE_ALLEN_KEY
156
+  - build_marlin
197 157
   # Delta Config (Mini Kossel)
198
-  - cp Marlin/example_configurations/delta/kossel_mini/Configuration* Marlin/
199
-  - rm -rf .build/
200
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
158
+  - use_example_configs delta/kossel_mini
159
+  - build_marlin
201 160
   # Makibox Config  need to check board type for Teensy++ 2.0
202
-  #- cp Marlin/example_configurations/makibox/Configuration* Marlin/
203
-  #- rm -rf .build/
204
-  #- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
161
+  #- use_example_configs makibox
162
+  #- build_marlin
205 163
   # SCARA Config
206
-  - cp Marlin/example_configurations/SCARA/Configuration* Marlin/
207
-  - rm -rf .build/
208
-  - DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
164
+  - use_example_configs SCARA
165
+  - build_marlin
209 166
   # tvrrug Config need to check board type for sanguino atmega644p
210
-  #- cp Marlin/example_configurations/tvrrug/Round2/Configuration* Marlin/
211
-  #- rm -rf .build/
212
-  #- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino
167
+  #- use_example_configs tvrrug/Round2
168
+  #- build_marlin
213 169
   ######## Board Types #############

+ 1
- 1
ArduinoAddons/Arduino_1.6.x/hardware/marlin/avr/boards.txt Näytä tiedosto

@@ -95,7 +95,7 @@ rambo.build.variant=rambo
95 95
 sanguino.name=Sanguino
96 96
 
97 97
 sanguino.upload.tool=arduino:avrdude
98
-sanguino.upload.protocol=stk500
98
+sanguino.upload.protocol=arduino
99 99
 sanguino.upload.maximum_size=131072
100 100
 sanguino.upload.speed=57600
101 101
 

+ 4
- 0
LinuxAddons/bin/build_marlin Näytä tiedosto

@@ -0,0 +1,4 @@
1
+#!/usr/bin/env bash
2
+
3
+rm -rf .build/
4
+DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega  Marlin/Marlin.ino

+ 5
- 0
LinuxAddons/bin/opt_disable Näytä tiedosto

@@ -0,0 +1,5 @@
1
+#!/usr/bin/env bash
2
+
3
+for opt in "$@" ; do
4
+  eval "sed -i 's/\(\/\/ *\)*\(\#define *$opt\)/\/\/\2/g' Marlin/Configuration.h"
5
+done

+ 5
- 0
LinuxAddons/bin/opt_enable Näytä tiedosto

@@ -0,0 +1,5 @@
1
+#!/usr/bin/env bash
2
+
3
+for opt in "$@" ; do
4
+  eval "sed -i 's/\/\/ *\(#define *$opt\)/\1/g' Marlin/Configuration.h"
5
+done

+ 5
- 0
LinuxAddons/bin/opt_enable_adv Näytä tiedosto

@@ -0,0 +1,5 @@
1
+#!/usr/bin/env bash
2
+
3
+for opt in "$@" ; do
4
+  eval "sed -i 's/\/\/ *\(#define *$opt\)/\1/g' Marlin/Configuration_adv.h"
5
+done

+ 3
- 0
LinuxAddons/bin/opt_set Näytä tiedosto

@@ -0,0 +1,3 @@
1
+#!/usr/bin/env bash
2
+
3
+eval "sed -i 's/\(#define *$1\) *.*$/\1 $2/g' Marlin/Configuration.h"

+ 3
- 0
LinuxAddons/bin/opt_set_adv Näytä tiedosto

@@ -0,0 +1,3 @@
1
+#!/usr/bin/env bash
2
+
3
+eval "sed -i 's/\(#define *$1\) *.*$/\1 $2/g' Marlin/Configuration_adv.h"

+ 3
- 0
LinuxAddons/bin/pins_set Näytä tiedosto

@@ -0,0 +1,3 @@
1
+#!/usr/bin/env bash
2
+
3
+eval "sed -i 's/\(#define *$2\) *.*$/\1 $3/g' Marlin/pins_$1.h"

+ 5
- 0
LinuxAddons/bin/restore_configs Näytä tiedosto

@@ -0,0 +1,5 @@
1
+#!/usr/bin/env bash
2
+
3
+cp Marlin/Configuration.h.backup      Marlin/Configuration.h
4
+cp Marlin/Configuration_adv.h.backup  Marlin/Configuration_adv.h
5
+cp Marlin/pins_RAMPS_14.h.backup      Marlin/pins_RAMPS_14.h

+ 3
- 0
LinuxAddons/bin/use_example_configs Näytä tiedosto

@@ -0,0 +1,3 @@
1
+#!/usr/bin/env bash
2
+
3
+eval "cp Marlin/example_configurations/$1/Configuration* Marlin/"

+ 111
- 20
Marlin/Conditionals.h Näytä tiedosto

@@ -45,11 +45,26 @@
45 45
     #define DOGLCD  // Support for I2C LCD 128x64 (Controller SSD1306 graphic Display Family)
46 46
   #endif
47 47
 
48
-
49 48
   #if ENABLED(PANEL_ONE)
50 49
     #define ULTIMAKERCONTROLLER
51 50
   #endif
52 51
 
52
+  #if ENABLED(BQ_LCD_SMART_CONTROLLER)
53
+    #define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
54
+
55
+    #ifndef ENCODER_PULSES_PER_STEP
56
+      #define ENCODER_PULSES_PER_STEP 4
57
+    #endif
58
+
59
+    #ifndef ENCODER_STEPS_PER_MENU_ITEM
60
+      #define ENCODER_STEPS_PER_MENU_ITEM 1
61
+    #endif
62
+
63
+    #ifndef LONG_FILENAME_HOST_SUPPORT
64
+      #define LONG_FILENAME_HOST_SUPPORT
65
+    #endif
66
+  #endif
67
+
53 68
   #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
54 69
     #define DOGLCD
55 70
     #define U8GLIB_ST7920
@@ -135,28 +150,35 @@
135 150
   // https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
136 151
 
137 152
   #if ENABLED(SAV_3DLCD)
138
-    #define SR_LCD_2W_NL    // Non latching 2 wire shiftregister
153
+    #define SR_LCD_2W_NL    // Non latching 2 wire shift register
139 154
     #define ULTIPANEL
140 155
     #define NEWPANEL
141 156
   #endif
142 157
 
158
+  #if ENABLED(DOGLCD) // Change number of lines to match the DOG graphic display
159
+    #ifndef LCD_WIDTH
160
+      #define LCD_WIDTH 22
161
+    #endif
162
+    #ifndef LCD_HEIGHT
163
+      #define LCD_HEIGHT 5
164
+    #endif
165
+  #endif
166
+
143 167
   #if ENABLED(ULTIPANEL)
144 168
     #define NEWPANEL  //enable this if you have a click-encoder panel
145 169
     #define ULTRA_LCD
146
-    #if ENABLED(DOGLCD) // Change number of lines to match the DOG graphic display
147
-      #define LCD_WIDTH 22
148
-      #define LCD_HEIGHT 5
149
-    #else
170
+    #ifndef LCD_WIDTH
150 171
       #define LCD_WIDTH 20
172
+    #endif
173
+    #ifndef LCD_HEIGHT
151 174
       #define LCD_HEIGHT 4
152 175
     #endif
153 176
   #else //no panel but just LCD
154 177
     #if ENABLED(ULTRA_LCD)
155
-      #if ENABLED(DOGLCD) // Change number of lines to match the 128x64 graphics display
156
-        #define LCD_WIDTH 22
157
-        #define LCD_HEIGHT 5
158
-      #else
178
+      #ifndef LCD_WIDTH
159 179
         #define LCD_WIDTH 16
180
+      #endif
181
+      #ifndef LCD_HEIGHT
160 182
         #define LCD_HEIGHT 2
161 183
       #endif
162 184
     #endif
@@ -242,9 +264,20 @@
242 264
   /**
243 265
    * Axis lengths
244 266
    */
245
-  #define X_MAX_LENGTH (X_MAX_POS - X_MIN_POS)
246
-  #define Y_MAX_LENGTH (Y_MAX_POS - Y_MIN_POS)
247
-  #define Z_MAX_LENGTH (Z_MAX_POS - Z_MIN_POS)
267
+  #define X_MAX_LENGTH (X_MAX_POS - (X_MIN_POS))
268
+  #define Y_MAX_LENGTH (Y_MAX_POS - (Y_MIN_POS))
269
+  #define Z_MAX_LENGTH (Z_MAX_POS - (Z_MIN_POS))
270
+
271
+  /**
272
+   * CoreXY and CoreXZ
273
+   */
274
+  #if ENABLED(COREXY)
275
+    #define CORE_AXIS_2 B_AXIS
276
+    #define CORE_AXIS_3 Z_AXIS
277
+  #elif ENABLED(COREXZ)
278
+    #define CORE_AXIS_2 C_AXIS
279
+    #define CORE_AXIS_3 Y_AXIS
280
+  #endif
248 281
 
249 282
   /**
250 283
    * SCARA
@@ -263,8 +296,8 @@
263 296
     #define Z_HOME_POS MANUAL_Z_HOME_POS
264 297
   #else //!MANUAL_HOME_POSITIONS – Use home switch positions based on homing direction and travel limits
265 298
     #if ENABLED(BED_CENTER_AT_0_0)
266
-      #define X_HOME_POS X_MAX_LENGTH * X_HOME_DIR * 0.5
267
-      #define Y_HOME_POS Y_MAX_LENGTH * Y_HOME_DIR * 0.5
299
+      #define X_HOME_POS (X_MAX_LENGTH) * (X_HOME_DIR) * 0.5
300
+      #define Y_HOME_POS (Y_MAX_LENGTH) * (Y_HOME_DIR) * 0.5
268 301
     #else
269 302
       #define X_HOME_POS (X_HOME_DIR < 0 ? X_MIN_POS : X_MAX_POS)
270 303
       #define Y_HOME_POS (Y_HOME_DIR < 0 ? Y_MIN_POS : Y_MAX_POS)
@@ -293,6 +326,13 @@
293 326
   #endif
294 327
 
295 328
   /**
329
+   * Avoid double-negatives for enabling features
330
+   */
331
+  #if DISABLED(DISABLE_HOST_KEEPALIVE)
332
+    #define HOST_KEEPALIVE_FEATURE
333
+  #endif
334
+
335
+  /**
296 336
    * MAX_STEP_FREQUENCY differs for TOSHIBA
297 337
    */
298 338
   #if ENABLED(CONFIG_STEPPERS_TOSHIBA)
@@ -312,14 +352,30 @@
312 352
    * Advance calculated values
313 353
    */
314 354
   #if ENABLED(ADVANCE)
315
-    #define EXTRUSION_AREA (0.25 * D_FILAMENT * D_FILAMENT * M_PI)
316
-    #define STEPS_PER_CUBIC_MM_E (axis_steps_per_unit[E_AXIS] / EXTRUSION_AREA)
355
+    #define EXTRUSION_AREA (0.25 * (D_FILAMENT) * (D_FILAMENT) * M_PI)
356
+    #define STEPS_PER_CUBIC_MM_E (axis_steps_per_unit[E_AXIS] / (EXTRUSION_AREA))
317 357
   #endif
318 358
 
319 359
   #if ENABLED(ULTIPANEL) && DISABLED(ELB_FULL_GRAPHIC_CONTROLLER)
320 360
     #undef SD_DETECT_INVERTED
321 361
   #endif
322 362
 
363
+  /**
364
+   * Set defaults for missing (newer) options
365
+   */
366
+  #ifndef DISABLE_INACTIVE_X
367
+    #define DISABLE_INACTIVE_X DISABLE_X
368
+  #endif
369
+  #ifndef DISABLE_INACTIVE_Y
370
+    #define DISABLE_INACTIVE_Y DISABLE_Y
371
+  #endif
372
+  #ifndef DISABLE_INACTIVE_Z
373
+    #define DISABLE_INACTIVE_Z DISABLE_Z
374
+  #endif
375
+  #ifndef DISABLE_INACTIVE_E
376
+    #define DISABLE_INACTIVE_E DISABLE_E
377
+  #endif
378
+
323 379
   // Power Signal Control Definitions
324 380
   // By default use ATX definition
325 381
   #ifndef POWER_SUPPLY
@@ -337,7 +393,10 @@
337 393
   /**
338 394
    * Temp Sensor defines
339 395
    */
340
-  #if TEMP_SENSOR_0 == -2
396
+  #if TEMP_SENSOR_0 == -3
397
+    #define HEATER_0_USES_MAX6675
398
+    #define MAX6675_IS_MAX31855
399
+  #elif TEMP_SENSOR_0 == -2
341 400
     #define HEATER_0_USES_MAX6675
342 401
   #elif TEMP_SENSOR_0 == -1
343 402
     #define HEATER_0_USES_AD595
@@ -422,7 +481,9 @@
422 481
   #define HAS_AUTO_FAN_2 (PIN_EXISTS(EXTRUDER_2_AUTO_FAN))
423 482
   #define HAS_AUTO_FAN_3 (PIN_EXISTS(EXTRUDER_3_AUTO_FAN))
424 483
   #define HAS_AUTO_FAN (HAS_AUTO_FAN_0 || HAS_AUTO_FAN_1 || HAS_AUTO_FAN_2 || HAS_AUTO_FAN_3)
425
-  #define HAS_FAN (PIN_EXISTS(FAN))
484
+  #define HAS_FAN0 (PIN_EXISTS(FAN))
485
+  #define HAS_FAN1 (PIN_EXISTS(FAN1) && CONTROLLERFAN_PIN != FAN1_PIN && EXTRUDER_0_AUTO_FAN_PIN != FAN1_PIN && EXTRUDER_1_AUTO_FAN_PIN != FAN1_PIN && EXTRUDER_2_AUTO_FAN_PIN != FAN1_PIN)
486
+  #define HAS_FAN2 (PIN_EXISTS(FAN2) && CONTROLLERFAN_PIN != FAN2_PIN && EXTRUDER_0_AUTO_FAN_PIN != FAN2_PIN && EXTRUDER_1_AUTO_FAN_PIN != FAN2_PIN && EXTRUDER_2_AUTO_FAN_PIN != FAN2_PIN)
426 487
   #define HAS_CONTROLLERFAN (PIN_EXISTS(CONTROLLERFAN))
427 488
   #define HAS_SERVOS (defined(NUM_SERVOS) && NUM_SERVOS > 0)
428 489
   #define HAS_SERVO_0 (PIN_EXISTS(SERVO0))
@@ -462,6 +523,7 @@
462 523
   #define HAS_E1_ENABLE (PIN_EXISTS(E1_ENABLE))
463 524
   #define HAS_E2_ENABLE (PIN_EXISTS(E2_ENABLE))
464 525
   #define HAS_E3_ENABLE (PIN_EXISTS(E3_ENABLE))
526
+  #define HAS_E4_ENABLE (PIN_EXISTS(E4_ENABLE))
465 527
   #define HAS_X_DIR (PIN_EXISTS(X_DIR))
466 528
   #define HAS_X2_DIR (PIN_EXISTS(X2_DIR))
467 529
   #define HAS_Y_DIR (PIN_EXISTS(Y_DIR))
@@ -472,6 +534,7 @@
472 534
   #define HAS_E1_DIR (PIN_EXISTS(E1_DIR))
473 535
   #define HAS_E2_DIR (PIN_EXISTS(E2_DIR))
474 536
   #define HAS_E3_DIR (PIN_EXISTS(E3_DIR))
537
+  #define HAS_E4_DIR (PIN_EXISTS(E4_DIR))
475 538
   #define HAS_X_STEP (PIN_EXISTS(X_STEP))
476 539
   #define HAS_X2_STEP (PIN_EXISTS(X2_STEP))
477 540
   #define HAS_Y_STEP (PIN_EXISTS(Y_STEP))
@@ -482,6 +545,7 @@
482 545
   #define HAS_E1_STEP (PIN_EXISTS(E1_STEP))
483 546
   #define HAS_E2_STEP (PIN_EXISTS(E2_STEP))
484 547
   #define HAS_E3_STEP (PIN_EXISTS(E3_STEP))
548
+  #define HAS_E4_STEP (PIN_EXISTS(E4_STEP))
485 549
 
486 550
   /**
487 551
    * Helper Macros for heaters and extruder fan
@@ -504,9 +568,31 @@
504 568
   #if HAS_HEATER_BED
505 569
     #define WRITE_HEATER_BED(v) WRITE(HEATER_BED_PIN, v)
506 570
   #endif
507
-  #if HAS_FAN
571
+
572
+  /**
573
+   * Up to 3 PWM fans
574
+   */
575
+  #if HAS_FAN2
576
+    #define FAN_COUNT 3
577
+  #elif HAS_FAN1
578
+    #define FAN_COUNT 2
579
+  #elif HAS_FAN0
580
+    #define FAN_COUNT 1
581
+  #else
582
+    #define FAN_COUNT 0
583
+  #endif
584
+
585
+  #if HAS_FAN0
508 586
     #define WRITE_FAN(v) WRITE(FAN_PIN, v)
587
+    #define WRITE_FAN0(v) WRITE_FAN(v)
588
+  #endif
589
+  #if HAS_FAN1
590
+    #define WRITE_FAN1(v) WRITE(FAN1_PIN, v)
509 591
   #endif
592
+  #if HAS_FAN2
593
+    #define WRITE_FAN2(v) WRITE(FAN2_PIN, v)
594
+  #endif
595
+  #define WRITE_FAN_N(n, v) WRITE_FAN##n(v)
510 596
 
511 597
   #define HAS_BUZZER (PIN_EXISTS(BEEPER) || defined(LCD_USE_I2C_BUZZER))
512 598
 
@@ -526,5 +612,10 @@
526 612
     #endif
527 613
   #endif
528 614
 
615
+  #if ( (HAS_Z_MIN && ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)) || HAS_Z_PROBE ) && \
616
+    ( ENABLED(FIX_MOUNTED_PROBE) || defined(Z_ENDSTOP_SERVO_NR) || ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED) )
617
+    #define HAS_Z_MIN_PROBE
618
+  #endif
619
+
529 620
 #endif //CONFIGURATION_LCD
530 621
 #endif //CONDITIONALS_H

+ 153
- 104
Marlin/Configuration.h Näytä tiedosto

@@ -70,7 +70,7 @@ Here are some standard links for getting your machine calibrated:
70 70
 // The following define selects which electronics board you have.
71 71
 // Please choose the name from boards.h that matches your setup
72 72
 #ifndef MOTHERBOARD
73
-  #define MOTHERBOARD BOARD_RAMPS_13_EFB
73
+  #define MOTHERBOARD BOARD_RAMPS_14_EFB
74 74
 #endif
75 75
 
76 76
 // Optional custom name for your RepStrap or other custom machine
@@ -110,6 +110,7 @@ Here are some standard links for getting your machine calibrated:
110 110
 //--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
111 111
 //
112 112
 //// Temperature sensor settings:
113
+// -3 is thermocouple with MAX31855 (only for sensor 0)
113 114
 // -2 is thermocouple with MAX6675 (only for sensor 0)
114 115
 // -1 is thermocouple with AD595
115 116
 // 0 is not used
@@ -129,6 +130,7 @@ Here are some standard links for getting your machine calibrated:
129 130
 // 13 is 100k Hisens 3950  1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
130 131
 // 20 is the PT100 circuit found in the Ultimainboard V2.x
131 132
 // 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
133
+// 70 is the 100K thermistor found in the bq Hephestos 2
132 134
 //
133 135
 //    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
134 136
 //                          (but gives greater accuracy and more stable PID)
@@ -144,7 +146,7 @@ Here are some standard links for getting your machine calibrated:
144 146
 //     Use it for Testing or Development purposes. NEVER for production machine.
145 147
 //#define DUMMY_THERMISTOR_998_VALUE 25
146 148
 //#define DUMMY_THERMISTOR_999_VALUE 100
147
-// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
149
+// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-3': "Thermocouple + MAX31855 (only for sensor 0)", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
148 150
 #define TEMP_SENSOR_0 1
149 151
 #define TEMP_SENSOR_1 0
150 152
 #define TEMP_SENSOR_2 0
@@ -178,14 +180,9 @@ Here are some standard links for getting your machine calibrated:
178 180
 #define HEATER_3_MAXTEMP 275
179 181
 #define BED_MAXTEMP 150
180 182
 
181
-// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
182
-// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
183
-// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
184
-//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
185
-
186 183
 // If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
187
-//#define EXTRUDER_WATTS (12.0*12.0/6.7) //  P=I^2/R
188
-//#define BED_WATTS (12.0*12.0/1.1)      // P=I^2/R
184
+//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
185
+//#define BED_WATTS (12.0*12.0/1.1)      // P=U^2/R
189 186
 
190 187
 //===========================================================================
191 188
 //============================= PID Settings ================================
@@ -253,13 +250,13 @@ Here are some standard links for getting your machine calibrated:
253 250
 
254 251
   #define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
255 252
 
256
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
253
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
257 254
   //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
258 255
   #define  DEFAULT_bedKp 10.00
259 256
   #define  DEFAULT_bedKi .023
260 257
   #define  DEFAULT_bedKd 305.4
261 258
 
262
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
259
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
263 260
   //from pidautotune
264 261
   //#define  DEFAULT_bedKp 97.1
265 262
   //#define  DEFAULT_bedKi 1.41
@@ -284,16 +281,15 @@ Here are some standard links for getting your machine calibrated:
284 281
 //===========================================================================
285 282
 
286 283
 /**
287
- * Thermal Runaway Protection protects your printer from damage and fire if a
284
+ * Thermal Protection protects your printer from damage and fire if a
288 285
  * thermistor falls out or temperature sensors fail in any way.
289 286
  *
290 287
  * The issue: If a thermistor falls out or a temperature sensor fails,
291 288
  * Marlin can no longer sense the actual temperature. Since a disconnected
292 289
  * thermistor reads as a low temperature, the firmware will keep the heater on.
293 290
  *
294
- * The solution: Once the temperature reaches the target, start observing.
295
- * If the temperature stays too far below the target (hysteresis) for too long,
296
- * the firmware will halt as a safety precaution.
291
+ * If you get "Thermal Runaway" or "Heating failed" errors the
292
+ * details can be tuned in Configuration_adv.h
297 293
  */
298 294
 
299 295
 #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
@@ -341,10 +337,52 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
341 337
 //#define DISABLE_MAX_ENDSTOPS
342 338
 //#define DISABLE_MIN_ENDSTOPS
343 339
 
344
-// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
345
-// This only affects a Z probe endstop if you have separate Z min endstop as well and have
346
-// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
347
-// this has no effect.
340
+//===========================================================================
341
+//============================= Z Probe Options =============================
342
+//===========================================================================
343
+
344
+// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
345
+// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
346
+//
347
+// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
348
+//
349
+// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
350
+// Example: To park the head outside the bed area when homing with G28.
351
+//
352
+// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
353
+//
354
+// For a servo-based Z probe, you must set up servo support below, including
355
+// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
356
+//
357
+// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
358
+// - Use 5V for powered (usu. inductive) sensors.
359
+// - Otherwise connect:
360
+//   - normally-closed switches to GND and D32.
361
+//   - normally-open switches to 5V and D32.
362
+//
363
+// Normally-closed switches are advised and are the default.
364
+//
365
+// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
366
+// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
367
+// default pin for all RAMPS-based boards. Some other boards map differently.
368
+// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
369
+//
370
+// WARNING:
371
+// Setting the wrong pin may have unexpected and potentially disastrous consequences.
372
+// Use with caution and do your homework.
373
+//
374
+//#define Z_MIN_PROBE_ENDSTOP
375
+
376
+// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
377
+// The Z_MIN_PIN will then be used for both Z-homing and probing.
378
+#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
379
+
380
+// To use a probe you must enable one of the two options above!
381
+
382
+// This option disables the use of the Z_MIN_PROBE_PIN
383
+// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
384
+// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
385
+// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
348 386
 //#define DISABLE_Z_MIN_PROBE_ENDSTOP
349 387
 
350 388
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
@@ -354,11 +392,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
354 392
 #define Z_ENABLE_ON 0
355 393
 #define E_ENABLE_ON 0 // For all extruders
356 394
 
357
-// Disables axis when it's not being used.
395
+// Disables axis stepper immediately when it's not being used.
358 396
 // WARNING: When motors turn off there is a chance of losing position accuracy!
359 397
 #define DISABLE_X false
360 398
 #define DISABLE_Y false
361 399
 #define DISABLE_Z false
400
+// Warn on display about possibly reduced accuracy
401
+//#define DISABLE_REDUCED_ACCURACY_WARNING
362 402
 
363 403
 // @section extruder
364 404
 
@@ -381,6 +421,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
381 421
 #define INVERT_E3_DIR false
382 422
 
383 423
 // @section homing
424
+//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
425
+                                    // Be sure you have this distance over your Z_MAX_POS in case.
384 426
 
385 427
 // ENDSTOP SETTINGS:
386 428
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
@@ -416,24 +458,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
416 458
 #endif
417 459
 
418 460
 //===========================================================================
419
-//=========================== Manual Bed Leveling ===========================
461
+//============================ Mesh Bed Leveling ============================
420 462
 //===========================================================================
421 463
 
422
-//#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
423 464
 //#define MESH_BED_LEVELING    // Enable mesh bed leveling.
424 465
 
425
-#if ENABLED(MANUAL_BED_LEVELING)
426
-  #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
427
-#endif  // MANUAL_BED_LEVELING
428
-
429 466
 #if ENABLED(MESH_BED_LEVELING)
430 467
   #define MESH_MIN_X 10
431
-  #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
468
+  #define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
432 469
   #define MESH_MIN_Y 10
433
-  #define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
470
+  #define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
434 471
   #define MESH_NUM_X_POINTS 3  // Don't use more than 7 points per axis, implementation limited.
435 472
   #define MESH_NUM_Y_POINTS 3
436 473
   #define MESH_HOME_SEARCH_Z 4  // Z after Home, bed somewhere below but above 0.0.
474
+
475
+  //#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
476
+
477
+  #if ENABLED(MANUAL_BED_LEVELING)
478
+    #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
479
+  #endif  // MANUAL_BED_LEVELING
480
+
437 481
 #endif  // MESH_BED_LEVELING
438 482
 
439 483
 //===========================================================================
@@ -444,7 +488,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
444 488
 
445 489
 //#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
446 490
 //#define DEBUG_LEVELING_FEATURE
447
-#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
491
+#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
448 492
 
449 493
 #if ENABLED(AUTO_BED_LEVELING_FEATURE)
450 494
 
@@ -456,7 +500,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
456 500
   //   This mode is preferred because there are more measurements.
457 501
   //
458 502
   // - "3-point" mode
459
-  //   Probe 3 arbitrary points on the bed (that aren't colinear)
503
+  //   Probe 3 arbitrary points on the bed (that aren't collinear)
460 504
   //   You specify the XY coordinates of all 3 points.
461 505
 
462 506
   // Enable this to sample the bed in a grid (least squares solution).
@@ -478,25 +522,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
478 522
 
479 523
   #else  // !AUTO_BED_LEVELING_GRID
480 524
 
481
-      // Arbitrary points to probe.
482
-      // A simple cross-product is used to estimate the plane of the bed.
483
-      #define ABL_PROBE_PT_1_X 15
484
-      #define ABL_PROBE_PT_1_Y 180
485
-      #define ABL_PROBE_PT_2_X 15
486
-      #define ABL_PROBE_PT_2_Y 20
487
-      #define ABL_PROBE_PT_3_X 170
488
-      #define ABL_PROBE_PT_3_Y 20
525
+    // Arbitrary points to probe.
526
+    // A simple cross-product is used to estimate the plane of the bed.
527
+    #define ABL_PROBE_PT_1_X 15
528
+    #define ABL_PROBE_PT_1_Y 180
529
+    #define ABL_PROBE_PT_2_X 15
530
+    #define ABL_PROBE_PT_2_Y 20
531
+    #define ABL_PROBE_PT_3_X 170
532
+    #define ABL_PROBE_PT_3_Y 20
489 533
 
490 534
   #endif // AUTO_BED_LEVELING_GRID
491 535
 
492
-  // Offsets to the Z probe relative to the nozzle tip.
536
+  // Z Probe to nozzle (X,Y) offset, relative to (0, 0).
493 537
   // X and Y offsets must be integers.
494
-  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // Z probe to nozzle X offset: -left  +right
495
-  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Z probe to nozzle Y offset: -front +behind
496
-  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z probe to nozzle Z offset: -below (always!)
497
-
498
-  #define Z_RAISE_BEFORE_HOMING 4       // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
499
-                                        // Be sure you have this distance over your Z_MAX_POS in case.
538
+  //
539
+  // In the following example the X and Y offsets are both positive:
540
+  // #define X_PROBE_OFFSET_FROM_EXTRUDER 10
541
+  // #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
542
+  //
543
+  //    +-- BACK ---+
544
+  //    |           |
545
+  //  L |    (+) P  | R <-- probe (20,20)
546
+  //  E |           | I
547
+  //  F | (-) N (+) | G <-- nozzle (10,10)
548
+  //  T |           | H
549
+  //    |    (-)    | T
550
+  //    |           |
551
+  //    O-- FRONT --+
552
+  //  (0,0)
553
+  #define X_PROBE_OFFSET_FROM_EXTRUDER 10  // X offset: -left  [of the nozzle] +right
554
+  #define Y_PROBE_OFFSET_FROM_EXTRUDER 10  // Y offset: -front [of the nozzle] +behind
555
+  #define Z_PROBE_OFFSET_FROM_EXTRUDER 0   // Z offset: -below [the nozzle] (always negative!)
500 556
 
501 557
   #define XY_TRAVEL_SPEED 8000         // X and Y axis travel speed between probes, in mm/min.
502 558
 
@@ -504,17 +560,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
504 560
   #define Z_RAISE_BETWEEN_PROBINGS 5  // How much the Z axis will be raised when traveling from between next probing points.
505 561
   #define Z_RAISE_AFTER_PROBING 15    // How much the Z axis will be raised after the last probing point.
506 562
 
507
-//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
508
-                                                                            // Useful to retract a deployable Z probe.
563
+  //#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
564
+                                                                             // Useful to retract a deployable Z probe.
509 565
 
510
-  //#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
511
-  //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
566
+  // Probes are sensors/switches that need to be activated before they can be used
567
+  // and deactivated after the use.
568
+  // Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
569
+
570
+  // A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
571
+  // when the hardware endstops are active.
572
+  //#define FIX_MOUNTED_PROBE
512 573
 
574
+  // A Servo Probe can be defined in the servo section below.
575
+
576
+  // An Allen Key Probe is currently predefined only in the delta example configurations.
577
+
578
+  //#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
579
+  //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
513 580
 
514
-  //If you have enabled the Bed Auto Leveling and are using the same Z Probe for Z Homing,
515
-  //it is highly recommended you let this Z_SAFE_HOMING enabled!!!
581
+  // If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
582
+  // it is highly recommended you leave Z_SAFE_HOMING enabled!
516 583
 
517
-  #define Z_SAFE_HOMING   // This feature is meant to avoid Z homing with Z probe outside the bed area.
584
+  #define Z_SAFE_HOMING   // Use the z-min-probe for homing to z-min - not the z-min-endstop.
585
+                          // This feature is meant to avoid Z homing with Z probe outside the bed area.
518 586
                           // When defined, it will:
519 587
                           // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
520 588
                           // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
@@ -528,37 +596,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
528 596
 
529 597
   #endif
530 598
 
531
-  // Support for a dedicated Z probe endstop separate from the Z min endstop.
532
-  // If you would like to use both a Z probe and a Z min endstop together,
533
-  // uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
534
-  // If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
535
-  // Example: To park the head outside the bed area when homing with G28.
536
-  //
537
-  // WARNING:
538
-  // The Z min endstop will need to set properly as it would without a Z probe
539
-  // to prevent head crashes and premature stopping during a print.
540
-  //
541
-  // To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
542
-  // defined in the pins_XXXXX.h file for your control board.
543
-  // If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
544
-  // Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
545
-  // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
546
-  // in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
547
-  // otherwise connect to ground and D32 for normally closed configuration
548
-  // and 5V and D32 for normally open configurations.
549
-  // Normally closed configuration is advised and assumed.
550
-  // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
551
-  // Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
552
-  // Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
553
-  // D32 is currently selected in the RAMPS 1.3/1.4 pin file.
554
-  // All other boards will need changes to the respective pins_XXXXX.h file.
555
-  //
556
-  // WARNING:
557
-  // Setting the wrong pin may have unexpected and potentially disastrous outcomes.
558
-  // Use with caution and do your homework.
559
-  //
560
-  //#define Z_MIN_PROBE_ENDSTOP
561
-
562 599
 #endif // AUTO_BED_LEVELING_FEATURE
563 600
 
564 601
 
@@ -633,6 +670,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
633 670
 #endif
634 671
 
635 672
 //
673
+// Host Keepalive
674
+//
675
+// By default Marlin will send a busy status message to the host
676
+// every 2 seconds when it can't accept commands.
677
+//
678
+//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
679
+
680
+//
636 681
 // M100 Free Memory Watcher
637 682
 //
638 683
 //#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
@@ -652,13 +697,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
652 697
 // @section lcd
653 698
 
654 699
 // Define your display language below. Replace (en) with your language code and uncomment.
655
-// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
700
+// en, pl, fr, de, es, ru, bg, it, pt, pt_utf8, pt-br, pt-br_utf8, fi, an, nl, ca, eu, kana, kana_utf8, cn, cz, test
656 701
 // See also language.h
657 702
 #define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
658 703
 
659 704
 // Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
660 705
 // To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
661
-// See also documentation/LCDLanguageFont.md
706
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
662 707
   #define DISPLAY_CHARSET_HD44780_JAPAN        // this is the most common hardware
663 708
   //#define DISPLAY_CHARSET_HD44780_WESTERN
664 709
   //#define DISPLAY_CHARSET_HD44780_CYRILLIC
@@ -666,12 +711,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
666 711
 //#define ULTRA_LCD  //general LCD support, also 16x2
667 712
 //#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
668 713
 //#define SDSUPPORT // Enable SD Card Support in Hardware Console
669
-// Changed behaviour! If you need SDSUPPORT uncomment it!
670
-//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
671
-//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
714
+                    // Changed behaviour! If you need SDSUPPORT uncomment it!
715
+//#define SPI_SPEED SPI_HALF_SPEED // (also SPI_QUARTER_SPEED, SPI_EIGHTH_SPEED) Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
672 716
 //#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
673 717
 //#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
674 718
 //#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
719
+//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
675 720
 //#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
676 721
 //#define ULTIPANEL  //the UltiPanel as on Thingiverse
677 722
 //#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
@@ -688,13 +733,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
688 733
 
689 734
 // The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
690 735
 // http://panucatt.com
691
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
736
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
692 737
 //#define VIKI2
693 738
 //#define miniVIKI
694 739
 
695 740
 // This is a new controller currently under development.  https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
696 741
 //
697
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
742
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
698 743
 //#define ELB_FULL_GRAPHIC_CONTROLLER
699 744
 //#define SD_DETECT_INVERTED
700 745
 
@@ -709,7 +754,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
709 754
 // The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
710 755
 // http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
711 756
 //
712
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
757
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
713 758
 //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
714 759
 
715 760
 // The RepRapWorld REPRAPWORLD_KEYPAD v1.1
@@ -732,6 +777,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
732 777
 
733 778
 //#define LCD_I2C_SAINSMART_YWROBOT
734 779
 
780
+//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
781
+
735 782
 // PANELOLU2 LCD with status LEDs, separate encoder and click inputs
736 783
 //
737 784
 // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
@@ -743,9 +790,9 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
743 790
 
744 791
 // Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs
745 792
 //#define LCD_I2C_VIKI
746
-  
793
+
747 794
 // SSD1306 OLED generic display support
748
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
795
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
749 796
 //#define U8GLIB_SSD1306
750 797
 
751 798
 // Shift register panels
@@ -757,7 +804,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
757 804
 
758 805
 // @section extras
759 806
 
760
-// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
807
+// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
761 808
 //#define FAST_PWM_FAN
762 809
 
763 810
 // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
@@ -839,19 +886,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
839 886
 // Uncomment below to enable
840 887
 //#define FILAMENT_SENSOR
841 888
 
842
-#define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
843
-#define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
844
-
845 889
 #define DEFAULT_NOMINAL_FILAMENT_DIA 3.00  //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
846
-#define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
847
-#define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
848
-#define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
849 890
 
850
-//defines used in the code
851
-#define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
891
+#if ENABLED(FILAMENT_SENSOR)
892
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
893
+  #define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
894
+
895
+  #define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
896
+  #define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
897
+  #define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
852 898
 
853
-//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
854
-//#define FILAMENT_LCD_DISPLAY
899
+  #define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
900
+
901
+  //When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
902
+  //#define FILAMENT_LCD_DISPLAY
903
+#endif
855 904
 
856 905
 #include "Configuration_adv.h"
857 906
 #include "thermistortables.h"

+ 102
- 75
Marlin/Configuration_adv.h Näytä tiedosto

@@ -17,6 +17,20 @@
17 17
 /**
18 18
  * Thermal Protection parameters
19 19
  */
20
+  /**
21
+   * Thermal Protection protects your printer from damage and fire if a
22
+   * thermistor falls out or temperature sensors fail in any way.
23
+   *
24
+   * The issue: If a thermistor falls out or a temperature sensor fails,
25
+   * Marlin can no longer sense the actual temperature. Since a disconnected
26
+   * thermistor reads as a low temperature, the firmware will keep the heater on.
27
+   *
28
+   * The solution: Once the temperature reaches the target, start observing.
29
+   * If the temperature stays too far below the target (hysteresis) for too long (period),
30
+   * the firmware will halt the machine as a safety precaution.
31
+   *
32
+   * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
33
+   */
20 34
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
21 35
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
22 36
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
@@ -26,11 +40,19 @@
26 40
    * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
27 41
    * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
28 42
    * but only if the current temperature is far enough below the target for a reliable test.
43
+   *
44
+   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
45
+   * WATCH_TEMP_INCREASE should not be below 2.
29 46
    */
30 47
   #define WATCH_TEMP_PERIOD 16                // Seconds
31 48
   #define WATCH_TEMP_INCREASE 4               // Degrees Celsius
32 49
 #endif
33 50
 
51
+  /**
52
+   * Thermal Protection parameters for the bed
53
+   * are like the above for the hotends.
54
+   * WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
55
+   */
34 56
 #if ENABLED(THERMAL_PROTECTION_BED)
35 57
   #define THERMAL_PROTECTION_BED_PERIOD 20    // Seconds
36 58
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
@@ -52,7 +74,7 @@
52 74
  * The maximum buffered steps/sec of the extruder motor is called "se".
53 75
  * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
54 76
  * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
55
- * mintemp and maxtemp. Turn this off by excuting M109 without F*
77
+ * mintemp and maxtemp. Turn this off by executing M109 without F*
56 78
  * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
57 79
  * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
58 80
  */
@@ -137,7 +159,7 @@
137 159
 #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
138 160
 
139 161
   // 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.
140
-  // That way the machine is capable to align the bed during home, since both Z steppers are homed. 
162
+  // That way the machine is capable to align the bed during home, since both Z steppers are homed.
141 163
   // There is also an implementation of M666 (software endstops adjustment) to this feature.
142 164
   // After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
143 165
   // 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.
@@ -232,7 +254,13 @@
232 254
 #define INVERT_E_STEP_PIN false
233 255
 
234 256
 // Default stepper release if idle. Set to 0 to deactivate.
235
-#define DEFAULT_STEPPER_DEACTIVE_TIME 60
257
+// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
258
+// Time can be set by M18 and M84.
259
+#define DEFAULT_STEPPER_DEACTIVE_TIME 120
260
+#define DISABLE_INACTIVE_X true
261
+#define DISABLE_INACTIVE_Y true
262
+#define DISABLE_INACTIVE_Z true  // set to false if the nozzle will fall down on your printed part when print has finished.
263
+#define DISABLE_INACTIVE_E true
236 264
 
237 265
 #define DEFAULT_MINIMUMFEEDRATE       0.0     // minimum feedrate
238 266
 #define DEFAULT_MINTRAVELFEEDRATE     0.0
@@ -268,6 +296,9 @@
268 296
 // Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
269 297
 #define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
270 298
 
299
+// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
300
+//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
301
+
271 302
 // uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
272 303
 //#define DIGIPOT_I2C
273 304
 // Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
@@ -335,8 +366,8 @@
335 366
   // save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
336 367
   // we don't have a big font for Cyrillic, Kana
337 368
   //#define USE_BIG_EDIT_FONT
338
- 
339
-  // If you have spare 2300Byte of progmem and want to use a 
369
+
370
+  // If you have spare 2300Byte of progmem and want to use a
340 371
   // smaller font on the Info-screen uncomment the next line.
341 372
   //#define USE_SMALL_INFOFONT
342 373
 #endif // DOGLCD
@@ -344,13 +375,13 @@
344 375
 // @section more
345 376
 
346 377
 // The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
347
-//#define USE_WATCHDOG
378
+#define USE_WATCHDOG
348 379
 
349 380
 #if ENABLED(USE_WATCHDOG)
350
-// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
351
-// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
352
-//  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
353
-//#define WATCHDOG_RESET_MANUAL
381
+  // If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
382
+  // The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
383
+  //  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
384
+  //#define WATCHDOG_RESET_MANUAL
354 385
 #endif
355 386
 
356 387
 // @section lcd
@@ -361,7 +392,7 @@
361 392
 //#define BABYSTEPPING
362 393
 #if ENABLED(BABYSTEPPING)
363 394
   #define BABYSTEP_XY  //not only z, but also XY in the menu. more clutter, more functions
364
-                       //not implemented for CoreXY and deltabots!
395
+                       //not implemented for deltabots!
365 396
   #define BABYSTEP_INVERT_Z false  //true for inverse movements in Z
366 397
   #define BABYSTEP_MULTIPLICATOR 1 //faster movements
367 398
 #endif
@@ -380,7 +411,6 @@
380 411
 #if ENABLED(ADVANCE)
381 412
   #define EXTRUDER_ADVANCE_K .0
382 413
   #define D_FILAMENT 2.85
383
-  #define STEPS_MM_E 836
384 414
 #endif
385 415
 
386 416
 // @section extras
@@ -389,7 +419,7 @@
389 419
 #define MM_PER_ARC_SEGMENT 1
390 420
 #define N_ARC_CORRECTION 25
391 421
 
392
-const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
422
+const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
393 423
 
394 424
 // @section temperature
395 425
 
@@ -461,8 +491,8 @@ const unsigned int dropsegments=5; //everything with less than this number of st
461 491
 #endif
462 492
 
463 493
 /******************************************************************************\
464
- * enable this section if you have TMC26X motor drivers. 
465
- * you need to import the TMC26XStepper library into the arduino IDE for this
494
+ * enable this section if you have TMC26X motor drivers.
495
+ * you need to import the TMC26XStepper library into the Arduino IDE for this
466 496
  ******************************************************************************/
467 497
 
468 498
 // @section tmc
@@ -470,61 +500,61 @@ const unsigned int dropsegments=5; //everything with less than this number of st
470 500
 //#define HAVE_TMCDRIVER
471 501
 #if ENABLED(HAVE_TMCDRIVER)
472 502
 
473
-//#define X_IS_TMC
503
+  //#define X_IS_TMC
474 504
   #define X_MAX_CURRENT 1000  //in mA
475 505
   #define X_SENSE_RESISTOR 91 //in mOhms
476 506
   #define X_MICROSTEPS 16     //number of microsteps
477
-  
478
-//#define X2_IS_TMC
507
+
508
+  //#define X2_IS_TMC
479 509
   #define X2_MAX_CURRENT 1000  //in mA
480 510
   #define X2_SENSE_RESISTOR 91 //in mOhms
481 511
   #define X2_MICROSTEPS 16     //number of microsteps
482
-  
483
-//#define Y_IS_TMC
512
+
513
+  //#define Y_IS_TMC
484 514
   #define Y_MAX_CURRENT 1000  //in mA
485 515
   #define Y_SENSE_RESISTOR 91 //in mOhms
486 516
   #define Y_MICROSTEPS 16     //number of microsteps
487
-  
488
-//#define Y2_IS_TMC
517
+
518
+  //#define Y2_IS_TMC
489 519
   #define Y2_MAX_CURRENT 1000  //in mA
490 520
   #define Y2_SENSE_RESISTOR 91 //in mOhms
491
-  #define Y2_MICROSTEPS 16     //number of microsteps 
492
-  
493
-//#define Z_IS_TMC
521
+  #define Y2_MICROSTEPS 16     //number of microsteps
522
+
523
+  //#define Z_IS_TMC
494 524
   #define Z_MAX_CURRENT 1000  //in mA
495 525
   #define Z_SENSE_RESISTOR 91 //in mOhms
496 526
   #define Z_MICROSTEPS 16     //number of microsteps
497
-  
498
-//#define Z2_IS_TMC
527
+
528
+  //#define Z2_IS_TMC
499 529
   #define Z2_MAX_CURRENT 1000  //in mA
500 530
   #define Z2_SENSE_RESISTOR 91 //in mOhms
501 531
   #define Z2_MICROSTEPS 16     //number of microsteps
502
-  
503
-//#define E0_IS_TMC
532
+
533
+  //#define E0_IS_TMC
504 534
   #define E0_MAX_CURRENT 1000  //in mA
505 535
   #define E0_SENSE_RESISTOR 91 //in mOhms
506 536
   #define E0_MICROSTEPS 16     //number of microsteps
507
-  
508
-//#define E1_IS_TMC
537
+
538
+  //#define E1_IS_TMC
509 539
   #define E1_MAX_CURRENT 1000  //in mA
510 540
   #define E1_SENSE_RESISTOR 91 //in mOhms
511
-  #define E1_MICROSTEPS 16     //number of microsteps 
512
-  
513
-//#define E2_IS_TMC
541
+  #define E1_MICROSTEPS 16     //number of microsteps
542
+
543
+  //#define E2_IS_TMC
514 544
   #define E2_MAX_CURRENT 1000  //in mA
515 545
   #define E2_SENSE_RESISTOR 91 //in mOhms
516
-  #define E2_MICROSTEPS 16     //number of microsteps 
517
-  
518
-//#define E3_IS_TMC
546
+  #define E2_MICROSTEPS 16     //number of microsteps
547
+
548
+  //#define E3_IS_TMC
519 549
   #define E3_MAX_CURRENT 1000  //in mA
520 550
   #define E3_SENSE_RESISTOR 91 //in mOhms
521
-  #define E3_MICROSTEPS 16     //number of microsteps   
551
+  #define E3_MICROSTEPS 16     //number of microsteps
522 552
 
523 553
 #endif
524 554
 
525 555
 /******************************************************************************\
526
- * enable this section if you have L6470  motor drivers. 
527
- * you need to import the L6470 library into the arduino IDE for this
556
+ * enable this section if you have L6470  motor drivers.
557
+ * you need to import the L6470 library into the Arduino IDE for this
528 558
  ******************************************************************************/
529 559
 
530 560
 // @section l6470
@@ -532,69 +562,66 @@ const unsigned int dropsegments=5; //everything with less than this number of st
532 562
 //#define HAVE_L6470DRIVER
533 563
 #if ENABLED(HAVE_L6470DRIVER)
534 564
 
535
-//#define X_IS_L6470
565
+  //#define X_IS_L6470
536 566
   #define X_MICROSTEPS 16     //number of microsteps
537
-  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
567
+  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
538 568
   #define X_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
539 569
   #define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
540
-  
541
-//#define X2_IS_L6470
570
+
571
+  //#define X2_IS_L6470
542 572
   #define X2_MICROSTEPS 16     //number of microsteps
543
-  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
573
+  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
544 574
   #define X2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
545 575
   #define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
546
-  
547
-//#define Y_IS_L6470
576
+
577
+  //#define Y_IS_L6470
548 578
   #define Y_MICROSTEPS 16     //number of microsteps
549
-  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
579
+  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
550 580
   #define Y_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
551 581
   #define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
552
-  
553
-//#define Y2_IS_L6470
554
-  #define Y2_MICROSTEPS 16     //number of microsteps 
555
-  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
582
+
583
+  //#define Y2_IS_L6470
584
+  #define Y2_MICROSTEPS 16     //number of microsteps
585
+  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
556 586
   #define Y2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
557
-  #define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall 
558
-  
559
-//#define Z_IS_L6470
587
+  #define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
588
+
589
+  //#define Z_IS_L6470
560 590
   #define Z_MICROSTEPS 16     //number of microsteps
561
-  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
591
+  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
562 592
   #define Z_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
563 593
   #define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
564
-  
565
-//#define Z2_IS_L6470
594
+
595
+  //#define Z2_IS_L6470
566 596
   #define Z2_MICROSTEPS 16     //number of microsteps
567
-  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
597
+  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
568 598
   #define Z2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
569 599
   #define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
570
-  
571
-//#define E0_IS_L6470
600
+
601
+  //#define E0_IS_L6470
572 602
   #define E0_MICROSTEPS 16     //number of microsteps
573
-  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
603
+  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
574 604
   #define E0_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
575 605
   #define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
576
-  
577
-//#define E1_IS_L6470
578
-  #define E1_MICROSTEPS 16     //number of microsteps 
606
+
607
+  //#define E1_IS_L6470
579 608
   #define E1_MICROSTEPS 16     //number of microsteps
580
-  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
609
+  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
581 610
   #define E1_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
582 611
   #define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
583
-  
584
-//#define E2_IS_L6470
585
-  #define E2_MICROSTEPS 16     //number of microsteps 
612
+
613
+  //#define E2_IS_L6470
586 614
   #define E2_MICROSTEPS 16     //number of microsteps
587
-  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
615
+  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
588 616
   #define E2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
589 617
   #define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
590
-  
591
-//#define E3_IS_L6470
592
-  #define E3_MICROSTEPS 16     //number of microsteps   
618
+
619
+  //#define E3_IS_L6470
593 620
   #define E3_MICROSTEPS 16     //number of microsteps
594
-  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
621
+  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
595 622
   #define E3_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
596 623
   #define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
597
-  
624
+
598 625
 #endif
599 626
 
600 627
 #include "Conditionals.h"

+ 4
- 4
Marlin/Default_Version.h Näytä tiedosto

@@ -6,9 +6,9 @@
6 6
 // #error "You must specify the following parameters related to your distribution"
7 7
 
8 8
 #if true
9
-#define SHORT_BUILD_VERSION "1.1.0-RC3"
10
-#define DETAILED_BUILD_VERSION "1.1.0-RC3 From Archive"
11
-#define STRING_DISTRIBUTION_DATE "2015-12-01 12:00"
9
+#define SHORT_BUILD_VERSION "1.1.0-RC4"
10
+#define DETAILED_BUILD_VERSION "1.1.0-RC4 From Archive"
11
+#define STRING_DISTRIBUTION_DATE "2016-03-07 12:00"
12 12
 // It might also be appropriate to define a location where additional information can be found
13
-#define SOURCE_CODE_URL  "http:// ..."
13
+// #define SOURCE_CODE_URL  "http:// ..."
14 14
 #endif

+ 9
- 6
Marlin/Makefile Näytä tiedosto

@@ -12,14 +12,14 @@
12 12
 #
13 13
 # Detailed instructions for using the makefile:
14 14
 #
15
-#  1. Modify the line containg "ARDUINO_INSTALL_DIR" to point to the directory that
15
+#  1. Modify the line containing "ARDUINO_INSTALL_DIR" to point to the directory that
16 16
 #     contains the Arduino installation (for example, under Mac OS X, this
17 17
 #     might be /Applications/Arduino.app/Contents/Resources/Java).
18 18
 #
19 19
 #  2. Modify the line containing "UPLOAD_PORT" to refer to the filename
20 20
 #     representing the USB or serial connection to your Arduino board
21 21
 #     (e.g. UPLOAD_PORT = /dev/tty.USB0).  If the exact name of this file
22
-#     changes, you can use * as a wildcard (e.g. UPLOAD_PORT = /dev/tty.usb*).
22
+#     changes, you can use * as a wild card (e.g. UPLOAD_PORT = /dev/tty.usb*).
23 23
 #
24 24
 #  3. Set the line containing "MCU" to match your board's processor.
25 25
 #     Older one's are atmega8 based, newer ones like Arduino Mini, Bluetooth
@@ -163,6 +163,9 @@ MCU              ?= at90usb1286
163 163
 else ifeq  ($(HARDWARE_MOTHERBOARD),81)
164 164
 HARDWARE_VARIANT ?= Teensy
165 165
 MCU              ?= at90usb1286
166
+else ifeq  ($(HARDWARE_MOTHERBOARD),811)
167
+HARDWARE_VARIANT ?= Teensy
168
+MCU              ?= at90usb1286
166 169
 else ifeq  ($(HARDWARE_MOTHERBOARD),82)
167 170
 HARDWARE_VARIANT ?= Teensy
168 171
 MCU              ?= at90usb646
@@ -218,7 +221,7 @@ endif
218 221
 # Set to 16Mhz if not yet set.
219 222
 F_CPU ?= 16000000
220 223
 
221
-# Arduino containd the main source code for the Arduino
224
+# Arduino contained the main source code for the Arduino
222 225
 # Libraries, the "hardware variant" are for boards
223 226
 # that derives from that, and their source are present in
224 227
 # the main Marlin source directory
@@ -287,7 +290,7 @@ CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp	\
287 290
 	SdFile.cpp SdVolume.cpp planner.cpp stepper.cpp \
288 291
 	temperature.cpp cardreader.cpp configuration_store.cpp \
289 292
 	watchdog.cpp SPI.cpp servo.cpp Tone.cpp ultralcd.cpp digipot_mcp4451.cpp \
290
-	vector_3.cpp qr_solve.cpp buzzer.cpp
293
+	dac_mcp4728.cpp vector_3.cpp qr_solve.cpp buzzer.cpp
291 294
 ifeq ($(LIQUID_TWI2), 0)
292 295
 CXXSRC += LiquidCrystal.cpp
293 296
 else
@@ -300,7 +303,7 @@ SRC += twi.c
300 303
 CXXSRC += Wire.cpp
301 304
 endif
302 305
 
303
-#Check for Arduino 1.0.0 or higher and use the correct sourcefiles for that version
306
+#Check for Arduino 1.0.0 or higher and use the correct source files for that version
304 307
 ifeq ($(shell [ $(ARDUINO_VERSION) -ge 100 ] && echo true), true)
305 308
 CXXSRC += main.cpp
306 309
 else
@@ -421,7 +424,7 @@ lss: $(BUILD_DIR)/$(TARGET).lss
421 424
 sym: $(BUILD_DIR)/$(TARGET).sym
422 425
 
423 426
 # Program the device.
424
-# Do not try to reset an arduino if it's not one
427
+# Do not try to reset an Arduino if it's not one
425 428
 upload: $(BUILD_DIR)/$(TARGET).hex
426 429
 ifeq (${AVRDUDE_PROGRAMMER}, arduino)
427 430
 	stty hup < $(UPLOAD_PORT); true

+ 36
- 27
Marlin/Marlin.h Näytä tiedosto

@@ -6,7 +6,7 @@
6 6
 
7 7
 #define  FORCE_INLINE __attribute__((always_inline)) inline
8 8
 /**
9
- * Compiler warning on unused varable.
9
+ * Compiler warning on unused variable.
10 10
  */
11 11
 #define UNUSED(x) (void) (x)
12 12
 
@@ -45,13 +45,6 @@ typedef unsigned long millis_t;
45 45
 
46 46
 #include "MarlinSerial.h"
47 47
 
48
-#ifndef cbi
49
-  #define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
50
-#endif
51
-#ifndef sbi
52
-  #define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
53
-#endif
54
-
55 48
 #include "WString.h"
56 49
 
57 50
 #ifdef USBCON
@@ -110,7 +103,11 @@ FORCE_INLINE void serialprintPGM(const char* str) {
110 103
 
111 104
 void get_command();
112 105
 
113
-void idle(); // the standard idle routine calls manage_inactivity(false)
106
+void idle(
107
+  #if ENABLED(FILAMENTCHANGEENABLE)
108
+    bool no_stepper_sleep=false  // pass true to keep steppers from disabling on timeout
109
+  #endif
110
+);
114 111
 
115 112
 void manage_inactivity(bool ignore_stepper_queue = false);
116 113
 
@@ -217,12 +214,12 @@ void Stop();
217 214
  * Debug flags - not yet widely applied
218 215
  */
219 216
 enum DebugFlags {
220
-  DEBUG_ECHO          = BIT(0),
221
-  DEBUG_INFO          = BIT(1),
222
-  DEBUG_ERRORS        = BIT(2),
223
-  DEBUG_DRYRUN        = BIT(3),
224
-  DEBUG_COMMUNICATION = BIT(4),
225
-  DEBUG_LEVELING      = BIT(5)
217
+  DEBUG_ECHO          = _BV(0),
218
+  DEBUG_INFO          = _BV(1),
219
+  DEBUG_ERRORS        = _BV(2),
220
+  DEBUG_DRYRUN        = _BV(3),
221
+  DEBUG_COMMUNICATION = _BV(4),
222
+  DEBUG_LEVELING      = _BV(5)
226 223
 };
227 224
 extern uint8_t marlin_debug_flags;
228 225
 
@@ -230,8 +227,9 @@ extern bool Running;
230 227
 inline bool IsRunning() { return  Running; }
231 228
 inline bool IsStopped() { return !Running; }
232 229
 
233
-bool enqueuecommand(const char* cmd); //put a single ASCII command at the end of the current buffer or return false when it is full
234
-void enqueuecommands_P(const char* cmd); //put one or many ASCII commands at the end of the current buffer, read from flash
230
+bool enqueue_and_echo_command(const char* cmd, bool say_ok=false); //put a single ASCII command at the end of the current buffer or return false when it is full
231
+void enqueue_and_echo_command_now(const char* cmd); // enqueue now, only return when the command has been enqueued
232
+void enqueue_and_echo_commands_P(const char* cmd); //put one or many ASCII commands at the end of the current buffer, read from flash
235 233
 
236 234
 void prepare_arc_move(char isclockwise);
237 235
 void clamp_to_software_endstops(float target[3]);
@@ -259,11 +257,9 @@ extern float home_offset[3]; // axis[n].home_offset
259 257
 extern float min_pos[3]; // axis[n].min_pos
260 258
 extern float max_pos[3]; // axis[n].max_pos
261 259
 extern bool axis_known_position[3]; // axis[n].is_known
260
+extern bool axis_homed[3]; // axis[n].is_homed
262 261
 
263 262
 #if ENABLED(DELTA)
264
-  extern float delta[3];
265
-  extern float endstop_adj[3]; // axis[n].endstop_adj
266
-  extern float delta_radius;
267 263
   #ifndef DELTA_RADIUS_TRIM_TOWER_1
268 264
     #define DELTA_RADIUS_TRIM_TOWER_1 0.0
269 265
   #endif
@@ -273,7 +269,6 @@ extern bool axis_known_position[3]; // axis[n].is_known
273 269
   #ifndef DELTA_RADIUS_TRIM_TOWER_3
274 270
     #define DELTA_RADIUS_TRIM_TOWER_3 0.0
275 271
   #endif
276
-  extern float delta_diagonal_rod;
277 272
   #ifndef DELTA_DIAGONAL_ROD_TRIM_TOWER_1
278 273
     #define DELTA_DIAGONAL_ROD_TRIM_TOWER_1 0.0
279 274
   #endif
@@ -283,7 +278,14 @@ extern bool axis_known_position[3]; // axis[n].is_known
283 278
   #ifndef DELTA_DIAGONAL_ROD_TRIM_TOWER_3
284 279
     #define DELTA_DIAGONAL_ROD_TRIM_TOWER_3 0.0
285 280
   #endif
281
+  extern float delta[3];
282
+  extern float endstop_adj[3]; // axis[n].endstop_adj
283
+  extern float delta_radius;
284
+  extern float delta_diagonal_rod;
286 285
   extern float delta_segments_per_second;
286
+  extern float delta_diagonal_rod_trim_tower_1;
287
+  extern float delta_diagonal_rod_trim_tower_2;
288
+  extern float delta_diagonal_rod_trim_tower_3;
287 289
   void calculate_delta(float cartesian[3]);
288 290
   void recalc_delta_settings(float radius, float diagonal_rod);
289 291
   #if ENABLED(AUTO_BED_LEVELING_FEATURE)
@@ -308,19 +310,17 @@ extern bool axis_known_position[3]; // axis[n].is_known
308 310
   extern float extrude_min_temp;
309 311
 #endif
310 312
 
311
-extern int fanSpeed;
313
+#if FAN_COUNT > 0
314
+  extern int fanSpeeds[FAN_COUNT];
315
+#endif
312 316
 
313 317
 #if ENABLED(BARICUDA)
314 318
   extern int ValvePressure;
315 319
   extern int EtoPPressure;
316 320
 #endif
317 321
 
318
-#if ENABLED(FAN_SOFT_PWM)
319
-  extern unsigned char fanSpeedSoftPwm;
320
-#endif
321
-
322 322
 #if ENABLED(FILAMENT_SENSOR)
323
-  extern float filament_width_nominal;  //holds the theoretical filament diameter ie., 3.00 or 1.75
323
+  extern float filament_width_nominal;  //holds the theoretical filament diameter i.e., 3.00 or 1.75
324 324
   extern bool filament_sensor;  //indicates that filament sensor readings should control extrusion
325 325
   extern float filament_width_meas; //holds the filament diameter as accurately measured
326 326
   extern signed char measurement_delay[];  //ring buffer to delay measurement
@@ -351,6 +351,15 @@ extern uint8_t active_extruder;
351 351
   extern void digipot_i2c_init();
352 352
 #endif
353 353
 
354
+#if HAS_TEMP_0 || HAS_TEMP_BED || ENABLED(HEATER_0_USES_MAX6675)
355
+  void print_heaterstates();
356
+#endif
357
+
354 358
 extern void calculate_volumetric_multipliers();
355 359
 
360
+// Print job timer related functions
361
+millis_t print_job_timer();
362
+bool print_job_start(millis_t t = 0);
363
+bool print_job_stop(bool force = false);
364
+
356 365
 #endif //MARLIN_H

+ 4
- 0
Marlin/Marlin.ino Näytä tiedosto

@@ -40,6 +40,10 @@
40 40
   #elif ENABLED(LCD_I2C_TYPE_MCP23017) || ENABLED(LCD_I2C_TYPE_MCP23008)
41 41
     #include <Wire.h>
42 42
     #include <LiquidTWI2.h>
43
+  #elif ENABLED(LCM1602)
44
+    #include <Wire.h>
45
+    #include <LCD.h>
46
+    #include <LiquidCrystal_I2C.h>
43 47
   #elif ENABLED(DOGLCD)
44 48
     #include <U8glib.h> // library for graphics LCD by Oli Kraus (https://code.google.com/p/u8glib/)
45 49
   #else

+ 40
- 31
Marlin/MarlinSerial.cpp Näytä tiedosto

@@ -33,16 +33,19 @@
33 33
 #endif
34 34
 
35 35
 FORCE_INLINE void store_char(unsigned char c) {
36
-  int i = (unsigned int)(rx_buffer.head + 1) % RX_BUFFER_SIZE;
37
-
38
-  // if we should be storing the received character into the location
39
-  // just before the tail (meaning that the head would advance to the
40
-  // current location of the tail), we're about to overflow the buffer
41
-  // and so we don't write the character or advance the head.
42
-  if (i != rx_buffer.tail) {
43
-    rx_buffer.buffer[rx_buffer.head] = c;
44
-    rx_buffer.head = i;
45
-  }
36
+  CRITICAL_SECTION_START;
37
+    uint8_t h = rx_buffer.head;
38
+    uint8_t i = (uint8_t)(h + 1)  & (RX_BUFFER_SIZE - 1);
39
+
40
+    // if we should be storing the received character into the location
41
+    // just before the tail (meaning that the head would advance to the
42
+    // current location of the tail), we're about to overflow the buffer
43
+    // and so we don't write the character or advance the head.
44
+    if (i != rx_buffer.tail) {
45
+      rx_buffer.buffer[h] = c;
46
+      rx_buffer.head = i;
47
+    }
48
+  CRITICAL_SECTION_END;
46 49
 }
47 50
 
48 51
 
@@ -76,7 +79,7 @@ void MarlinSerial::begin(long baud) {
76 79
   #endif
77 80
 
78 81
   if (useU2X) {
79
-    M_UCSRxA = BIT(M_U2Xx);
82
+    M_UCSRxA = _BV(M_U2Xx);
80 83
     baud_setting = (F_CPU / 4 / baud - 1) / 2;
81 84
   }
82 85
   else {
@@ -88,37 +91,45 @@ void MarlinSerial::begin(long baud) {
88 91
   M_UBRRxH = baud_setting >> 8;
89 92
   M_UBRRxL = baud_setting;
90 93
 
91
-  sbi(M_UCSRxB, M_RXENx);
92
-  sbi(M_UCSRxB, M_TXENx);
93
-  sbi(M_UCSRxB, M_RXCIEx);
94
+  SBI(M_UCSRxB, M_RXENx);
95
+  SBI(M_UCSRxB, M_TXENx);
96
+  SBI(M_UCSRxB, M_RXCIEx);
94 97
 }
95 98
 
96 99
 void MarlinSerial::end() {
97
-  cbi(M_UCSRxB, M_RXENx);
98
-  cbi(M_UCSRxB, M_TXENx);
99
-  cbi(M_UCSRxB, M_RXCIEx);
100
+  CBI(M_UCSRxB, M_RXENx);
101
+  CBI(M_UCSRxB, M_TXENx);
102
+  CBI(M_UCSRxB, M_RXCIEx);
100 103
 }
101 104
 
102 105
 
103 106
 int MarlinSerial::peek(void) {
104
-  if (rx_buffer.head == rx_buffer.tail) {
105
-    return -1;
107
+  int v;
108
+  CRITICAL_SECTION_START;
109
+  uint8_t t = rx_buffer.tail;
110
+  if (rx_buffer.head == t) {
111
+    v = -1;
106 112
   }
107 113
   else {
108
-    return rx_buffer.buffer[rx_buffer.tail];
114
+    v = rx_buffer.buffer[t];
109 115
   }
116
+  CRITICAL_SECTION_END;
117
+  return v;
110 118
 }
111 119
 
112 120
 int MarlinSerial::read(void) {
113
-  // if the head isn't ahead of the tail, we don't have any characters
114
-  if (rx_buffer.head == rx_buffer.tail) {
115
-    return -1;
121
+  int v;
122
+  CRITICAL_SECTION_START;
123
+  uint8_t t = rx_buffer.tail;
124
+  if (rx_buffer.head == t) {
125
+    v = -1;
116 126
   }
117 127
   else {
118
-    unsigned char c = rx_buffer.buffer[rx_buffer.tail];
119
-    rx_buffer.tail = (unsigned int)(rx_buffer.tail + 1) % RX_BUFFER_SIZE;
120
-    return c;
128
+    v = rx_buffer.buffer[t];
129
+    rx_buffer.tail = (uint8_t)(t + 1) & (RX_BUFFER_SIZE - 1);
121 130
   }
131
+  CRITICAL_SECTION_END;
132
+  return v;
122 133
 }
123 134
 
124 135
 void MarlinSerial::flush() {
@@ -126,12 +137,10 @@ void MarlinSerial::flush() {
126 137
   // occurs after reading the value of rx_buffer_head but before writing
127 138
   // the value to rx_buffer_tail; the previous value of rx_buffer_head
128 139
   // may be written to rx_buffer_tail, making it appear as if the buffer
129
-  // don't reverse this or there may be problems if the RX interrupt
130
-  // occurs after reading the value of rx_buffer_head but before writing
131
-  // the value to rx_buffer_tail; the previous value of rx_buffer_head
132
-  // may be written to rx_buffer_tail, making it appear as if the buffer
133 140
   // were full, not empty.
134
-  rx_buffer.head = rx_buffer.tail;
141
+  CRITICAL_SECTION_START;
142
+    rx_buffer.head = rx_buffer.tail;
143
+  CRITICAL_SECTION_END;
135 144
 }
136 145
 
137 146
 

+ 34
- 16
Marlin/MarlinSerial.h Näytä tiedosto

@@ -23,6 +23,12 @@
23 23
 #define MarlinSerial_h
24 24
 #include "Marlin.h"
25 25
 
26
+#ifndef CRITICAL_SECTION_START
27
+  #define CRITICAL_SECTION_START  unsigned char _sreg = SREG; cli();
28
+  #define CRITICAL_SECTION_END    SREG = _sreg;
29
+#endif
30
+
31
+
26 32
 #ifndef SERIAL_PORT
27 33
   #define SERIAL_PORT 0
28 34
 #endif
@@ -69,13 +75,18 @@
69 75
 // using a ring buffer (I think), in which rx_buffer_head is the index of the
70 76
 // location to which to write the next incoming character and rx_buffer_tail
71 77
 // is the index of the location from which to read.
72
-#define RX_BUFFER_SIZE 128
73
-
78
+// 256 is the max limit due to uint8_t head and tail. Use only powers of 2. (...,16,32,64,128,256)
79
+#ifndef RX_BUFFER_SIZE
80
+  #define RX_BUFFER_SIZE 128
81
+#endif
82
+#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))
83
+  #error RX_BUFFER_SIZE has to be a power of 2 and >= 2
84
+#endif
74 85
 
75 86
 struct ring_buffer {
76 87
   unsigned char buffer[RX_BUFFER_SIZE];
77
-  int head;
78
-  int tail;
88
+  volatile uint8_t head;
89
+  volatile uint8_t tail;
79 90
 };
80 91
 
81 92
 #if UART_PRESENT(SERIAL_PORT)
@@ -92,8 +103,12 @@ class MarlinSerial { //: public Stream
92 103
     int read(void);
93 104
     void flush(void);
94 105
 
95
-    FORCE_INLINE int available(void) {
96
-      return (unsigned int)(RX_BUFFER_SIZE + rx_buffer.head - rx_buffer.tail) % RX_BUFFER_SIZE;
106
+    FORCE_INLINE uint8_t available(void) {
107
+      CRITICAL_SECTION_START;
108
+        uint8_t h = rx_buffer.head;
109
+        uint8_t t = rx_buffer.tail;
110
+      CRITICAL_SECTION_END;
111
+      return (uint8_t)(RX_BUFFER_SIZE + h - t) & (RX_BUFFER_SIZE - 1);
97 112
     }
98 113
 
99 114
     FORCE_INLINE void write(uint8_t c) {
@@ -105,16 +120,19 @@ class MarlinSerial { //: public Stream
105 120
     FORCE_INLINE void checkRx(void) {
106 121
       if (TEST(M_UCSRxA, M_RXCx)) {
107 122
         unsigned char c  =  M_UDRx;
108
-        int i = (unsigned int)(rx_buffer.head + 1) % RX_BUFFER_SIZE;
109
-
110
-        // if we should be storing the received character into the location
111
-        // just before the tail (meaning that the head would advance to the
112
-        // current location of the tail), we're about to overflow the buffer
113
-        // and so we don't write the character or advance the head.
114
-        if (i != rx_buffer.tail) {
115
-          rx_buffer.buffer[rx_buffer.head] = c;
116
-          rx_buffer.head = i;
117
-        }
123
+        CRITICAL_SECTION_START;
124
+          uint8_t h = rx_buffer.head;
125
+          uint8_t i = (uint8_t)(h + 1) & (RX_BUFFER_SIZE - 1);
126
+
127
+          // if we should be storing the received character into the location
128
+          // just before the tail (meaning that the head would advance to the
129
+          // current location of the tail), we're about to overflow the buffer
130
+          // and so we don't write the character or advance the head.
131
+          if (i != rx_buffer.tail) {
132
+            rx_buffer.buffer[h] = c;
133
+            rx_buffer.head = i;
134
+          }
135
+        CRITICAL_SECTION_END;
118 136
       }
119 137
     }
120 138
 

+ 949
- 571
Marlin/Marlin_main.cpp
File diff suppressed because it is too large
Näytä tiedosto


+ 63
- 16
Marlin/SanityCheck.h Näytä tiedosto

@@ -32,8 +32,8 @@
32 32
  * Babystepping
33 33
  */
34 34
 #if ENABLED(BABYSTEPPING)
35
-  #if ENABLED(COREXY) && ENABLED(BABYSTEP_XY)
36
-    #error BABYSTEPPING only implemented for Z axis on CoreXY.
35
+  #if DISABLED(ULTRA_LCD)
36
+    #error BABYSTEPPING requires an LCD controller.
37 37
   #endif
38 38
   #if ENABLED(SCARA)
39 39
     #error BABYSTEPPING is not implemented for SCARA yet.
@@ -112,6 +112,7 @@
112 112
 /**
113 113
  * Mesh Bed Leveling
114 114
  */
115
+
115 116
 #if ENABLED(MESH_BED_LEVELING)
116 117
   #if ENABLED(DELTA)
117 118
     #error MESH_BED_LEVELING does not yet support DELTA printers.
@@ -122,8 +123,38 @@
122 123
   #if MESH_NUM_X_POINTS > 7 || MESH_NUM_Y_POINTS > 7
123 124
     #error MESH_NUM_X_POINTS and MESH_NUM_Y_POINTS need to be less than 8.
124 125
   #endif
126
+#elif ENABLED(MANUAL_BED_LEVELING)
127
+  #error MESH_BED_LEVELING is required for MANUAL_BED_LEVELING.
128
+#endif
129
+
130
+/**
131
+ * Probes
132
+ */
133
+
134
+  /**
135
+   * A probe needs a pin
136
+   */
137
+#if (!((HAS_Z_MIN && ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)) || HAS_Z_PROBE )) && ( ENABLED(FIX_MOUNTED_PROBE) || defined(Z_ENDSTOP_SERVO_NR) || ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED))
138
+  #error A probe needs a pin! [Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN || HAS_Z_PROBE]
139
+#endif
140
+
141
+#if ((HAS_Z_MIN && ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)) && HAS_Z_PROBE) && ( ENABLED(FIX_MOUNTED_PROBE) || defined(Z_ENDSTOP_SERVO_NR) || ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED))
142
+  #error A probe should not be connected to more then one pin! [Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN || HAS_Z_PROBE]
143
+#endif
144
+
145
+  /**
146
+    * Require one kind of probe
147
+    */
148
+#if ENABLED(AUTO_BED_LEVELING_FEATURE) && !( ENABLED(FIX_MOUNTED_PROBE) || defined(Z_ENDSTOP_SERVO_NR) || ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED))
149
+  #error For AUTO_BED_LEVELING_FEATURE define one kind of probe! {Servo | Z_PROBE_ALLEN_KEY | Z_PROBE_SLED | FIX_MOUNTED_PROBE]
150
+#endif
151
+
152
+#if ENABLED(Z_SAFE_HOMING)&& !( ENABLED(FIX_MOUNTED_PROBE) || defined(Z_ENDSTOP_SERVO_NR) || ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED))
153
+  #error For Z_SAFE_HOMING define one kind of probe! {Servo | Z_PROBE_ALLEN_KEY | Z_PROBE_SLED | FIX_MOUNTED_PROBE]
125 154
 #endif
126 155
 
156
+// To do: Fail with more then one probe defined
157
+
127 158
 /**
128 159
  * Auto Bed Leveling
129 160
  */
@@ -228,10 +259,6 @@
228 259
       #error You cannot use Z_PROBE_SLED with DELTA.
229 260
     #endif
230 261
 
231
-    #if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST)
232
-      #error Z_MIN_PROBE_REPEATABILITY_TEST is not supported with DELTA yet.
233
-    #endif
234
-
235 262
   #endif
236 263
 
237 264
 #endif
@@ -261,22 +288,36 @@
261 288
 /**
262 289
  * Make sure auto fan pins don't conflict with the fan pin
263 290
  */
264
-#if HAS_AUTO_FAN && HAS_FAN
265
-  #if EXTRUDER_0_AUTO_FAN_PIN == FAN_PIN
266
-    #error You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to FAN_PIN.
267
-  #elif EXTRUDER_1_AUTO_FAN_PIN == FAN_PIN
268
-    #error You cannot set EXTRUDER_1_AUTO_FAN_PIN equal to FAN_PIN.
269
-  #elif EXTRUDER_2_AUTO_FAN_PIN == FAN_PIN
270
-    #error You cannot set EXTRUDER_2_AUTO_FAN_PIN equal to FAN_PIN.
271
-  #elif EXTRUDER_3_AUTO_FAN_PIN == FAN_PIN
272
-    #error You cannot set EXTRUDER_3_AUTO_FAN_PIN equal to FAN_PIN.
291
+#if HAS_AUTO_FAN
292
+  #if HAS_FAN0
293
+    #if EXTRUDER_0_AUTO_FAN_PIN == FAN_PIN
294
+      #error You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to FAN_PIN.
295
+    #elif EXTRUDER_1_AUTO_FAN_PIN == FAN_PIN
296
+      #error You cannot set EXTRUDER_1_AUTO_FAN_PIN equal to FAN_PIN.
297
+    #elif EXTRUDER_2_AUTO_FAN_PIN == FAN_PIN
298
+      #error You cannot set EXTRUDER_2_AUTO_FAN_PIN equal to FAN_PIN.
299
+    #elif EXTRUDER_3_AUTO_FAN_PIN == FAN_PIN
300
+      #error You cannot set EXTRUDER_3_AUTO_FAN_PIN equal to FAN_PIN.
301
+    #endif
273 302
   #endif
274 303
 #endif
275 304
 
276
-#if HAS_FAN && CONTROLLERFAN_PIN == FAN_PIN
305
+#if HAS_FAN0 && CONTROLLERFAN_PIN == FAN_PIN
277 306
   #error You cannot set CONTROLLERFAN_PIN equal to FAN_PIN.
278 307
 #endif
279 308
 
309
+#if HAS_CONTROLLERFAN
310
+  #if EXTRUDER_0_AUTO_FAN_PIN == CONTROLLERFAN_PIN
311
+    #error You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN.
312
+  #elif EXTRUDER_1_AUTO_FAN_PIN == CONTROLLERFAN_PIN
313
+    #error You cannot set EXTRUDER_1_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN.
314
+  #elif EXTRUDER_2_AUTO_FAN_PIN == CONTROLLERFAN_PIN
315
+    #error You cannot set EXTRUDER_2_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN.
316
+  #elif EXTRUDER_3_AUTO_FAN_PIN == CONTROLLERFAN_PIN
317
+    #error You cannot set EXTRUDER_3_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN.
318
+  #endif
319
+#endif
320
+
280 321
 /**
281 322
  * Test Heater, Temp Sensor, and Extruder Pins; Sensor Type must also be set.
282 323
  */
@@ -361,6 +402,12 @@
361 402
   #error HAS_AUTOMATIC_VERSIONING deprecated - use USE_AUTOMATIC_VERSIONING instead
362 403
 #elif defined(ENABLE_AUTO_BED_LEVELING)
363 404
   #error ENABLE_AUTO_BED_LEVELING deprecated - use AUTO_BED_LEVELING_FEATURE instead
405
+#elif defined(SDSLOW)
406
+  #error SDSLOW deprecated - set SPI_SPEED to SPI_HALF_SPEED instead
407
+#elif defined(SDEXTRASLOW)
408
+  #error SDEXTRASLOW deprecated - set SPI_SPEED to SPI_QUARTER_SPEED instead
409
+#elif defined(Z_RAISE_BEFORE_HOMING)
410
+  #error Z_RAISE_BEFORE_HOMING is deprecated. Use MIN_Z_HEIGHT_FOR_HOMING instead.
364 411
 #endif
365 412
 
366 413
 #endif //SANITYCHECK_H

+ 6
- 2
Marlin/Sd2Card.cpp Näytä tiedosto

@@ -35,8 +35,8 @@
35 35
    */
36 36
   static void spiInit(uint8_t spiRate) {
37 37
     // See avr processor documentation
38
-    SPCR = BIT(SPE) | BIT(MSTR) | (spiRate >> 1);
39
-    SPSR = spiRate & 1 || spiRate == 6 ? 0 : BIT(SPI2X);
38
+    SPCR = _BV(SPE) | _BV(MSTR) | (spiRate >> 1);
39
+    SPSR = spiRate & 1 || spiRate == 6 ? 0 : _BV(SPI2X);
40 40
   }
41 41
   //------------------------------------------------------------------------------
42 42
   /** SPI receive a byte */
@@ -498,9 +498,13 @@ bool Sd2Card::readData(uint8_t* dst, uint16_t count) {
498 498
   spiRec();
499 499
 #endif
500 500
   chipSelectHigh();
501
+  // Send an additional dummy byte, required by Toshiba Flash Air SD Card
502
+  spiSend(0XFF);
501 503
   return true;
502 504
 fail:
503 505
   chipSelectHigh();
506
+  // Send an additional dummy byte, required by Toshiba Flash Air SD Card
507
+  spiSend(0XFF);
504 508
   return false;
505 509
 }
506 510
 //------------------------------------------------------------------------------

+ 4
- 4
Marlin/Sd2PinMap.h Näytä tiedosto

@@ -405,10 +405,10 @@ static inline __attribute__((always_inline))
405 405
   void setPinMode(uint8_t pin, uint8_t mode) {
406 406
   if (__builtin_constant_p(pin) && pin < digitalPinCount) {
407 407
     if (mode) {
408
-      *digitalPinMap[pin].ddr |= BIT(digitalPinMap[pin].bit);
408
+      SBI(*digitalPinMap[pin].ddr, digitalPinMap[pin].bit);
409 409
     }
410 410
     else {
411
-      *digitalPinMap[pin].ddr &= ~BIT(digitalPinMap[pin].bit);
411
+      CBI(*digitalPinMap[pin].ddr, digitalPinMap[pin].bit);
412 412
     }
413 413
   }
414 414
   else {
@@ -428,10 +428,10 @@ static inline __attribute__((always_inline))
428 428
   void fastDigitalWrite(uint8_t pin, uint8_t value) {
429 429
   if (__builtin_constant_p(pin) && pin < digitalPinCount) {
430 430
     if (value) {
431
-      *digitalPinMap[pin].port |= BIT(digitalPinMap[pin].bit);
431
+      SBI(*digitalPinMap[pin].port, digitalPinMap[pin].bit);
432 432
     }
433 433
     else {
434
-      *digitalPinMap[pin].port &= ~BIT(digitalPinMap[pin].bit);
434
+      CBI(*digitalPinMap[pin].port, digitalPinMap[pin].bit);
435 435
     }
436 436
   }
437 437
   else {

+ 8
- 9
Marlin/SdBaseFile.cpp Näytä tiedosto

@@ -291,7 +291,7 @@ bool SdBaseFile::getFilename(char* name) {
291 291
   return true;
292 292
 }
293 293
 //------------------------------------------------------------------------------
294
-void SdBaseFile::getpos(fpos_t* pos) {
294
+void SdBaseFile::getpos(filepos_t* pos) {
295 295
   pos->position = curPosition_;
296 296
   pos->cluster = curCluster_;
297 297
 }
@@ -923,7 +923,7 @@ fail:
923 923
  * \return The byte if no error and not at eof else -1;
924 924
  */
925 925
 int SdBaseFile::peek() {
926
-  fpos_t pos;
926
+  filepos_t pos;
927 927
   getpos(&pos);
928 928
   int c = read();
929 929
   if (c >= 0) setpos(&pos);
@@ -1049,9 +1049,8 @@ int16_t SdBaseFile::read(void* buf, uint16_t nbyte) {
1049 1049
   if (!isOpen() || !(flags_ & O_READ)) goto fail;
1050 1050
 
1051 1051
   // max bytes left in file
1052
-  if (nbyte >= (fileSize_ - curPosition_)) {
1053
-    nbyte = fileSize_ - curPosition_;
1054
-  }
1052
+  NOMORE(nbyte, fileSize_ - curPosition_);
1053
+
1055 1054
   // amount left to read
1056 1055
   toRead = nbyte;
1057 1056
   while (toRead > 0) {
@@ -1077,7 +1076,7 @@ int16_t SdBaseFile::read(void* buf, uint16_t nbyte) {
1077 1076
     uint16_t n = toRead;
1078 1077
 
1079 1078
     // amount to be read from current block
1080
-    if (n > (512 - offset)) n = 512 - offset;
1079
+    NOMORE(n, 512 - offset);
1081 1080
 
1082 1081
     // no buffering needed if n == 512
1083 1082
     if (n == 512 && block != vol_->cacheBlockNumber()) {
@@ -1135,7 +1134,7 @@ int8_t SdBaseFile::readDir(dir_t* dir, char* longFilename) {
1135 1134
       // Sanity-check the VFAT entry. The first cluster is always set to zero. And the sequence number should be higher than 0
1136 1135
       if (VFAT->firstClusterLow == 0 && (VFAT->sequenceNumber & 0x1F) > 0 && (VFAT->sequenceNumber & 0x1F) <= MAX_VFAT_ENTRIES) {
1137 1136
         // TODO: Store the filename checksum to verify if a none-long filename aware system modified the file table.
1138
-        n = ((VFAT->sequenceNumber & 0x1F) - 1) * FILENAME_LENGTH;
1137
+        n = ((VFAT->sequenceNumber & 0x1F) - 1) * (FILENAME_LENGTH);
1139 1138
         for (uint8_t i = 0; i < FILENAME_LENGTH; i++)
1140 1139
           longFilename[n + i] = (i < 5) ? VFAT->name1[i] : (i < 11) ? VFAT->name2[i - 5] : VFAT->name3[i - 11];
1141 1140
         // If this VFAT entry is the last one, add a NUL terminator at the end of the string
@@ -1479,7 +1478,7 @@ fail:
1479 1478
   return false;
1480 1479
 }
1481 1480
 //------------------------------------------------------------------------------
1482
-void SdBaseFile::setpos(fpos_t* pos) {
1481
+void SdBaseFile::setpos(filepos_t* pos) {
1483 1482
   curPosition_ = pos->position;
1484 1483
   curCluster_ = pos->cluster;
1485 1484
 }
@@ -1758,7 +1757,7 @@ int16_t SdBaseFile::write(const void* buf, uint16_t nbyte) {
1758 1757
     uint16_t n = 512 - blockOffset;
1759 1758
 
1760 1759
     // lesser of space and amount to write
1761
-    if (n > nToWrite) n = nToWrite;
1760
+    NOMORE(n, nToWrite);
1762 1761
 
1763 1762
     // block for data write
1764 1763
     uint32_t block = vol_->clusterStartBlock(curCluster_) + blockOfCluster;

+ 5
- 5
Marlin/SdBaseFile.h Näytä tiedosto

@@ -31,16 +31,16 @@
31 31
 #include "SdVolume.h"
32 32
 //------------------------------------------------------------------------------
33 33
 /**
34
- * \struct fpos_t
34
+ * \struct filepos_t
35 35
  * \brief internal type for istream
36 36
  * do not use in user apps
37 37
  */
38
-struct fpos_t {
38
+struct filepos_t {
39 39
   /** stream position */
40 40
   uint32_t position;
41 41
   /** cluster for position */
42 42
   uint32_t cluster;
43
-  fpos_t() : position(0), cluster(0) {}
43
+  filepos_t() : position(0), cluster(0) {}
44 44
 };
45 45
 
46 46
 // use the gnu style oflag in open()
@@ -196,11 +196,11 @@ class SdBaseFile {
196 196
   /** get position for streams
197 197
    * \param[out] pos struct to receive position
198 198
    */
199
-  void getpos(fpos_t* pos);
199
+  void getpos(filepos_t* pos);
200 200
   /** set position for streams
201 201
    * \param[out] pos struct with value for new position
202 202
    */
203
-  void setpos(fpos_t* pos);
203
+  void setpos(filepos_t* pos);
204 204
   //----------------------------------------------------------------------------
205 205
   bool close();
206 206
   bool contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock);

+ 2
- 2
Marlin/SdVolume.cpp Näytä tiedosto

@@ -296,7 +296,7 @@ int32_t SdVolume::freeClusterCount() {
296 296
 
297 297
   for (uint32_t lba = fatStartBlock_; todo; todo -= n, lba++) {
298 298
     if (!cacheRawBlock(lba, CACHE_FOR_READ)) return -1;
299
-    if (todo < n) n = todo;
299
+    NOMORE(n, todo);
300 300
     if (fatType_ == 16) {
301 301
       for (uint16_t i = 0; i < n; i++) {
302 302
         if (cacheBuffer_.fat16[i] == 0) free++;
@@ -364,7 +364,7 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) {
364 364
   blocksPerCluster_ = fbs->sectorsPerCluster;
365 365
   // determine shift that is same as multiply by blocksPerCluster_
366 366
   clusterSizeShift_ = 0;
367
-  while (blocksPerCluster_ != BIT(clusterSizeShift_)) {
367
+  while (blocksPerCluster_ != _BV(clusterSizeShift_)) {
368 368
     // error if not power of 2
369 369
     if (clusterSizeShift_++ > 7) goto fail;
370 370
   }

+ 3
- 0
Marlin/boards.h Näytä tiedosto

@@ -40,6 +40,7 @@
40 40
 #define BOARD_TEENSYLU          8    // Teensylu
41 41
 #define BOARD_RUMBA             80   // Rumba
42 42
 #define BOARD_PRINTRBOARD       81   // Printrboard (AT90USB1286)
43
+#define BOARD_PRINTRBOARD_REVF  811  // Printrboard Revision F (AT90USB1286)
43 44
 #define BOARD_BRAINWAVE         82   // Brainwave (AT90USB646)
44 45
 #define BOARD_SAV_MKI           83   // SAV Mk-I (AT90USB1286)
45 46
 #define BOARD_TEENSY2           84   // Teensy++2.0 (AT90USB1286) - CLI compile: DEFINES=AT90USBxx_TEENSYPP_ASSIGNMENTS HARDWARE_MOTHERBOARD=84  make
@@ -54,6 +55,7 @@
54 55
 #define BOARD_OMCA              91   // Final OMCA board
55 56
 #define BOARD_RAMBO             301  // Rambo
56 57
 #define BOARD_MINIRAMBO         302  // Mini-Rambo
58
+#define BOARD_AJ4P              303  // AJ4P
57 59
 #define BOARD_MEGACONTROLLER    310  // Mega controller
58 60
 #define BOARD_ELEFU_3           21   // Elefu Ra Board (v3)
59 61
 #define BOARD_5DPRINT           88   // 5DPrint D8 Driver Board
@@ -61,6 +63,7 @@
61 63
 #define BOARD_MKS_BASE          40   // MKS BASE 1.0
62 64
 #define BOARD_BAM_DICE          401  // 2PrintBeta BAM&DICE with STK drivers
63 65
 #define BOARD_BAM_DICE_DUE      402  // 2PrintBeta BAM&DICE Due with STK drivers
66
+#define BOARD_BQ_ZUM_MEGA_3D    503  // bq ZUM Mega 3D
64 67
 
65 68
 #define BOARD_99                99   // This is in pins.h but...?
66 69
 

+ 13
- 12
Marlin/cardreader.cpp Näytä tiedosto

@@ -88,7 +88,7 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
88 88
       // close() is done automatically by destructor of SdFile
89 89
     }
90 90
     else {
91
-      char pn0 = p.name[0];
91
+      uint8_t pn0 = p.name[0];
92 92
       if (pn0 == DIR_NAME_FREE) break;
93 93
       if (pn0 == DIR_NAME_DELETED || pn0 == '.') continue;
94 94
       if (longFilename[0] == '.') continue;
@@ -195,11 +195,7 @@ void CardReader::initsd() {
195 195
   cardOK = false;
196 196
   if (root.isOpen()) root.close();
197 197
 
198
-  #if ENABLED(SDEXTRASLOW)
199
-    #define SPI_SPEED SPI_QUARTER_SPEED
200
-  #elif ENABLED(SDSLOW)
201
-    #define SPI_SPEED SPI_HALF_SPEED
202
-  #else
198
+  #ifndef SPI_SPEED
203 199
     #define SPI_SPEED SPI_FULL_SPEED
204 200
   #endif
205 201
 
@@ -247,6 +243,14 @@ void CardReader::release() {
247 243
   cardOK = false;
248 244
 }
249 245
 
246
+void CardReader::openAndPrintFile(const char *name) {
247
+  char cmd[4 + (FILENAME_LENGTH + 1) * MAX_DIR_DEPTH + 2]; // Room for "M23 ", names with slashes, a null, and one extra
248
+  sprintf_P(cmd, PSTR("M23 %s"), name);
249
+  for (char *c = &cmd[4]; *c; c++) *c = tolower(*c);
250
+  enqueue_and_echo_command_now(cmd);
251
+  enqueue_and_echo_commands_P(PSTR("M24"));
252
+}
253
+
250 254
 void CardReader::startFileprint() {
251 255
   if (cardOK)
252 256
     sdprinting = true;
@@ -268,7 +272,7 @@ void CardReader::getAbsFilename(char *t) {
268 272
     workDirParents[i].getFilename(t); //SDBaseFile.getfilename!
269 273
     while (*t && cnt < MAXPATHNAMELENGTH) { t++; cnt++; } //crawl counter forward.
270 274
   }
271
-  if (cnt < MAXPATHNAMELENGTH - FILENAME_LENGTH)
275
+  if (cnt < MAXPATHNAMELENGTH - (FILENAME_LENGTH))
272 276
     file.getFilename(t);
273 277
   else
274 278
     t[0] = 0;
@@ -504,10 +508,7 @@ void CardReader::checkautostart(bool force) {
504 508
   while (root.readDir(p, NULL) > 0) {
505 509
     for (int8_t i = 0; i < (int8_t)strlen((char*)p.name); i++) p.name[i] = tolower(p.name[i]);
506 510
     if (p.name[9] != '~' && strncmp((char*)p.name, autoname, 5) == 0) {
507
-      char cmd[4 + (FILENAME_LENGTH + 1) * MAX_DIR_DEPTH + 2];
508
-      sprintf_P(cmd, PSTR("M23 %s"), autoname);
509
-      enqueuecommand(cmd);
510
-      enqueuecommands_P(PSTR("M24"));
511
+      openAndPrintFile(autoname);
511 512
       found = true;
512 513
     }
513 514
   }
@@ -593,7 +594,7 @@ void CardReader::printingHasFinished() {
593 594
     sdprinting = false;
594 595
     if (SD_FINISHED_STEPPERRELEASE) {
595 596
       //finishAndDisableSteppers();
596
-      enqueuecommands_P(PSTR(SD_FINISHED_RELEASECOMMAND));
597
+      enqueue_and_echo_commands_P(PSTR(SD_FINISHED_RELEASECOMMAND));
597 598
     }
598 599
     autotempShutdown();
599 600
   }

+ 1
- 0
Marlin/cardreader.h Näytä tiedosto

@@ -23,6 +23,7 @@ public:
23 23
   void removeFile(char* name);
24 24
   void closefile(bool store_location=false);
25 25
   void release();
26
+  void openAndPrintFile(const char *name);
26 27
   void startFileprint();
27 28
   void pauseSDPrint();
28 29
   void getStatus();

+ 99
- 75
Marlin/configuration_store.cpp Näytä tiedosto

@@ -14,79 +14,85 @@
14 14
  *
15 15
  */
16 16
 
17
-#define EEPROM_VERSION "V21"
17
+#define EEPROM_VERSION "V22"
18 18
 
19 19
 /**
20
- * V19 EEPROM Layout:
20
+ * V21 EEPROM Layout:
21 21
  *
22
- *  ver
23
- *  M92 XYZE  axis_steps_per_unit (x4)
24
- *  M203 XYZE max_feedrate (x4)
25
- *  M201 XYZE max_acceleration_units_per_sq_second (x4)
26
- *  M204 P    acceleration
27
- *  M204 R    retract_acceleration
28
- *  M204 T    travel_acceleration
29
- *  M205 S    minimumfeedrate
30
- *  M205 T    mintravelfeedrate
31
- *  M205 B    minsegmenttime
32
- *  M205 X    max_xy_jerk
33
- *  M205 Z    max_z_jerk
34
- *  M205 E    max_e_jerk
35
- *  M206 XYZ  home_offset (x3)
22
+ *  100  Version (char x4)
23
+ *
24
+ *  104  M92 XYZE  axis_steps_per_unit (float x4)
25
+ *  120  M203 XYZE max_feedrate (float x4)
26
+ *  136  M201 XYZE max_acceleration_units_per_sq_second (uint32_t x4)
27
+ *  152  M204 P    acceleration (float)
28
+ *  156  M204 R    retract_acceleration (float)
29
+ *  160  M204 T    travel_acceleration (float)
30
+ *  164  M205 S    minimumfeedrate (float)
31
+ *  168  M205 T    mintravelfeedrate (float)
32
+ *  172  M205 B    minsegmenttime (ulong)
33
+ *  176  M205 X    max_xy_jerk (float)
34
+ *  180  M205 Z    max_z_jerk (float)
35
+ *  184  M205 E    max_e_jerk (float)
36
+ *  188  M206 XYZ  home_offset (float x3)
36 37
  *
37 38
  * Mesh bed leveling:
38
- *  M420 S    active
39
- *            mesh_num_x (set in firmware)
40
- *            mesh_num_y (set in firmware)
41
- *  M421 XYZ  z_values[][]
42
- *  M851      zprobe_zoffset
39
+ *  200  M420 S    active (bool)
40
+ *  201            mesh_num_x (uint8 as set in firmware)
41
+ *  202            mesh_num_y (uint8 as set in firmware)
42
+ *  203  M421 XYZ  z_values[][] (float x9, by default)
43
+ *  239  M851      zprobe_zoffset (float)
43 44
  *
44 45
  * DELTA:
45
- *  M666 XYZ  endstop_adj (x3)
46
- *  M665 R    delta_radius
47
- *  M665 L    delta_diagonal_rod
48
- *  M665 S    delta_segments_per_second
46
+ *  243  M666 XYZ  endstop_adj (float x3)
47
+ *  255  M665 R    delta_radius (float)
48
+ *  259  M665 L    delta_diagonal_rod (float)
49
+ *  263  M665 S    delta_segments_per_second (float)
50
+ *  267  M665 A    delta_diagonal_rod_trim_tower_1 (float)
51
+ *  271  M665 B    delta_diagonal_rod_trim_tower_2 (float)
52
+ *  275  M665 C    delta_diagonal_rod_trim_tower_3 (float)
53
+ *
54
+ * Z_DUAL_ENDSTOPS:
55
+ *  279  M666 Z    z_endstop_adj (float)
49 56
  *
50 57
  * ULTIPANEL:
51
- *  M145 S0 H plaPreheatHotendTemp
52
- *  M145 S0 B plaPreheatHPBTemp
53
- *  M145 S0 F plaPreheatFanSpeed
54
- *  M145 S1 H absPreheatHotendTemp
55
- *  M145 S1 B absPreheatHPBTemp
56
- *  M145 S1 F absPreheatFanSpeed
58
+ *  283  M145 S0 H plaPreheatHotendTemp (int)
59
+ *  285  M145 S0 B plaPreheatHPBTemp (int)
60
+ *  287  M145 S0 F plaPreheatFanSpeed (int)
61
+ *  289  M145 S1 H absPreheatHotendTemp (int)
62
+ *  291  M145 S1 B absPreheatHPBTemp (int)
63
+ *  293  M145 S1 F absPreheatFanSpeed (int)
57 64
  *
58 65
  * PIDTEMP:
59
- *  M301 E0 PIDC  Kp[0], Ki[0], Kd[0], Kc[0]
60
- *  M301 E1 PIDC  Kp[1], Ki[1], Kd[1], Kc[1]
61
- *  M301 E2 PIDC  Kp[2], Ki[2], Kd[2], Kc[2]
62
- *  M301 E3 PIDC  Kp[3], Ki[3], Kd[3], Kc[3]
63
- *  M301 L        lpq_len
66
+ *  295  M301 E0 PIDC  Kp[0], Ki[0], Kd[0], Kc[0] (float x4)
67
+ *  311  M301 E1 PIDC  Kp[1], Ki[1], Kd[1], Kc[1] (float x4)
68
+ *  327  M301 E2 PIDC  Kp[2], Ki[2], Kd[2], Kc[2] (float x4)
69
+ *  343  M301 E3 PIDC  Kp[3], Ki[3], Kd[3], Kc[3] (float x4)
70
+ *  359  M301 L        lpq_len (int)
64 71
  *
65 72
  * PIDTEMPBED:
66
- *  M304 PID  bedKp, bedKi, bedKd
73
+ *  361  M304 PID  bedKp, bedKi, bedKd (float x3)
67 74
  *
68 75
  * DOGLCD:
69
- *  M250 C    lcd_contrast
76
+ *  373  M250 C    lcd_contrast (int)
70 77
  *
71 78
  * SCARA:
72
- *  M365 XYZ  axis_scaling (x3)
79
+ *  375  M365 XYZ  axis_scaling (float x3)
73 80
  *
74 81
  * FWRETRACT:
75
- *  M209 S    autoretract_enabled
76
- *  M207 S    retract_length
77
- *  M207 W    retract_length_swap
78
- *  M207 F    retract_feedrate
79
- *  M207 Z    retract_zlift
80
- *  M208 S    retract_recover_length
81
- *  M208 W    retract_recover_length_swap
82
- *  M208 F    retract_recover_feedrate
82
+ *  387  M209 S    autoretract_enabled (bool)
83
+ *  388  M207 S    retract_length (float)
84
+ *  392  M207 W    retract_length_swap (float)
85
+ *  396  M207 F    retract_feedrate (float)
86
+ *  400  M207 Z    retract_zlift (float)
87
+ *  404  M208 S    retract_recover_length (float)
88
+ *  408  M208 W    retract_recover_length_swap (float)
89
+ *  412  M208 F    retract_recover_feedrate (float)
83 90
  *
84
- *  M200 D    volumetric_enabled (D>0 makes this enabled)
91
+ * Volumetric Extrusion:
92
+ *  416  M200 D    volumetric_enabled (bool)
93
+ *  417  M200 T D  filament_size (float x4) (T0..3)
85 94
  *
86
- *  M200 T D  filament_size (x4) (T0..3)
87
- *
88
- * Z_DUAL_ENDSTOPS:
89
- *  M666 Z    z_endstop_adj
95
+ *  433  This Slot is Available!
90 96
  *
91 97
  */
92 98
 #include "Marlin.h"
@@ -133,6 +139,10 @@ void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size) {
133 139
 
134 140
 #if ENABLED(EEPROM_SETTINGS)
135 141
 
142
+/**
143
+ * Store Configuration Settings - M500
144
+ */
145
+
136 146
 void Config_StoreSettings()  {
137 147
   float dummy = 0.0f;
138 148
   char ver[4] = "000";
@@ -156,7 +166,7 @@ void Config_StoreSettings()  {
156 166
   uint8_t mesh_num_y = 3;
157 167
   #if ENABLED(MESH_BED_LEVELING)
158 168
     // Compile time test that sizeof(mbl.z_values) is as expected
159
-    typedef char c_assert[(sizeof(mbl.z_values) == MESH_NUM_X_POINTS * MESH_NUM_Y_POINTS * sizeof(dummy)) ? 1 : -1];
169
+    typedef char c_assert[(sizeof(mbl.z_values) == (MESH_NUM_X_POINTS) * (MESH_NUM_Y_POINTS) * sizeof(dummy)) ? 1 : -1];
160 170
     mesh_num_x = MESH_NUM_X_POINTS;
161 171
     mesh_num_y = MESH_NUM_Y_POINTS;
162 172
     EEPROM_WRITE_VAR(i, mbl.active);
@@ -182,13 +192,16 @@ void Config_StoreSettings()  {
182 192
     EEPROM_WRITE_VAR(i, delta_radius);              // 1 float
183 193
     EEPROM_WRITE_VAR(i, delta_diagonal_rod);        // 1 float
184 194
     EEPROM_WRITE_VAR(i, delta_segments_per_second); // 1 float
195
+    EEPROM_WRITE_VAR(i, delta_diagonal_rod_trim_tower_1);  // 1 float
196
+    EEPROM_WRITE_VAR(i, delta_diagonal_rod_trim_tower_2);  // 1 float
197
+    EEPROM_WRITE_VAR(i, delta_diagonal_rod_trim_tower_3);  // 1 float
185 198
   #elif ENABLED(Z_DUAL_ENDSTOPS)
186
-    EEPROM_WRITE_VAR(i, z_endstop_adj);            // 1 floats
199
+    EEPROM_WRITE_VAR(i, z_endstop_adj);            // 1 float
187 200
     dummy = 0.0f;
188
-    for (int q = 5; q--;) EEPROM_WRITE_VAR(i, dummy);
201
+    for (uint8_t q = 8; q--;) EEPROM_WRITE_VAR(i, dummy);
189 202
   #else
190 203
     dummy = 0.0f;
191
-    for (int q = 6; q--;) EEPROM_WRITE_VAR(i, dummy);
204
+    for (uint8_t q = 9; q--;) EEPROM_WRITE_VAR(i, dummy);
192 205
   #endif
193 206
 
194 207
   #if DISABLED(ULTIPANEL)
@@ -203,7 +216,7 @@ void Config_StoreSettings()  {
203 216
   EEPROM_WRITE_VAR(i, absPreheatHPBTemp);
204 217
   EEPROM_WRITE_VAR(i, absPreheatFanSpeed);
205 218
 
206
-  for (int e = 0; e < 4; e++) {
219
+  for (uint8_t e = 0; e < 4; e++) {
207 220
 
208 221
     #if ENABLED(PIDTEMP)
209 222
       if (e < EXTRUDERS) {
@@ -223,7 +236,7 @@ void Config_StoreSettings()  {
223 236
         dummy = DUMMY_PID_VALUE; // When read, will not change the existing value
224 237
         EEPROM_WRITE_VAR(i, dummy);
225 238
         dummy = 0.0f;
226
-        for (int q = 3; q--;) EEPROM_WRITE_VAR(i, dummy);
239
+        for (uint8_t q = 3; q--;) EEPROM_WRITE_VAR(i, dummy);
227 240
       }
228 241
 
229 242
   } // Extruders Loop
@@ -277,7 +290,7 @@ void Config_StoreSettings()  {
277 290
   EEPROM_WRITE_VAR(i, volumetric_enabled);
278 291
 
279 292
   // Save filament sizes
280
-  for (int q = 0; q < 4; q++) {
293
+  for (uint8_t q = 0; q < 4; q++) {
281 294
     if (q < EXTRUDERS) dummy = filament_size[q];
282 295
     EEPROM_WRITE_VAR(i, dummy);
283 296
   }
@@ -339,10 +352,10 @@ void Config_RetrieveSettings() {
339 352
         EEPROM_READ_VAR(i, mbl.z_values);
340 353
       } else {
341 354
         mbl.reset();
342
-        for (int q = 0; q < mesh_num_x * mesh_num_y; q++) EEPROM_READ_VAR(i, dummy);
355
+        for (uint8_t q = 0; q < mesh_num_x * mesh_num_y; q++) EEPROM_READ_VAR(i, dummy);
343 356
       }
344 357
     #else
345
-      for (int q = 0; q < mesh_num_x * mesh_num_y; q++) EEPROM_READ_VAR(i, dummy);
358
+      for (uint8_t q = 0; q < mesh_num_x * mesh_num_y; q++) EEPROM_READ_VAR(i, dummy);
346 359
     #endif // MESH_BED_LEVELING
347 360
 
348 361
     #if DISABLED(AUTO_BED_LEVELING_FEATURE)
@@ -355,13 +368,16 @@ void Config_RetrieveSettings() {
355 368
       EEPROM_READ_VAR(i, delta_radius);               // 1 float
356 369
       EEPROM_READ_VAR(i, delta_diagonal_rod);         // 1 float
357 370
       EEPROM_READ_VAR(i, delta_segments_per_second);  // 1 float
371
+      EEPROM_READ_VAR(i, delta_diagonal_rod_trim_tower_1);  // 1 float
372
+      EEPROM_READ_VAR(i, delta_diagonal_rod_trim_tower_2);  // 1 float
373
+      EEPROM_READ_VAR(i, delta_diagonal_rod_trim_tower_3);  // 1 float
358 374
     #elif ENABLED(Z_DUAL_ENDSTOPS)
359 375
       EEPROM_READ_VAR(i, z_endstop_adj);
360 376
       dummy = 0.0f;
361
-      for (int q=5; q--;) EEPROM_READ_VAR(i, dummy);
377
+      for (uint8_t q=8; q--;) EEPROM_READ_VAR(i, dummy);
362 378
     #else
363 379
       dummy = 0.0f;
364
-      for (int q=6; q--;) EEPROM_READ_VAR(i, dummy);
380
+      for (uint8_t q=9; q--;) EEPROM_READ_VAR(i, dummy);
365 381
     #endif
366 382
 
367 383
     #if DISABLED(ULTIPANEL)
@@ -377,7 +393,7 @@ void Config_RetrieveSettings() {
377 393
     EEPROM_READ_VAR(i, absPreheatFanSpeed);
378 394
 
379 395
     #if ENABLED(PIDTEMP)
380
-      for (int e = 0; e < 4; e++) { // 4 = max extruders currently supported by Marlin
396
+      for (uint8_t e = 0; e < 4; e++) { // 4 = max extruders currently supported by Marlin
381 397
         EEPROM_READ_VAR(i, dummy); // Kp
382 398
         if (e < EXTRUDERS && dummy != DUMMY_PID_VALUE) {
383 399
           // do not need to scale PID values as the values in EEPROM are already scaled
@@ -391,12 +407,12 @@ void Config_RetrieveSettings() {
391 407
           #endif
392 408
         }
393 409
         else {
394
-          for (int q=3; q--;) EEPROM_READ_VAR(i, dummy); // Ki, Kd, Kc
410
+          for (uint8_t q=3; q--;) EEPROM_READ_VAR(i, dummy); // Ki, Kd, Kc
395 411
         }
396 412
       }
397 413
     #else // !PIDTEMP
398 414
       // 4 x 4 = 16 slots for PID parameters
399
-      for (int q=16; q--;) EEPROM_READ_VAR(i, dummy);  // 4x Kp, Ki, Kd, Kc
415
+      for (uint8_t q=16; q--;) EEPROM_READ_VAR(i, dummy);  // 4x Kp, Ki, Kd, Kc
400 416
     #endif // !PIDTEMP
401 417
 
402 418
     #if DISABLED(PID_ADD_EXTRUSION_RATE)
@@ -415,7 +431,7 @@ void Config_RetrieveSettings() {
415 431
       EEPROM_READ_VAR(i, bedKd);
416 432
     }
417 433
     else {
418
-      for (int q=2; q--;) EEPROM_READ_VAR(i, dummy); // bedKi, bedKd
434
+      for (uint8_t q=2; q--;) EEPROM_READ_VAR(i, dummy); // bedKi, bedKd
419 435
     }
420 436
 
421 437
     #if DISABLED(HAS_LCD_CONTRAST)
@@ -450,7 +466,7 @@ void Config_RetrieveSettings() {
450 466
 
451 467
     EEPROM_READ_VAR(i, volumetric_enabled);
452 468
 
453
-    for (int q = 0; q < 4; q++) {
469
+    for (uint8_t q = 0; q < 4; q++) {
454 470
       EEPROM_READ_VAR(i, dummy);
455 471
       if (q < EXTRUDERS) filament_size[q] = dummy;
456 472
     }
@@ -518,6 +534,9 @@ void Config_ResetDefault() {
518 534
     delta_radius =  DELTA_RADIUS;
519 535
     delta_diagonal_rod =  DELTA_DIAGONAL_ROD;
520 536
     delta_segments_per_second =  DELTA_SEGMENTS_PER_SECOND;
537
+    delta_diagonal_rod_trim_tower_1 = DELTA_DIAGONAL_ROD_TRIM_TOWER_1;
538
+    delta_diagonal_rod_trim_tower_2 = DELTA_DIAGONAL_ROD_TRIM_TOWER_2;
539
+    delta_diagonal_rod_trim_tower_3 = DELTA_DIAGONAL_ROD_TRIM_TOWER_3;
521 540
     recalc_delta_settings(delta_radius, delta_diagonal_rod);
522 541
   #elif ENABLED(Z_DUAL_ENDSTOPS)
523 542
     z_endstop_adj = 0;
@@ -538,7 +557,7 @@ void Config_ResetDefault() {
538 557
 
539 558
   #if ENABLED(PIDTEMP)
540 559
     #if ENABLED(PID_PARAMS_PER_EXTRUDER)
541
-      for (int e = 0; e < EXTRUDERS; e++)
560
+      for (uint8_t e = 0; e < EXTRUDERS; e++)
542 561
     #else
543 562
       int e = 0; UNUSED(e); // only need to write once
544 563
     #endif
@@ -686,8 +705,8 @@ void Config_PrintSettings(bool forReplay) {
686 705
     SERIAL_ECHOPAIR(" X", (unsigned long)MESH_NUM_X_POINTS);
687 706
     SERIAL_ECHOPAIR(" Y", (unsigned long)MESH_NUM_Y_POINTS);
688 707
     SERIAL_EOL;
689
-    for (int y = 0; y < MESH_NUM_Y_POINTS; y++) {
690
-      for (int x = 0; x < MESH_NUM_X_POINTS; x++) {
708
+    for (uint8_t y = 0; y < MESH_NUM_Y_POINTS; y++) {
709
+      for (uint8_t x = 0; x < MESH_NUM_X_POINTS; x++) {
691 710
         CONFIG_ECHO_START;
692 711
         SERIAL_ECHOPAIR("  M421 X", mbl.get_x(x));
693 712
         SERIAL_ECHOPAIR(" Y", mbl.get_y(y));
@@ -708,11 +727,16 @@ void Config_PrintSettings(bool forReplay) {
708 727
     SERIAL_ECHOPAIR(" Z", endstop_adj[Z_AXIS]);
709 728
     SERIAL_EOL;
710 729
     CONFIG_ECHO_START;
711
-    SERIAL_ECHOLNPGM("Delta settings: L=delta_diagonal_rod, R=delta_radius, S=delta_segments_per_second");
712
-    CONFIG_ECHO_START;
730
+    if (!forReplay) {
731
+      SERIAL_ECHOLNPGM("Delta settings: L=diagonal_rod, R=radius, S=segments_per_second, ABC=diagonal_rod_trim_tower_[123]");
732
+      CONFIG_ECHO_START;
733
+    }
713 734
     SERIAL_ECHOPAIR("  M665 L", delta_diagonal_rod);
714 735
     SERIAL_ECHOPAIR(" R", delta_radius);
715 736
     SERIAL_ECHOPAIR(" S", delta_segments_per_second);
737
+    SERIAL_ECHOPAIR(" A", delta_diagonal_rod_trim_tower_1);
738
+    SERIAL_ECHOPAIR(" B", delta_diagonal_rod_trim_tower_2);
739
+    SERIAL_ECHOPAIR(" C", delta_diagonal_rod_trim_tower_3);
716 740
     SERIAL_EOL;
717 741
   #elif ENABLED(Z_DUAL_ENDSTOPS)
718 742
     CONFIG_ECHO_START;
@@ -730,12 +754,12 @@ void Config_PrintSettings(bool forReplay) {
730 754
       SERIAL_ECHOLNPGM("Material heatup parameters:");
731 755
       CONFIG_ECHO_START;
732 756
     }
733
-    SERIAL_ECHOPAIR("  M145 M0 H", (unsigned long)plaPreheatHotendTemp);
757
+    SERIAL_ECHOPAIR("  M145 S0 H", (unsigned long)plaPreheatHotendTemp);
734 758
     SERIAL_ECHOPAIR(" B", (unsigned long)plaPreheatHPBTemp);
735 759
     SERIAL_ECHOPAIR(" F", (unsigned long)plaPreheatFanSpeed);
736 760
     SERIAL_EOL;
737 761
     CONFIG_ECHO_START;
738
-    SERIAL_ECHOPAIR("  M145 M1 H", (unsigned long)absPreheatHotendTemp);
762
+    SERIAL_ECHOPAIR("  M145 S1 H", (unsigned long)absPreheatHotendTemp);
739 763
     SERIAL_ECHOPAIR(" B", (unsigned long)absPreheatHPBTemp);
740 764
     SERIAL_ECHOPAIR(" F", (unsigned long)absPreheatFanSpeed);
741 765
     SERIAL_EOL;

+ 0
- 1
Marlin/configurator/config/_htaccess Näytä tiedosto

@@ -1 +0,0 @@
1
-Header set Access-Control-Allow-Origin "*"

+ 0
- 64
Marlin/configurator/config/boards.h Näytä tiedosto

@@ -1,64 +0,0 @@
1
-#ifndef BOARDS_H
2
-#define BOARDS_H
3
-
4
-#define BOARD_UNKNOWN -1
5
-
6
-#define BOARD_GEN7_CUSTOM       10   // Gen7 custom (Alfons3 Version) "https://github.com/Alfons3/Generation_7_Electronics"
7
-#define BOARD_GEN7_12           11   // Gen7 v1.1, v1.2
8
-#define BOARD_GEN7_13           12   // Gen7 v1.3
9
-#define BOARD_GEN7_14           13   // Gen7 v1.4
10
-#define BOARD_CHEAPTRONIC       2    // Cheaptronic v1.0
11
-#define BOARD_SETHI             20   // Sethi 3D_1
12
-#define BOARD_RAMPS_OLD         3    // MEGA/RAMPS up to 1.2
13
-#define BOARD_RAMPS_13_EFB      33   // RAMPS 1.3 / 1.4 (Power outputs: Extruder, Fan, Bed)
14
-#define BOARD_RAMPS_13_EEB      34   // RAMPS 1.3 / 1.4 (Power outputs: Extruder0, Extruder1, Bed)
15
-#define BOARD_RAMPS_13_EFF      35   // RAMPS 1.3 / 1.4 (Power outputs: Extruder, Fan, Fan)
16
-#define BOARD_RAMPS_13_EEF      36   // RAMPS 1.3 / 1.4 (Power outputs: Extruder0, Extruder1, Fan)
17
-#define BOARD_RAMPS_13_SF       38   // RAMPS 1.3 / 1.4 (Power outputs: Spindle, Controller Fan)
18
-#define BOARD_FELIX2            37   // Felix 2.0+ Electronics Board (RAMPS like)
19
-#define BOARD_RIGIDBOARD        42   // Invent-A-Part RigidBoard
20
-#define BOARD_GEN6              5    // Gen6
21
-#define BOARD_GEN6_DELUXE       51   // Gen6 deluxe
22
-#define BOARD_SANGUINOLOLU_11   6    // Sanguinololu < 1.2
23
-#define BOARD_SANGUINOLOLU_12   62   // Sanguinololu 1.2 and above
24
-#define BOARD_MELZI             63   // Melzi
25
-#define BOARD_STB_11            64   // STB V1.1
26
-#define BOARD_AZTEEG_X1         65   // Azteeg X1
27
-#define BOARD_MELZI_MAKR3D      66   // Melzi with ATmega1284 (MaKr3d version)
28
-#define BOARD_AZTEEG_X3         67   // Azteeg X3
29
-#define BOARD_AZTEEG_X3_PRO     68   // Azteeg X3 Pro
30
-#define BOARD_ULTIMAKER         7    // Ultimaker
31
-#define BOARD_ULTIMAKER_OLD     71   // Ultimaker (Older electronics. Pre 1.5.4. This is rare)
32
-#define BOARD_ULTIMAIN_2        72   // Ultimainboard 2.x (Uses TEMP_SENSOR 20)
33
-#define BOARD_3DRAG             77   // 3Drag Controller
34
-#define BOARD_K8200             78   // Vellemann K8200 Controller (derived from 3Drag Controller)
35
-#define BOARD_TEENSYLU          8    // Teensylu
36
-#define BOARD_RUMBA             80   // Rumba
37
-#define BOARD_PRINTRBOARD       81   // Printrboard (AT90USB1286)
38
-#define BOARD_BRAINWAVE         82   // Brainwave (AT90USB646)
39
-#define BOARD_SAV_MKI           83   // SAV Mk-I (AT90USB1286)
40
-#define BOARD_TEENSY2           84   // Teensy++2.0 (AT90USB1286) - CLI compile: DEFINES=AT90USBxx_TEENSYPP_ASSIGNMENTS HARDWARE_MOTHERBOARD=84  make
41
-#define BOARD_BRAINWAVE_PRO     85   // Brainwave Pro (AT90USB1286)
42
-#define BOARD_GEN3_PLUS         9    // Gen3+
43
-#define BOARD_GEN3_MONOLITHIC   22   // Gen3 Monolithic Electronics
44
-#define BOARD_MEGATRONICS       70   // Megatronics
45
-#define BOARD_MEGATRONICS_2     701  // Megatronics v2.0
46
-#define BOARD_MINITRONICS       702  // Minitronics v1.0/1.1
47
-#define BOARD_MEGATRONICS_3     703  // Megatronics v3.0
48
-#define BOARD_OMCA_A            90   // Alpha OMCA board
49
-#define BOARD_OMCA              91   // Final OMCA board
50
-#define BOARD_RAMBO             301  // Rambo
51
-#define BOARD_MINIRAMBO         302  // Mini-Rambo
52
-#define BOARD_MEGACONTROLLER    310  // Mega controller
53
-#define BOARD_ELEFU_3           21   // Elefu Ra Board (v3)
54
-#define BOARD_5DPRINT           88   // 5DPrint D8 Driver Board
55
-#define BOARD_LEAPFROG          999  // Leapfrog
56
-#define BOARD_MKS_BASE          40   // MKS BASE 1.0
57
-#define BOARD_BAM_DICE          401  // 2PrintBeta BAM&DICE with STK drivers
58
-#define BOARD_BAM_DICE_DUE      402  // 2PrintBeta BAM&DICE Due with STK drivers
59
-
60
-#define BOARD_99                99   // This is in pins.h but...?
61
-
62
-#define MB(board) (MOTHERBOARD==BOARD_##board)
63
-
64
-#endif //__BOARDS_H

+ 0
- 228
Marlin/configurator/config/language.h Näytä tiedosto

@@ -1,228 +0,0 @@
1
-#ifndef LANGUAGE_H
2
-#define LANGUAGE_H
3
-
4
-#include "Configuration.h"
5
-
6
-#define LANGUAGE_CONCAT(M)       #M
7
-#define GENERATE_LANGUAGE_INCLUDE(M)  LANGUAGE_CONCAT(language_##M.h)
8
-
9
-
10
-// NOTE: IF YOU CHANGE LANGUAGE FILES OR MERGE A FILE WITH CHANGES
11
-//
12
-//   ==> ALWAYS TRY TO COMPILE MARLIN WITH/WITHOUT "ULTIPANEL" / "ULTRALCD" / "SDSUPPORT" #define IN "Configuration.h"
13
-//   ==> ALSO TRY ALL AVAILABLE LANGUAGE OPTIONS
14
-// See also documentation/LCDLanguageFont.md
15
-
16
-// Languages
17
-// en       English
18
-// pl       Polish
19
-// fr       French
20
-// de       German
21
-// es       Spanish
22
-// ru       Russian
23
-// bg       Bulgarian
24
-// it       Italian
25
-// pt       Portuguese
26
-// pt-br    Portuguese (Brazil)
27
-// fi       Finnish
28
-// an       Aragonese
29
-// nl       Dutch
30
-// ca       Catalan
31
-// eu       Basque-Euskera
32
-// kana     Japanese
33
-// kana_utf Japanese
34
-// cn       Chinese
35
-
36
-// fallback if no language is set, don't change
37
-#ifndef LANGUAGE_INCLUDE
38
-  #define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
39
-#endif
40
-
41
-#if ENABLED(USE_AUTOMATIC_VERSIONING)
42
-  #include "_Version.h"
43
-#else
44
-  #include "Default_Version.h"
45
-#endif
46
-
47
-#define PROTOCOL_VERSION "1.0"
48
-
49
-#if MB(ULTIMAKER)|| MB(ULTIMAKER_OLD)|| MB(ULTIMAIN_2)
50
-  #define MACHINE_NAME "Ultimaker"
51
-  #define SOURCE_CODE_URL "https://github.com/Ultimaker/Marlin"
52
-#elif MB(RUMBA)
53
-  #define MACHINE_NAME "Rumba"
54
-#elif MB(3DRAG)
55
-  #define MACHINE_NAME "3Drag"
56
-  #define SOURCE_CODE_URL "http://3dprint.elettronicain.it/"
57
-#elif MB(K8200)
58
-  #define MACHINE_NAME "K8200"
59
-  #define SOURCE_CODE_URL "https://github.com/CONSULitAS/Marlin-K8200"
60
-#elif MB(5DPRINT)
61
-  #define MACHINE_NAME "Makibox"
62
-#elif MB(SAV_MKI)
63
-  #define MACHINE_NAME "SAV MkI"
64
-  #define SOURCE_CODE_URL "https://github.com/fmalpartida/Marlin/tree/SAV-MkI-config"
65
-#elif !defined(MACHINE_NAME)
66
-  #define MACHINE_NAME "3D Printer"
67
-#endif
68
-
69
-#ifdef CUSTOM_MACHINE_NAME
70
-  #undef MACHINE_NAME
71
-  #define MACHINE_NAME CUSTOM_MACHINE_NAME
72
-#endif
73
-
74
-#ifndef SOURCE_CODE_URL
75
-  #define SOURCE_CODE_URL "https://github.com/MarlinFirmware/Marlin"
76
-#endif
77
-
78
-#ifndef DETAILED_BUILD_VERSION
79
-  #error BUILD_VERSION Information must be specified
80
-#endif
81
-
82
-#ifndef MACHINE_UUID
83
-   #define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
84
-#endif
85
-
86
-
87
-#define STRINGIFY_(n) #n
88
-#define STRINGIFY(n) STRINGIFY_(n)
89
-
90
-
91
-// Common LCD messages
92
-
93
-  /* nothing here yet */
94
-
95
-// Common serial messages
96
-#define MSG_MARLIN "Marlin"
97
-
98
-// Serial Console Messages (do not translate those!)
99
-
100
-#define MSG_Enqueueing                      "enqueueing \""
101
-#define MSG_POWERUP                         "PowerUp"
102
-#define MSG_EXTERNAL_RESET                  " External Reset"
103
-#define MSG_BROWNOUT_RESET                  " Brown out Reset"
104
-#define MSG_WATCHDOG_RESET                  " Watchdog Reset"
105
-#define MSG_SOFTWARE_RESET                  " Software Reset"
106
-#define MSG_AUTHOR                          " | Author: "
107
-#define MSG_CONFIGURATION_VER               " Last Updated: "
108
-#define MSG_FREE_MEMORY                     " Free Memory: "
109
-#define MSG_PLANNER_BUFFER_BYTES            "  PlannerBufferBytes: "
110
-#define MSG_OK                              "ok"
111
-#define MSG_WAIT                            "wait"
112
-#define MSG_FILE_SAVED                      "Done saving file."
113
-#define MSG_ERR_LINE_NO                     "Line Number is not Last Line Number+1, Last Line: "
114
-#define MSG_ERR_CHECKSUM_MISMATCH           "checksum mismatch, Last Line: "
115
-#define MSG_ERR_NO_CHECKSUM                 "No Checksum with line number, Last Line: "
116
-#define MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM "No Line Number with checksum, Last Line: "
117
-#define MSG_FILE_PRINTED                    "Done printing file"
118
-#define MSG_BEGIN_FILE_LIST                 "Begin file list"
119
-#define MSG_END_FILE_LIST                   "End file list"
120
-#define MSG_INVALID_EXTRUDER                "Invalid extruder"
121
-#define MSG_INVALID_SOLENOID                "Invalid solenoid"
122
-#define MSG_ERR_NO_THERMISTORS              "No thermistors - no temperature"
123
-#define MSG_M115_REPORT                     "FIRMWARE_NAME:Marlin " DETAILED_BUILD_VERSION " SOURCE_CODE_URL:" SOURCE_CODE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
124
-#define MSG_COUNT_X                         " Count X: "
125
-#define MSG_ERR_KILLED                      "Printer halted. kill() called!"
126
-#define MSG_ERR_STOPPED                     "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
127
-#define MSG_RESEND                          "Resend: "
128
-#define MSG_UNKNOWN_COMMAND                 "Unknown command: \""
129
-#define MSG_ACTIVE_EXTRUDER                 "Active Extruder: "
130
-#define MSG_X_MIN                           "x_min: "
131
-#define MSG_X_MAX                           "x_max: "
132
-#define MSG_Y_MIN                           "y_min: "
133
-#define MSG_Y_MAX                           "y_max: "
134
-#define MSG_Z_MIN                           "z_min: "
135
-#define MSG_Z_MAX                           "z_max: "
136
-#define MSG_Z2_MAX                          "z2_max: "
137
-#define MSG_Z_PROBE                         "z_probe: "
138
-#define MSG_ERR_MATERIAL_INDEX              "M145 S<index> out of range (0-1)"
139
-#define MSG_ERR_M421_REQUIRES_XYZ           "M421 requires XYZ parameters"
140
-#define MSG_ERR_MESH_INDEX_OOB              "Mesh XY index is out of bounds"
141
-#define MSG_ERR_M428_TOO_FAR                "Too far from reference point"
142
-#define MSG_M119_REPORT                     "Reporting endstop status"
143
-#define MSG_ENDSTOP_HIT                     "TRIGGERED"
144
-#define MSG_ENDSTOP_OPEN                    "open"
145
-#define MSG_HOTEND_OFFSET                   "Hotend offsets:"
146
-
147
-#define MSG_SD_CANT_OPEN_SUBDIR             "Cannot open subdir"
148
-#define MSG_SD_INIT_FAIL                    "SD init fail"
149
-#define MSG_SD_VOL_INIT_FAIL                "volume.init failed"
150
-#define MSG_SD_OPENROOT_FAIL                "openRoot failed"
151
-#define MSG_SD_CARD_OK                      "SD card ok"
152
-#define MSG_SD_WORKDIR_FAIL                 "workDir open failed"
153
-#define MSG_SD_OPEN_FILE_FAIL               "open failed, File: "
154
-#define MSG_SD_FILE_OPENED                  "File opened: "
155
-#define MSG_SD_SIZE                         " Size: "
156
-#define MSG_SD_FILE_SELECTED                "File selected"
157
-#define MSG_SD_WRITE_TO_FILE                "Writing to file: "
158
-#define MSG_SD_PRINTING_BYTE                "SD printing byte "
159
-#define MSG_SD_NOT_PRINTING                 "Not SD printing"
160
-#define MSG_SD_ERR_WRITE_TO_FILE            "error writing to file"
161
-#define MSG_SD_CANT_ENTER_SUBDIR            "Cannot enter subdir: "
162
-
163
-#define MSG_STEPPER_TOO_HIGH                "Steprate too high: "
164
-#define MSG_ENDSTOPS_HIT                    "endstops hit: "
165
-#define MSG_ERR_COLD_EXTRUDE_STOP           " cold extrusion prevented"
166
-#define MSG_ERR_LONG_EXTRUDE_STOP           " too long extrusion prevented"
167
-#define MSG_TOO_COLD_FOR_M600               "M600 Hotend too cold to change filament"
168
-#define MSG_BABYSTEPPING_X                  "Babystepping X"
169
-#define MSG_BABYSTEPPING_Y                  "Babystepping Y"
170
-#define MSG_BABYSTEPPING_Z                  "Babystepping Z"
171
-#define MSG_SERIAL_ERROR_MENU_STRUCTURE     "Error in menu structure"
172
-
173
-#define MSG_ERR_EEPROM_WRITE                "Error writing to EEPROM!"
174
-
175
-// temperature.cpp strings
176
-#define MSG_PID_AUTOTUNE                    "PID Autotune"
177
-#define MSG_PID_AUTOTUNE_START              MSG_PID_AUTOTUNE " start"
178
-#define MSG_PID_AUTOTUNE_FAILED             MSG_PID_AUTOTUNE " failed!"
179
-#define MSG_PID_BAD_EXTRUDER_NUM            MSG_PID_AUTOTUNE_FAILED " Bad extruder number"
180
-#define MSG_PID_TEMP_TOO_HIGH               MSG_PID_AUTOTUNE_FAILED " Temperature too high"
181
-#define MSG_PID_TIMEOUT                     MSG_PID_AUTOTUNE_FAILED " timeout"
182
-#define MSG_BIAS                            " bias: "
183
-#define MSG_D                               " d: "
184
-#define MSG_T_MIN                           " min: "
185
-#define MSG_T_MAX                           " max: "
186
-#define MSG_KU                              " Ku: "
187
-#define MSG_TU                              " Tu: "
188
-#define MSG_CLASSIC_PID                     " Classic PID "
189
-#define MSG_KP                              " Kp: "
190
-#define MSG_KI                              " Ki: "
191
-#define MSG_KD                              " Kd: "
192
-#define MSG_B                               "B:"
193
-#define MSG_T                               "T:"
194
-#define MSG_AT                              " @:"
195
-#define MSG_PID_AUTOTUNE_FINISHED           MSG_PID_AUTOTUNE " finished! Put the last Kp, Ki and Kd constants from below into Configuration.h"
196
-#define MSG_PID_DEBUG                       " PID_DEBUG "
197
-#define MSG_PID_DEBUG_INPUT                 ": Input "
198
-#define MSG_PID_DEBUG_OUTPUT                " Output "
199
-#define MSG_PID_DEBUG_PTERM                 " pTerm "
200
-#define MSG_PID_DEBUG_ITERM                 " iTerm "
201
-#define MSG_PID_DEBUG_DTERM                 " dTerm "
202
-#define MSG_PID_DEBUG_CTERM                 " cTerm "
203
-#define MSG_INVALID_EXTRUDER_NUM            " - Invalid extruder number !"
204
-
205
-#define MSG_HEATER_BED                      "bed"
206
-#define MSG_STOPPED_HEATER                  ", system stopped! Heater_ID: "
207
-#define MSG_REDUNDANCY                      "Heater switched off. Temperature difference between temp sensors is too high !"
208
-#define MSG_T_HEATING_FAILED                "Heating failed"
209
-#define MSG_T_THERMAL_RUNAWAY               "Thermal Runaway"
210
-#define MSG_T_MAXTEMP                       "MAXTEMP triggered"
211
-#define MSG_T_MINTEMP                       "MINTEMP triggered"
212
-
213
-// Debug
214
-#define MSG_DEBUG_ECHO                      "DEBUG ECHO ENABLED"
215
-#define MSG_DEBUG_INFO                      "DEBUG INFO ENABLED"
216
-#define MSG_DEBUG_ERRORS                    "DEBUG ERRORS ENABLED"
217
-#define MSG_DEBUG_DRYRUN                    "DEBUG DRYRUN ENABLED"
218
-
219
-// LCD Menu Messages
220
-
221
-#if DISABLED(DISPLAY_CHARSET_HD44780_JAPAN) && DISABLED(DISPLAY_CHARSET_HD44780_WESTERN) && DISABLED(DISPLAY_CHARSET_HD44780_CYRILLIC)
222
-  #define DISPLAY_CHARSET_HD44780_JAPAN
223
-#endif
224
-
225
-#include LANGUAGE_INCLUDE
226
-#include "language_en.h"
227
-
228
-#endif //__LANGUAGE_H

+ 0
- 344
Marlin/configurator/css/configurator.css Näytä tiedosto

@@ -1,344 +0,0 @@
1
-/* configurator.css */
2
-/* Styles for Marlin Configurator */
3
-
4
-.clear { clear: both; }
5
-
6
-/* Prevent selection except PRE tags */
7
-* {
8
-    -webkit-touch-callout: none;
9
-    -webkit-user-select: none;
10
-    -khtml-user-select: none;
11
-    -moz-user-select: none;
12
-    -ms-user-select: none;
13
-    user-select: none;
14
-	}
15
-pre {
16
-    -webkit-touch-callout: text;
17
-    -webkit-user-select: text;
18
-    -khtml-user-select: text;
19
-    -moz-user-select: text;
20
-    -ms-user-select: text;
21
-    user-select: text;
22
-	}
23
-
24
-body { margin: 0; padding: 0; background: #56A; color: #000; font-family: monospace; }
25
-#main {
26
-	max-width: 1100px;
27
-	margin: 0 auto 10px;
28
- 	padding: 0 2%; width: 96%;
29
-	}
30
-
31
-h1, h2, h3, h4, h5, h6 { clear: both; }
32
-
33
-h1, p.info { font-family: sans-serif; }
34
-h1 {
35
-	height: 38px;
36
-	margin-bottom: -30px;
37
-	color: #FFF;
38
-	background: transparent url(logo.png) right top no-repeat;
39
-	}
40
-p.info { padding: 0; color: #000; }
41
-p.info span { color: #800; }
42
-
43
-#message { text-align: center; }
44
-#message { width: 80%; margin: 0 auto 0.25em; color: #FF0; }
45
-#message p { padding: 2px 0; font-weight: bold; border-radius: 0.8em; }
46
-#message p.message { color: #080; background: #CFC; }
47
-#message p.error { color: #F00; background: #FF4; }
48
-#message p.warning { color: #FF0; background: #BA4; }
49
-#message p.message span,
50
-#message p.error span,
51
-#message p.warning span {
52
-	color: #A00;
53
-	background: rgba(255, 255, 255, 1);
54
-	border: 1px solid rgba(0,0,0,0.5);
55
-	border-radius: 1em;
56
-	float: right;
57
-	margin-right: 0.5em;
58
-	padding: 0 3px;
59
-	font-family: sans-serif;
60
-	font-size: small;
61
-	position: relative;
62
-	top: -1px;
63
-	}
64
-
65
-#help strong { color: #0DD; }
66
-img { display: none; }
67
-
68
-/* Forms */
69
-
70
-#config_form {
71
-	display: block;
72
-	background: #EEE;
73
-	padding: 6px 20px 20px;
74
-	color: #000;
75
-	position: relative;
76
-	border-radius: 1.5em;
77
-	border-top-left-radius: 0;
78
-	}
79
-fieldset {
80
-	height: 16.1em;
81
-	overflow-y: scroll;
82
-	overflow-x: hidden;
83
-	margin-top: 10px;
84
-	}
85
-label, input, select, textarea { display: block; float: left; margin: 1px 0; }
86
-label.newline, textarea, fieldset { clear: both; }
87
-label {
88
-	width: 120px; /* label area */
89
-	height: 1em;
90
-	padding: 10px 460px 10px 1em;
91
-	margin-right: -450px;
92
-	text-align: right;
93
-	}
94
-label.blocked, label.added.blocked, label.added.blocked.sublabel { color: #AAA; }
95
-
96
-label.added.sublabel {
97
-	width: auto;
98
-	margin: 11px -2.5em 0 1em;
99
-	padding: 0 3em 0 0;
100
-	font-style: italic;
101
-	color: #444;
102
-	}
103
-label+label.added.sublabel {
104
-	margin-left: 0;
105
-	}
106
-
107
-input[type="text"], select { margin: 0.75em 0 0; }
108
-input[type="checkbox"], input[type="radio"], input[type="file"] { margin: 1em 0 0; }
109
-input[type="checkbox"].enabler, input[type="radio"].enabler { margin-left: 1em; }
110
-
111
-input:disabled { color: #BBB; }
112
-
113
-#config_form input[type="text"].subitem { width: 4em; }
114
-#config_form input[type="text"].subitem+.subitem { margin-left: 4px; }
115
-
116
-input[type="text"].added { width: 20em; }
117
-label.added {
118
-	width: 265px; /* label area */
119
-	height: 1em;
120
-	padding: 10px 370px 10px 1em;
121
-	margin-right: -360px;
122
-	text-align: right;
123
-	}
124
-
125
-ul.tabs { padding: 0; list-style: none; }
126
-ul.tabs li { display: inline; }
127
-ul.tabs li a,
128
-ul.tabs li a.active:hover,
129
-ul.tabs li a.active:active {
130
-	display: block;
131
-	float: left;
132
-	background: #1E4059;
133
-	color: #CCC;
134
-	font-size: 110%;
135
-	border-radius: 0.25em 0.25em 0 0;
136
-	margin: 0 4px 0 0;
137
-	padding: 2px 8px;
138
-	text-decoration: none;
139
-	font-family: georgia,"times new roman",times;
140
-	}
141
-ul.tabs li a.active:link,
142
-ul.tabs li a.active:visited {
143
-	background: #DDD;
144
-	color: #06F;
145
-	cursor: default;
146
-	margin-top: -4px;
147
-	padding-bottom: 4px;
148
-	padding-top: 4px;
149
-	}
150
-ul.tabs li a:hover,
151
-ul.tabs li a:active {
152
-	background: #000;
153
-	color: #FFF;
154
-	}
155
-
156
-fieldset { display: none; border: 1px solid #AAA; border-radius: 1em; }
157
-fieldset legend { display: none; }
158
-
159
-.hilightable span {
160
-	display: block;
161
-	float: left;
162
-	width: 100%;
163
-	height: 1.3em;
164
-	background: rgba(225,255,0,1);
165
-	margin: 0 -100% -1em 0;
166
-	}
167
-
168
-#serial_stepper { padding-top: 0.75em; display: block; float: left; }
169
-/*#SERIAL_PORT { display: none; }*/
170
-
171
-/* Tooltips */
172
-
173
-#tooltip {
174
-	display: none;
175
-	max-width: 30em;
176
-	padding: 8px;
177
-	border: 2px solid #73d699;
178
-	border-radius: 1em;
179
-	position: absolute;
180
-	z-index: 999;
181
-	font-family: sans-serif;
182
-	font-size: 85%;
183
-	color: #000;
184
-	line-height: 1.1;
185
-	background: #e2ff99; /* Old browsers */
186
-	background: -moz-linear-gradient(top,  #e2ff99 0%, #73d699 100%); /* FF3.6+ */
187
-	background: -webkit-gradient(linear, left top, left bottom, color-stop(0%,#e2ff99), color-stop(100%,#73d699)); /* Chrome,Safari4+ */
188
-	background: -webkit-linear-gradient(top,  #e2ff99 0%,#73d699 100%); /* Chrome10+,Safari5.1+ */
189
-	background: -o-linear-gradient(top,  #e2ff99 0%,#73d699 100%); /* Opera 11.10+ */
190
-	background: -ms-linear-gradient(top,  #e2ff99 0%,#73d699 100%); /* IE10+ */
191
-	background: linear-gradient(to bottom,  #e2ff99 0%,#73d699 100%); /* W3C */
192
-	filter: progid:DXImageTransform.Microsoft.gradient( startColorstr='#e2ff99', endColorstr='#73d699',GradientType=0 ); /* IE6-9 */
193
-	-webkit-box-shadow: 0px 6px 25px -4px rgba(0,0,0,0.75);
194
-	-moz-box-shadow: 0px 6px 25px -4px rgba(0,0,0,0.75);
195
-	box-shadow: 0px 6px 25px -4px rgba(0,0,0,0.75);
196
-	}
197
-#tooltip>span {
198
-	position: absolute;
199
-	content: "";
200
-	width: 0;
201
-	height: 0;
202
-	border-left: 8px solid transparent;
203
-	border-right: 8px solid transparent;
204
-	border-top: 8px solid #73d699;
205
-	z-index: 999;
206
-	bottom: -10px;
207
-	left: 20px;
208
-	}
209
-#tooltip>strong { color: #00B; }
210
-
211
-/* Tooltips Checkbox */
212
-
213
-#tipson {
214
-	width: auto;
215
-	height: auto;
216
-	padding: 0;
217
-	margin-right: 0;
218
-	float: right;
219
-	font-weight: bold;
220
-	font-size: 100%;
221
-	font-family: helvetica;
222
-	text-align: left;
223
-	cursor: pointer;
224
-	}
225
-#tipson input { float: none; display: inline; cursor: pointer; }
226
-
227
-/* Config Text */
228
-
229
-pre.config {
230
-	height: 25em;
231
-	padding: 10px;
232
-	border: 2px solid #888;
233
-	border-radius: 5px;
234
-	overflow: auto;
235
-	clear: both;
236
-	background-color: #FFF;
237
-	color: #000;
238
-	font-family: "Fira Mono", monospace;
239
-	font-size: small;
240
-	}
241
-
242
-/* Pre Headers */
243
-
244
-h2 {
245
-	width: 100%;
246
-	margin: 12px -300px 4px 0;
247
-	padding: 0;
248
-	float: left;
249
-	}
250
-
251
-/* Disclosure Widget */
252
-
253
-span.disclose, a.download, a.download-all {︎
254
-	display: block;
255
-	float: right;
256
-	margin-top: 12px;
257
-	}
258
-
259
-span.disclose {
260
-	margin-right: -10px; /* total width */
261
-	margin-left: 14px;
262
-	width: 0;
263
-	height: 0;
264
-	position: relative;
265
-	left: 3px;
266
-	top: 3px;
267
-	cursor: pointer;
268
-	border-left: 8px solid transparent;
269
-	border-right: 8px solid transparent;
270
-	border-top: 10px solid #000;
271
-	}
272
-span.disclose.closed {
273
-	margin-right: -8px; /* total width */
274
-	margin-left: 10px;
275
-	left: 0;
276
-	top: 0;
277
-	border-top: 8px solid transparent;
278
-	border-bottom: 8px solid transparent;
279
-	border-right: 10px solid #000;
280
-	}
281
-span.disclose.almost {
282
-    -ms-transform: rotate(45deg); /* IE 9 */
283
-    -webkit-transform: rotate(45deg); /* Chrome, Safari, Opera */
284
-    transform: rotate(45deg);
285
-	}
286
-span.disclose.closed.almost {
287
-	left: 1px;
288
-	top: 3px;
289
-    -ms-transform: rotate(315deg); /* IE 9 */
290
-    -webkit-transform: rotate(315deg); /* Chrome, Safari, Opera */
291
-    transform: rotate(315deg);
292
-	}
293
-
294
-/* Download Button */
295
-
296
-a.download, a.download-all {
297
-	visibility: hidden;
298
-	padding: 2px;
299
-	border: 1px solid #494;
300
-	border-radius: 4px;
301
-	margin: 12px 0 0;
302
-	background: #FFF;
303
-	color: #494;
304
-	font-family: sans-serif;
305
-	font-size: small;
306
-	font-weight: bold;
307
-	text-decoration: none;
308
-	}
309
-a.download-all { margin: 9px 2em 0; color: #449; border-color: #449; }
310
-
311
-input[type="text"].one_of_2 { max-width: 15%; }
312
-input[type="text"].one_of_3 { max-width: 10%; }
313
-input[type="text"].one_of_4 { max-width: 7%; }
314
-
315
-select.one_of_2 { max-width: 15%; }
316
-select.one_of_3 { max-width: 10%; }
317
-select.one_of_4 { max-width: 14%; }
318
-select.one_of_4+span.label+select.one_of_4+span.label { clear: both; margin-left: 265px; padding-left: 1.75em; }
319
-select.one_of_4+span.label+select.one_of_4+span.label+select.one_of_4+span.label { clear: none; margin-left: 1em; padding-left: 0; }
320
-
321
-@media all and (min-width: 1140px) {
322
-
323
-	#main { max-width: 10000px; }
324
-
325
-	fieldset { float: left; width: 50%; height: auto; }
326
-
327
-	#config_text, #config_adv_text { float: right; clear: right; width: 45%; }
328
-
329
-	pre.config { height: 20em; }
330
-
331
-	.disclose { display: none; }
332
-
333
-	input[type="text"].one_of_2 { max-width: 15%; }
334
-	input[type="text"].one_of_3 { max-width: 9%; }
335
-	input[type="text"].one_of_4 { max-width: 8%; }
336
-
337
-	select.one_of_2 { max-width: 15%; }
338
-	select.one_of_3 { max-width: 10%; }
339
-	select.one_of_4 { max-width: 16%; }
340
-
341
-}
342
-
343
-/*label.blocked, .blocked { display: none; }*/
344
-

BIN
Marlin/configurator/css/logo.png Näytä tiedosto


+ 0
- 129
Marlin/configurator/index.html Näytä tiedosto

@@ -1,129 +0,0 @@
1
-<!DOCTYPE html>
2
-<html>
3
-  <head>
4
-    <meta charset="UTF-8">
5
-    <title>Marlin Firmware Configurator</title>
6
-    <link href='http://fonts.googleapis.com/css?family=Fira+Mono&amp;subset=latin,latin-ext' rel='stylesheet' type='text/css' />
7
-    <script src="js/jquery-2.1.3.min.js"></script>
8
-    <script src="js/binarystring.js"></script>
9
-    <script src="js/binaryfileuploader.js"></script>
10
-    <script src="js/FileSaver.min.js"></script>
11
-    <script src="js/jszip.min.js"></script>
12
-    <script src="js/jcanvas.js"></script>
13
-    <script src="js/jstepper.js"></script>
14
-    <script src="js/configurator.js"></script>
15
-    <link rel="stylesheet" href="css/configurator.css" type="text/css" media="all" />
16
-  </head>
17
-  <body>
18
-    <section id="main">
19
-      <h1>Marlin Configurator</h1>
20
-      <p class="info">Select presets (coming soon), modify, and download.</p>
21
-
22
-      <div id="message"></div>
23
-      <div id="tabs"></div>
24
-
25
-      <form id="config_form">
26
-
27
-        <div id="tooltip"></div>
28
-
29
-        <label>Drop Files:</label><input type="file" id="file-upload" />
30
-        <label id="tipson"><input type="checkbox" checked /> ?</label>
31
-        <a href="" class="download-all">Download Zip</a>
32
-
33
-        <fieldset id="info">
34
-          <legend>Info</legend>
35
-        </fieldset>
36
-
37
-        <fieldset id="machine">
38
-          <legend>Machine</legend>
39
-
40
-          <label class="newline">Serial Port:</label><select name="SERIAL_PORT"></select><div id="serial_stepper"></div>
41
-
42
-          <label>Baud Rate:</label><select name="BAUDRATE"></select>
43
-
44
-          <label>AT90USB BT IF:</label>
45
-            <input name="BLUETOOTH" type="checkbox" value="1" checked />
46
-
47
-          <label class="newline">Motherboard:</label><select name="MOTHERBOARD"></select>
48
-
49
-          <label class="newline">Custom Name:</label><input name="CUSTOM_MACHINE_NAME" type="text" size="14" maxlength="12" value="" />
50
-
51
-          <label class="newline">Machine UUID:</label><input name="MACHINE_UUID" type="text" size="38" maxlength="36" value="" />
52
-
53
-          <label class="newline">Extruders:</label><select name="EXTRUDERS"></select>
54
-
55
-          <label class="newline">Power Supply:</label><select name="POWER_SUPPLY"></select>
56
-
57
-          <label>PS Default Off:</label>
58
-            <input name="PS_DEFAULT_OFF" type="checkbox" value="1" checked />
59
-        </fieldset>
60
-
61
-        <fieldset id="homing">
62
-          <legend>Homing</legend>
63
-        </fieldset>
64
-
65
-        <fieldset id="temperature">
66
-          <legend>Temperature</legend>
67
-          <label class="newline">Temp Sensor 0:</label><select name="TEMP_SENSOR_0"></select>
68
-          <label class="newline">Temp Sensor 1:</label><select name="TEMP_SENSOR_1"></select>
69
-          <label class="newline">Temp Sensor 2:</label><select name="TEMP_SENSOR_2"></select>
70
-          <label class="newline">Bed Temp Sensor:</label><select name="TEMP_SENSOR_BED"></select>
71
-
72
-          <label>Max Diff:</label>
73
-            <input name="MAX_REDUNDANT_TEMP_SENSOR_DIFF" type="text" size="3" maxlength="2" />
74
-
75
-          <label>Temp Residency Time (s):</label>
76
-            <input name="TEMP_RESIDENCY_TIME" type="text" size="3" maxlength="2" />
77
-        </fieldset>
78
-
79
-        <fieldset id="extruder">
80
-          <legend>Extruder</legend>
81
-        </fieldset>
82
-
83
-        <fieldset id="lcd">
84
-          <legend>LCD / SD</legend>
85
-        </fieldset>
86
-
87
-        <fieldset id="bedlevel">
88
-          <legend>Bed Leveling</legend>
89
-        </fieldset>
90
-
91
-        <fieldset id="fwretract">
92
-          <legend>FW Retract</legend>
93
-        </fieldset>
94
-
95
-        <fieldset id="tmc">
96
-          <legend>TMC</legend>
97
-        </fieldset>
98
-
99
-        <fieldset id="l6470">
100
-          <legend>L6470</legend>
101
-        </fieldset>
102
-
103
-        <fieldset id="extras">
104
-          <legend>Extras</legend>
105
-        </fieldset>
106
-
107
-        <fieldset id="more">
108
-          <legend>More…</legend>
109
-        </fieldset>
110
-
111
-        <section id="config_text">
112
-          <h2>Configuration.h</h2>
113
-          <span class="disclose"></span>
114
-          <a href="" class="download">Download</a>
115
-          <pre class="hilightable config"></pre>
116
-        </section>
117
-
118
-        <section id="config_adv_text">
119
-          <h2>Configuration_adv.h</h2>
120
-          <span class="disclose"></span>
121
-          <a href="" class="download">Download</a>
122
-          <pre class="hilightable config"></pre>
123
-        </section>
124
-
125
-        <br class="clear" />
126
-      </form>
127
-    </section>
128
-  </body>
129
-</html>

+ 0
- 2
Marlin/configurator/js/FileSaver.min.js Näytä tiedosto

@@ -1,2 +0,0 @@
1
-/*! @source http://purl.eligrey.com/github/FileSaver.js/blob/master/FileSaver.js */
2
-var saveAs=saveAs||typeof navigator!=="undefined"&&navigator.msSaveOrOpenBlob&&navigator.msSaveOrOpenBlob.bind(navigator)||function(view){"use strict";if(typeof navigator!=="undefined"&&/MSIE [1-9]\./.test(navigator.userAgent)){return}var doc=view.document,get_URL=function(){return view.URL||view.webkitURL||view},save_link=doc.createElementNS("http://www.w3.org/1999/xhtml","a"),can_use_save_link="download"in save_link,click=function(node){var event=doc.createEvent("MouseEvents");event.initMouseEvent("click",true,false,view,0,0,0,0,0,false,false,false,false,0,null);node.dispatchEvent(event)},webkit_req_fs=view.webkitRequestFileSystem,req_fs=view.requestFileSystem||webkit_req_fs||view.mozRequestFileSystem,throw_outside=function(ex){(view.setImmediate||view.setTimeout)(function(){throw ex},0)},force_saveable_type="application/octet-stream",fs_min_size=0,arbitrary_revoke_timeout=500,revoke=function(file){var revoker=function(){if(typeof file==="string"){get_URL().revokeObjectURL(file)}else{file.remove()}};if(view.chrome){revoker()}else{setTimeout(revoker,arbitrary_revoke_timeout)}},dispatch=function(filesaver,event_types,event){event_types=[].concat(event_types);var i=event_types.length;while(i--){var listener=filesaver["on"+event_types[i]];if(typeof listener==="function"){try{listener.call(filesaver,event||filesaver)}catch(ex){throw_outside(ex)}}}},FileSaver=function(blob,name){var filesaver=this,type=blob.type,blob_changed=false,object_url,target_view,dispatch_all=function(){dispatch(filesaver,"writestart progress write writeend".split(" "))},fs_error=function(){if(blob_changed||!object_url){object_url=get_URL().createObjectURL(blob)}if(target_view){target_view.location.href=object_url}else{var new_tab=view.open(object_url,"_blank");if(new_tab==undefined&&typeof safari!=="undefined"){view.location.href=object_url}}filesaver.readyState=filesaver.DONE;dispatch_all();revoke(object_url)},abortable=function(func){return function(){if(filesaver.readyState!==filesaver.DONE){return func.apply(this,arguments)}}},create_if_not_found={create:true,exclusive:false},slice;filesaver.readyState=filesaver.INIT;if(!name){name="download"}if(can_use_save_link){object_url=get_URL().createObjectURL(blob);save_link.href=object_url;save_link.download=name;click(save_link);filesaver.readyState=filesaver.DONE;dispatch_all();revoke(object_url);return}if(view.chrome&&type&&type!==force_saveable_type){slice=blob.slice||blob.webkitSlice;blob=slice.call(blob,0,blob.size,force_saveable_type);blob_changed=true}if(webkit_req_fs&&name!=="download"){name+=".download"}if(type===force_saveable_type||webkit_req_fs){target_view=view}if(!req_fs){fs_error();return}fs_min_size+=blob.size;req_fs(view.TEMPORARY,fs_min_size,abortable(function(fs){fs.root.getDirectory("saved",create_if_not_found,abortable(function(dir){var save=function(){dir.getFile(name,create_if_not_found,abortable(function(file){file.createWriter(abortable(function(writer){writer.onwriteend=function(event){target_view.location.href=file.toURL();filesaver.readyState=filesaver.DONE;dispatch(filesaver,"writeend",event);revoke(file)};writer.onerror=function(){var error=writer.error;if(error.code!==error.ABORT_ERR){fs_error()}};"writestart progress write abort".split(" ").forEach(function(event){writer["on"+event]=filesaver["on"+event]});writer.write(blob);filesaver.abort=function(){writer.abort();filesaver.readyState=filesaver.DONE};filesaver.readyState=filesaver.WRITING}),fs_error)}),fs_error)};dir.getFile(name,{create:false},abortable(function(file){file.remove();save()}),abortable(function(ex){if(ex.code===ex.NOT_FOUND_ERR){save()}else{fs_error()}}))}),fs_error)}),fs_error)},FS_proto=FileSaver.prototype,saveAs=function(blob,name){return new FileSaver(blob,name)};FS_proto.abort=function(){var filesaver=this;filesaver.readyState=filesaver.DONE;dispatch(filesaver,"abort")};FS_proto.readyState=FS_proto.INIT=0;FS_proto.WRITING=1;FS_proto.DONE=2;FS_proto.error=FS_proto.onwritestart=FS_proto.onprogress=FS_proto.onwrite=FS_proto.onabort=FS_proto.onerror=FS_proto.onwriteend=null;return saveAs}(typeof self!=="undefined"&&self||typeof window!=="undefined"&&window||this.content);if(typeof module!=="undefined"&&module.exports){module.exports.saveAs=saveAs}else if(typeof define!=="undefined"&&define!==null&&define.amd!=null){define([],function(){return saveAs})}

+ 0
- 79
Marlin/configurator/js/binaryfileuploader.js Näytä tiedosto

@@ -1,79 +0,0 @@
1
-function BinaryFileUploader(o) {
2
-	this.options = null;
3
-
4
-
5
-	this._defaultOptions = {
6
-		element: null, // HTML file element
7
-		onFileLoad: function(file) {
8
-			console.log(file.toString());
9
-		}
10
-	};
11
-
12
-
13
-	this._init = function(o) {
14
-		if (!this.hasFileUploaderSupport()) return;
15
-
16
-		this._verifyDependencies();
17
-
18
-		this.options = this._mergeObjects(this._defaultOptions, o);
19
-		this._verifyOptions();
20
-
21
-		this.addFileChangeListener();
22
-	}
23
-
24
-
25
-	this.hasFileUploaderSupport = function() {
26
-		return !!(window.File && window.FileReader && window.FileList && window.Blob);
27
-	}
28
-
29
-	this.addFileChangeListener = function() {
30
-		this.options.element.addEventListener(
31
-			'change',
32
-			this._bind(this, this.onFileChange)
33
-		);
34
-	}
35
-
36
-	this.onFileChange = function(e) {
37
-		// TODO accept multiple files
38
-		var file = e.target.files[0],
39
-		    reader = new FileReader();
40
-
41
-		reader.onload = this._bind(this, this.onFileLoad);
42
-		reader.readAsBinaryString(file);
43
-	}
44
-
45
-	this.onFileLoad = function(e) {
46
-		var content = e.target.result,
47
-		    string  = new BinaryString(content);
48
-		this.options.onFileLoad(string);
49
-	}
50
-
51
-
52
-	this._mergeObjects = function(starting, override) {
53
-		var merged = starting;
54
-		for (key in override) merged[key] = override[key];
55
-
56
-		return merged;
57
-	}
58
-
59
-	this._verifyOptions = function() {
60
-		if (!(this.options.element && this.options.element.type && this.options.element.type === 'file')) {
61
-			throw 'Invalid element param in options. Must be a file upload DOM element';
62
-		}
63
-
64
-		if (typeof this.options.onFileLoad !== 'function') {
65
-			throw 'Invalid onFileLoad param in options. Must be a function';
66
-		}
67
-	}
68
-
69
-	this._verifyDependencies = function() {
70
-		if (!window.BinaryString) throw 'BinaryString is missing. Check that you\'ve correctly included it';
71
-	}
72
-
73
-	// helper function for binding methods to objects
74
-	this._bind = function(object, method) {
75
-		return function() {return method.apply(object, arguments);};
76
-	}
77
-
78
-	this._init(o);
79
-}

+ 0
- 168
Marlin/configurator/js/binarystring.js Näytä tiedosto

@@ -1,168 +0,0 @@
1
-function BinaryString(source) {
2
-	this._source = null;
3
-	this._bytes  = [];
4
-	this._pos    = 0;
5
-	this._length = 0;
6
-
7
-	this._init = function(source) {
8
-		this._source = source;
9
-		this._bytes  = this._stringToBytes(this._source);
10
-		this._length = this._bytes.length;
11
-	}
12
-
13
-	this.current = function() {return this._pos;}
14
-
15
-	this.rewind  = function() {return this.jump(0);}
16
-	this.end     = function() {return this.jump(this.length()  - 1);}
17
-	this.next    = function() {return this.jump(this.current() + 1);}
18
-	this.prev    = function() {return this.jump(this.current() - 1);}
19
-
20
-	this.jump = function(pos) {
21
-		if (pos < 0 || pos >= this.length()) return false;
22
-
23
-		this._pos = pos;
24
-		return true;
25
-	}
26
-
27
-	this.readByte = function(pos) {
28
-		pos = (typeof pos == 'number') ? pos : this.current();
29
-		return this.readBytes(1, pos)[0];
30
-	}
31
-
32
-	this.readBytes = function(length, pos) {
33
-		length = length || 1;
34
-		pos    = (typeof pos == 'number') ? pos : this.current();
35
-
36
-		if (pos          >  this.length() ||
37
-		    pos          <  0             ||
38
-		    length       <= 0             ||
39
-		    pos + length >  this.length() ||
40
-		    pos + length <  0
41
-		) {
42
-			return false;
43
-		}
44
-
45
-		var bytes = [];
46
-		
47
-		for (var i = pos; i < pos + length; i++) {
48
-			bytes.push(this._bytes[i]);
49
-		}
50
-
51
-		return bytes;
52
-	}
53
-
54
-	this.length = function() {return this._length;}
55
-
56
-	this.toString = function() {
57
-		var string = '',
58
-		    length = this.length();
59
-
60
-		for (var i = 0; i < length; i++) {
61
-			string += String.fromCharCode(this.readByte(i));
62
-		}
63
-
64
-		return string;
65
-	}
66
-
67
-	this.toUtf8 = function() {
68
-		var inc    = 0,
69
-		    string = '',
70
-		    length = this.length();
71
-
72
-		// determine if first 3 characters are the BOM
73
-		// then skip them in output if so
74
-		if (length >= 3               &&
75
-		    this.readByte(0) === 0xEF &&
76
-		    this.readByte(1) === 0xBB &&
77
-		    this.readByte(2) === 0xBF
78
-		) {
79
-			inc = 3;
80
-		}
81
-
82
-		for (; inc < length; inc++) {
83
-			var byte1 = this.readByte(inc),
84
-			    byte2 = 0,
85
-			    byte3 = 0,
86
-			    byte4 = 0,
87
-			    code1 = 0,
88
-			    code2 = 0,
89
-			    point = 0;
90
-
91
-			switch (true) {
92
-				// single byte character; same as ascii
93
-				case (byte1 < 0x80):
94
-					code1 = byte1;
95
-					break;
96
-
97
-				// 2 byte character
98
-				case (byte1 >= 0xC2 && byte1 < 0xE0):
99
-					byte2 = this.readByte(++inc);
100
-
101
-					code1 = ((byte1 & 0x1F) << 6) +
102
-					         (byte2 & 0x3F);
103
-					break;
104
-
105
-				// 3 byte character
106
-				case (byte1 >= 0xE0 && byte1 < 0xF0):
107
-					byte2 = this.readByte(++inc);
108
-					byte3 = this.readByte(++inc);
109
-
110
-					code1 = ((byte1 & 0xFF) << 12) +
111
-					        ((byte2 & 0x3F) <<  6) +
112
-					         (byte3 & 0x3F);
113
-					break;
114
-
115
-				// 4 byte character
116
-				case (byte1 >= 0xF0 && byte1 < 0xF5):
117
-					byte2 = this.readByte(++inc);
118
-					byte3 = this.readByte(++inc);
119
-					byte4 = this.readByte(++inc);
120
-
121
-					point = ((byte1 & 0x07) << 18) +
122
-					        ((byte2 & 0x3F) << 12) +
123
-					        ((byte3 & 0x3F) <<  6) +
124
-					         (byte4 & 0x3F)
125
-					point -= 0x10000;
126
-
127
-					code1 = (point >> 10)    + 0xD800;
128
-					code2 = (point &  0x3FF) + 0xDC00;
129
-					break;
130
-
131
-				default:
132
-					throw 'Invalid byte ' + this._byteToString(byte1) + ' whilst converting to UTF-8';
133
-					break;
134
-			}
135
-
136
-			string += (code2) ? String.fromCharCode(code1, code2)
137
-			                  : String.fromCharCode(code1);
138
-		}
139
-
140
-		return string;
141
-	}
142
-
143
-	this.toArray  = function() {return this.readBytes(this.length() - 1, 0);} 
144
-
145
-
146
-	this._stringToBytes = function(str) {
147
-		var bytes = [],
148
-		    chr   = 0;
149
-
150
-		for (var i = 0; i < str.length; i++) {
151
-			chr = str.charCodeAt(i);
152
-			bytes.push(chr & 0xFF);
153
-		}
154
-
155
-		return bytes;
156
-	}
157
-
158
-	this._byteToString = function(byte) {
159
-		var asString = byte.toString(16).toUpperCase();
160
-		while (asString.length < 2) {
161
-			asString = '0' + asString;
162
-		}
163
-
164
-		return '0x' + asString;
165
-	}
166
-
167
-	this._init(source);
168
-}

+ 0
- 1432
Marlin/configurator/js/configurator.js
File diff suppressed because it is too large
Näytä tiedosto


+ 0
- 524
Marlin/configurator/js/jcanvas.js Näytä tiedosto

@@ -1,524 +0,0 @@
1
-/*!
2
-  jCanvas v2.2.1
3
-  Caleb Evans
4
-  2.2.1 revisions by Thinkyhead
5
-*/
6
-
7
-(function($, document, Math, Number, undefined) {
8
-
9
-// jC global object
10
-var jC = {};
11
-jC.originals = {
12
-	width: 20,
13
-	height: 20,
14
-	cornerRadius: 0,
15
-	fillStyle: 'transparent',
16
-	strokeStyle: 'transparent',
17
-	strokeWidth: 5,
18
-	strokeCap: 'butt',
19
-	strokeJoin: 'miter',
20
-	shadowX: 0,
21
-	shadowY: 0,
22
-	shadowBlur: 10,
23
-	shadowColor: 'transparent',
24
-	x: 0, y: 0,
25
-	x1: 0, y1: 0,
26
-	radius: 10,
27
-	start: 0,
28
-	end: 360,
29
-	ccw: false,
30
-	inDegrees: true,
31
-	fromCenter: true,
32
-	closed: false,
33
-	sides: 3,
34
-	angle: 0,
35
-	text: '',
36
-	font: 'normal 12pt sans-serif',
37
-	align: 'center',
38
-	baseline: 'middle',
39
-	source: '',
40
-	repeat: 'repeat'
41
-};
42
-// Duplicate original defaults
43
-jC.defaults = $.extend({}, jC.originals);
44
-
45
-// Set global properties
46
-function setGlobals(context, map) {
47
-	context.fillStyle = map.fillStyle;
48
-	context.strokeStyle = map.strokeStyle;
49
-	context.lineWidth = map.strokeWidth;
50
-	context.lineCap = map.strokeCap;
51
-	context.lineJoin = map.strokeJoin;
52
-	context.shadowOffsetX = map.shadowX;
53
-	context.shadowOffsetY = map.shadowY;
54
-	context.shadowBlur = map.shadowBlur;
55
-	context.shadowColor = map.shadowColor;
56
-}
57
-
58
-// Close path if chosen
59
-function closePath(context, map) {
60
-	if (map.closed === true) {
61
-		context.closePath();
62
-		context.fill();
63
-		context.stroke();
64
-	} else {
65
-		context.fill();
66
-		context.stroke();
67
-		context.closePath();
68
-	}
69
-}
70
-
71
-// Measure angles in degrees if chosen
72
-function checkUnits(map) {
73
-	if (map.inDegrees === true) {
74
-		return Math.PI / 180;
75
-	} else {
76
-		return 1;
77
-	}
78
-}
79
-
80
-// Set canvas defaults
81
-$.fn.canvas = function(args) {
82
-	// Reset defaults if no value is passed
83
-	if (typeof args === 'undefined') {
84
-		jC.defaults = jC.originals;
85
-	} else {
86
-		jC.defaults = $.extend({}, jC.defaults, args);
87
-	}
88
-	return this;
89
-};
90
-
91
-// Load canvas
92
-$.fn.loadCanvas = function(context) {
93
-	if (typeof context === 'undefined') {context = '2d';}
94
-	return this[0].getContext(context);
95
-};
96
-
97
-// Create gradient
98
-$.fn.gradient = function(args) {
99
-	var ctx = this.loadCanvas(),
100
-		// Specify custom defaults
101
-		gDefaults = {
102
-			x1: 0, y1: 0,
103
-			x2: 0, y2: 0,
104
-			r1: 10, r2: 100
105
-		},
106
-		params = $.extend({}, gDefaults, args),
107
-		gradient, stops = 0, percent, i;
108
-		
109
-	// Create radial gradient if chosen
110
-	if (typeof args.r1 === 'undefined' && typeof args.r2 === 'undefined') {
111
-		gradient = ctx.createLinearGradient(params.x1, params.y1, params.x2, params.y2);
112
-	} else {
113
-		gradient = ctx.createRadialGradient(params.x1, params.y1, params.r1, params.x2, params.y2, params.r2);
114
-	}
115
-	
116
-	// Count number of color stops
117
-	for (i=1; i<=Number.MAX_VALUE; i+=1) {
118
-		if (params['c' + i]) {
119
-			stops += 1;
120
-		} else {
121
-			break;
122
-		}
123
-	}
124
-	
125
-	// Calculate color stop percentages if absent
126
-	for (i=1; i<=stops; i+=1) {
127
-		percent = Math.round((100 / (stops-1)) * (i-1)) / 100;
128
-		if (typeof params['s' + i] === 'undefined') {
129
-			params['s' + i] = percent;
130
-		}
131
-		gradient.addColorStop(params['s' + i], params['c' + i]);
132
-	}
133
-	return gradient;
134
-};
135
-
136
-// Create pattern
137
-$.fn.pattern = function(args) {
138
-	var ctx = this.loadCanvas(),
139
-		params = $.extend({}, jC.defaults, args),
140
-		pattern,
141
-		img = document.createElement('img');
142
-	img.src = params.source;
143
-	
144
-	// Create pattern
145
-	function create() {
146
-		if (img.complete === true) {
147
-			// Create pattern
148
-			pattern = ctx.createPattern(img, params.repeat);
149
-		} else {
150
-			throw "The pattern has not loaded yet";
151
-		}
152
-	}
153
-	try {
154
-		create();
155
-	} catch(error) {
156
-		img.onload = create;
157
-	}
158
-	return pattern;
159
-};
160
-
161
-// Clear canvas
162
-$.fn.clearCanvas = function(args) {
163
-	var ctx = this.loadCanvas(),
164
-		params = $.extend({}, jC.defaults, args);
165
-
166
-	// Draw from center if chosen
167
-	if (params.fromCenter === true) {
168
-		params.x -= params.width / 2;
169
-		params.y -= params.height / 2;
170
-	}
171
-
172
-	// Clear entire canvas if chosen
173
-	ctx.beginPath();
174
-	if (typeof args === 'undefined') {
175
-		ctx.clearRect(0, 0, this.width(), this.height());
176
-	} else {
177
-		ctx.clearRect(params.x, params.y, params.width, params.height);
178
-	} 
179
-	ctx.closePath();
180
-	return this;
181
-};
182
-
183
-// Save canvas
184
-$.fn.saveCanvas = function() {
185
-	var ctx = this.loadCanvas();
186
-	ctx.save();
187
-	return this;
188
-};
189
-
190
-// Restore canvas
191
-$.fn.restoreCanvas = function() {
192
-	var ctx = this.loadCanvas();
193
-	ctx.restore();
194
-	return this;
195
-};
196
-
197
-// Scale canvas
198
-$.fn.scaleCanvas = function(args) {
199
-	var ctx = this.loadCanvas(),
200
-		params = $.extend({}, jC.defaults, args);
201
-	ctx.save();
202
-	ctx.translate(params.x, params.y);
203
-	ctx.scale(params.width, params.height);
204
-	ctx.translate(-params.x, -params.y)
205
-	return this;
206
-};
207
-
208
-// Translate canvas
209
-$.fn.translateCanvas = function(args) {
210
-	var ctx = this.loadCanvas(),
211
-		params = $.extend({}, jC.defaults, args);
212
-	ctx.save();
213
-	ctx.translate(params.x, params.y);		
214
-	return this;
215
-};
216
-
217
-// Rotate canvas
218
-$.fn.rotateCanvas = function(args) {
219
-	var ctx = this.loadCanvas(),
220
-		params = $.extend({}, jC.defaults, args),
221
-		toRad = checkUnits(params);
222
-	
223
-	ctx.save();
224
-	ctx.translate(params.x, params.y);
225
-	ctx.rotate(params.angle * toRad);
226
-	ctx.translate(-params.x, -params.y);
227
-	return this;
228
-};
229
-
230
-// Draw rectangle
231
-$.fn.drawRect = function(args) {
232
-	var ctx = this.loadCanvas(),
233
-		params = $.extend({}, jC.defaults, args),
234
-		toRad = checkUnits(params),
235
-		x1, y1, x2, y2, r;
236
-	setGlobals(ctx, params);
237
-	
238
-	// Draw from center if chosen
239
-	if (params.fromCenter === true) {
240
-		params.x -= params.width / 2;
241
-		params.y -= params.height / 2;
242
-	}
243
-		
244
-	// Draw rounded rectangle if chosen
245
-	if (params.cornerRadius > 0) {
246
-		x1 = params.x;
247
-		y1 = params.y;
248
-		x2 = params.x + params.width;
249
-		y2 = params.y + params.height;
250
-		r = params.cornerRadius;
251
-		if ((x2 - x1) - (2 * r) < 0) {
252
-			r = (x2 - x1) / 2;
253
-		}
254
-		if ((y2 - y1) - (2 * r) < 0) {
255
-			r = (y2 - y1) / 2;
256
-		}
257
-		ctx.beginPath();
258
-		ctx.moveTo(x1+r,y1);
259
-		ctx.lineTo(x2-r,y1);
260
-		ctx.arc(x2-r, y1+r, r, 270*toRad, 360*toRad, false);
261
-		ctx.lineTo(x2,y2-r);
262
-		ctx.arc(x2-r, y2-r, r, 0, 90*toRad, false);
263
-		ctx.lineTo(x1+r,y2);
264
-		ctx.arc(x1+r, y2-r, r, 90*toRad, 180*toRad, false);
265
-		ctx.lineTo(x1,y1+r);
266
-		ctx.arc(x1+r, y1+r, r, 180*toRad, 270*toRad, false);
267
-		ctx.fill();
268
-		ctx.stroke();
269
-		ctx.closePath();
270
-	} else {
271
-		ctx.fillRect(params.x, params.y, params.width, params.height);
272
-		ctx.strokeRect(params.x, params.y, params.width, params.height);
273
-	}
274
-	return this;
275
-};
276
-
277
-// Draw arc
278
-$.fn.drawArc = function(args) {
279
-	var ctx = this.loadCanvas(),
280
-		params = $.extend({}, jC.defaults, args),
281
-		toRad = checkUnits(params);
282
-		setGlobals(ctx, params);
283
-	
284
-	// Draw from center if chosen
285
-	if (params.fromCenter === false) {
286
-		params.x += params.radius;
287
-		params.y += params.radius;
288
-	}
289
-	
290
-	ctx.beginPath();
291
-	ctx.arc(params.x, params.y, params.radius, (params.start*toRad)-(Math.PI/2), (params.end*toRad)-(Math.PI/2), params.ccw);
292
-	// Close path if chosen
293
-	closePath(ctx, params);
294
-	return this;
295
-};
296
-
297
-// Draw ellipse
298
-$.fn.drawEllipse = function(args) {
299
-	var ctx = this.loadCanvas(),
300
-		params = $.extend({}, jC.defaults, args),
301
-		controlW = params.width * (4/3);
302
-		setGlobals(ctx, params);
303
-	
304
-	// Draw from center if chosen
305
-	if (params.fromCenter === false) {
306
-		params.x += params.width / 2;
307
-		params.y += params.height / 2;
308
-	}
309
-	
310
-	// Increment coordinates to prevent negative values
311
-	params.x += 1e-10;
312
-	params.y += 1e-10;
313
-	
314
-	// Create ellipse
315
-	ctx.beginPath();
316
-	ctx.moveTo(params.x, params.y-params.height/2);
317
-	ctx.bezierCurveTo(params.x-controlW/2,params.y-params.height/2,
318
-		params.x-controlW/2,params.y+params.height/2,
319
-		params.x,params.y+params.height/2);
320
-	ctx.bezierCurveTo(params.x+controlW/2,params.y+params.height/2,
321
-		params.x+controlW/2,params.y-params.height/2,
322
-		params.x,params.y-params.height/2);
323
-	ctx.closePath();
324
-	ctx.fill();
325
-	ctx.stroke();
326
-	return this;
327
-};
328
-
329
-// Draw line
330
-$.fn.drawLine = function(args) {
331
-	var ctx = this.loadCanvas(),
332
-		params = $.extend({}, jC.defaults, args),
333
-		max = Number.MAX_VALUE, l,
334
-		lx, ly;
335
-	setGlobals(ctx, params);
336
-	
337
-	// Draw each point
338
-	ctx.beginPath();
339
-	ctx.moveTo(params.x1, params.y1);
340
-	for (l=2; l<max; l+=1) {
341
-		lx = params['x' + l];
342
-		ly = params['y' + l];
343
-		// Stop loop when all points are drawn
344
-		if (typeof lx === 'undefined' || typeof ly === 'undefined') {
345
-			break;
346
-		}
347
-		ctx.lineTo(lx, ly);
348
-	}
349
-	// Close path if chosen
350
-	closePath(ctx, params);
351
-	return this;
352
-};
353
-
354
-// Draw quadratic curve
355
-$.fn.drawQuad = function(args) {
356
-	var ctx = this.loadCanvas(),
357
-		params = $.extend({}, jC.defaults, args),
358
-		max = Number.MAX_VALUE, l,
359
-		lx, ly, lcx, lcy;
360
-	setGlobals(ctx, params);
361
-	
362
-	// Draw each point
363
-	ctx.beginPath();
364
-	ctx.moveTo(params.x1, params.y1);
365
-	for (l=2; l<max; l+=1) {
366
-		lx = params['x' + l];
367
-    if (typeof lx === 'undefined') break;
368
-		ly = params['y' + l];
369
-    if (typeof ly === 'undefined') break;
370
-		lcx = params['cx' + (l-1)];
371
-    if (typeof lcx === 'undefined') break;
372
-		lcy = params['cy' + (l-1)];
373
-    if (typeof lcy === 'undefined') break;
374
-		ctx.quadraticCurveTo(lcx, lcy, lx, ly);
375
-	}
376
-	// Close path if chosen
377
-	closePath(ctx, params);
378
-	return this;
379
-};
380
-
381
-// Draw Bezier curve
382
-$.fn.drawBezier = function(args) {
383
-	var ctx = this.loadCanvas(),
384
-		params = $.extend({}, jC.defaults, args),
385
-		max = Number.MAX_VALUE,
386
-		l=2, lc=1, lx, ly, lcx1, lcy1, lcx2, lcy2, i;
387
-	setGlobals(ctx, params);
388
-
389
-	// Draw each point
390
-	ctx.beginPath();
391
-	ctx.moveTo(params.x1, params.y1);
392
-	for (i=2; i<max; i+=1) {
393
-		lx = params['x' + l];
394
-    if (typeof lx === 'undefined') break;
395
-		ly = params['y' + l];
396
-    if (typeof ly === 'undefined') break;
397
-		lcx1 = params['cx' + lc];
398
-    if (typeof lcx1 === 'undefined') break;
399
-		lcy1 = params['cy' + lc];
400
-    if (typeof lcy1 === 'undefined') break;
401
-		lcx2 = params['cx' + (lc+1)];
402
-    if (typeof lcx2 === 'undefined') break;
403
-		lcy2 = params['cy' + (lc+1)];
404
-    if (typeof lcy2 === 'undefined') break;
405
-		ctx.bezierCurveTo(lcx1, lcy1, lcx2, lcy2, lx, ly);
406
-		l += 1;
407
-		lc += 2;
408
-	}
409
-	// Close path if chosen
410
-	closePath(ctx, params);
411
-	return this;
412
-};
413
-
414
-// Draw text
415
-$.fn.drawText = function(args) {
416
-	var ctx = this.loadCanvas(),
417
-		params = $.extend({}, jC.defaults, args);
418
-	setGlobals(ctx, params);
419
-	
420
-	// Set text-specific properties
421
-	ctx.textBaseline = params.baseline;
422
-	ctx.textAlign = params.align;
423
-	ctx.font = params.font;
424
-	
425
-	ctx.strokeText(params.text, params.x, params.y);
426
-	ctx.fillText(params.text, params.x, params.y);
427
-	return this;
428
-};
429
-
430
-// Draw image
431
-$.fn.drawImage = function(args) {
432
-	var ctx = this.loadCanvas(),
433
-		params = $.extend({}, jC.defaults, args),
434
-		// Define image source
435
-		img = document.createElement('img');
436
-  	img.src = params.source;
437
-	  setGlobals(ctx, params);
438
-
439
-	// Draw image function
440
-	function draw() {
441
-		if (img.complete) {
442
-
443
-  		var scaleFac = img.width / img.height;
444
-
445
-			// If width/height are specified
446
-			if (typeof args.width !== 'undefined' && typeof args.height !== 'undefined') {
447
-				img.width = args.width;
448
-				img.height = args.height;
449
-			// If width is specified
450
-			} else if (typeof args.width !== 'undefined' && typeof args.height === 'undefined') {
451
-				img.width = args.width;
452
-				img.height = img.width / scaleFac;
453
-			// If height is specified
454
-			} else if (typeof args.width === 'undefined' && typeof args.height !== 'undefined') {
455
-				img.height = args.height;
456
-				img.width = img.height * scaleFac;
457
-			}
458
-		
459
-			// Draw from center if chosen
460
-			if (params.fromCenter === true) {
461
-				params.x -= img.width / 2;
462
-				params.y -= img.height / 2;
463
-			}
464
-
465
-			// Draw image
466
-			ctx.drawImage(img, params.x, params.y, img.width, img.height);
467
-		} else {
468
-			throw "The image has not loaded yet.";
469
-		}
470
-	}
471
-
472
-  function dodraw() {
473
-    // console.log("dodraw...");
474
-    try {
475
-  	  // console.log("dodraw...try...");
476
-      draw();
477
-    }
478
-    catch(error) {
479
-      // console.log("dodraw...catch: " + error);
480
-    }
481
-  }
482
-
483
-	// Draw image if already loaded
484
-  // console.log("--------------------");
485
-  // console.log("drawImage " + img.src);
486
-	try {
487
-    // console.log("try...");
488
-		draw();
489
-	} catch(error) {
490
-    // console.log("catch: " + error);
491
-		img.onload = dodraw;
492
-	}
493
-	return this;
494
-};
495
-
496
-// Draw polygon
497
-$.fn.drawPolygon = function(args) {
498
-	var ctx = this.loadCanvas(),
499
-		params = $.extend({}, jC.defaults, args),
500
-		theta, dtheta, x, y,
501
-		toRad = checkUnits(params), i;
502
-	setGlobals(ctx, params);
503
-	
504
-	if (params.sides >= 3) {		
505
-		// Calculate points and draw
506
-		theta = (Math.PI/2) + (Math.PI/params.sides) + (params.angle*toRad);
507
-		dtheta = (Math.PI*2) / params.sides;
508
-		for (i=0; i<params.sides; i+=1) {
509
-			x = params.x + (params.radius * Math.cos(theta)) + 1e-10;
510
-			y = params.y + (params.radius * Math.sin(theta)) + 1e-10;
511
-			if (params.fromCenter === false) {
512
-				x += params.radius;
513
-				y += params.radius;
514
-			}
515
-			ctx.lineTo(x, y);
516
-			theta += dtheta;
517
-		}
518
-		closePath(ctx, params);
519
-	}
520
-	return this;
521
-};
522
-
523
-return window.jCanvas = jC;
524
-}(jQuery, document, Math, Number));

+ 0
- 4
Marlin/configurator/js/jquery-2.1.3.min.js
File diff suppressed because it is too large
Näytä tiedosto


+ 0
- 220
Marlin/configurator/js/jstepper.js Näytä tiedosto

@@ -1,220 +0,0 @@
1
-/*!
2
- * jQuery "stepper" Plugin
3
- * version 0.0.1
4
- * @requires jQuery v1.3.2 or later
5
- * @requires jCanvas
6
- *
7
- * Authored 2011-06-11 Scott Lahteine (thinkyhead.com)
8
- *
9
- *  A very simple numerical stepper.
10
- *  TODO: place arrows based on div size, make 50/50 width
11
- *
12
- *  Usage example:
13
- *
14
- *  $('#mydiv').jstepper({
15
- *    min: 1,
16
- *    max: 4,
17
- *    val: 1,
18
- *    arrowWidth: 15,
19
- *    arrowHeight: '22px',
20
- *    color: '#FFF',
21
- *    acolor: '#F70',
22
- *    hcolor: '#FF0',
23
- *    id: 'select-me',
24
- *    stepperClass: 'inner',
25
- *    textStyle: {width:'1.5em',fontSize:'20px',textAlign:'center'},
26
- *    onChange: function(v) { },
27
- *  });
28
- *
29
- */
30
-;(function($) {
31
-  var un = 'undefined';
32
-
33
-  $.jstepperArrows = [
34
-    { name:'prev', poly:[[1.0,0],[0,0.5],[1.0,1.0]] },
35
-    { name:'next', poly:[[0,0],[1.0,0.5],[0,1.0]] }
36
-  ];
37
-
38
- 	$.fn.jstepper = function(args) {
39
-
40
-		return this.each(function() {
41
-
42
-      var defaults = {
43
-        min: 1,
44
-        max: null,
45
-        val: null,
46
-        active: true,
47
-        placeholder: null,
48
-        arrowWidth: 0,
49
-        arrowHeight: 0,
50
-        color: '#FFF',
51
-        hcolor: '#FF0',
52
-        acolor: '#F80',
53
-        id: '',
54
-        stepperClass: '',
55
-        textStyle: '',
56
-        onChange: (function(v){ if (typeof console.log !== 'undefined') console.log("val="+v); })
57
-      };
58
-
59
-      args = $.extend(defaults, args || {});
60
-
61
-		  var min = args.min * 1,
62
-          max = (args.max !== null) ? args.max * 1 : min,
63
-          span = max - min + 1,
64
-          val = (args.val !== null) ? args.val * 1 : min,
65
-          active = !args.disabled,
66
-          placeholder = args.placeholder,
67
-          arrowWidth = 1 * args.arrowWidth.toString().replace(/px/,''),
68
-          arrowHeight = 1 * args.arrowHeight.toString().replace(/px/,''),
69
-          color = args.color,
70
-          hcolor = args.hcolor,
71
-          acolor = args.acolor,
72
-			    $prev = $('<a href="#prev" style="cursor:w-resize;"><canvas/></a>'),
73
-			    $marq = $('<div class="number"/>').css({float:'left',textAlign:'center'}),
74
-			    $next = $('<a href="#next" style="cursor:e-resize;"><canvas/></a>'),
75
-			    arrow = [ $prev.find('canvas')[0], $next.find('canvas')[0] ],
76
-			    $stepper = $('<span class="jstepper"/>').append($prev).append($marq).append($next).append('<div style="clear:both;"/>'),
77
-			    onChange = args.onChange;
78
-
79
-      if (args.id) $stepper[0].id = args.id;
80
-      if (args.stepperClass) $stepper.addClass(args.stepperClass);
81
-      if (args.textStyle) $marq.css(args.textStyle);
82
-
83
-      // replace a span, but embed elsewhere
84
-      if (this.tagName == 'SPAN') {
85
-        var previd = this.id;
86
-        $(this).replaceWith($stepper);
87
-        if (previd) $stepper.attr('id',previd);
88
-      }
89
-      else {
90
-        $(this).append($stepper);
91
-      }
92
-
93
-      // hook to call functions on this object
94
-      $stepper[0].ui = {
95
-
96
-        refresh: function() {
97
-          this.updateNumber();
98
-          this._drawArrow(0, 1);
99
-          this._drawArrow(1, 1);
100
-          return this;
101
-        },
102
-
103
-        _drawArrow: function(i,state) {
104
-          var $elm = $(arrow[i]),
105
-              desc = $.jstepperArrows[i],
106
-              fillStyle = (state == 2) ? hcolor : (state == 3) ? acolor : color,
107
-              draw = { fillStyle: fillStyle },
108
-              w = $elm.width(), h = $elm.height();
109
-
110
-          if (w <= 0) w = $elm.attr('width');
111
-          if (h <= 0) h = $elm.attr('height');
112
-
113
-          $.each(desc.poly,function(i,v){
114
-            ++i;
115
-            draw['x'+i] = v[0] * w;
116
-            draw['y'+i] = v[1] * h;
117
-          });
118
-          $elm.restoreCanvas().clearCanvas().drawLine(draw);
119
-        },
120
-
121
-        updateNumber: function() {
122
-          $marq.html((active || placeholder === null) ? val.toString() : placeholder);
123
-          return this;
124
-        },
125
-
126
-        _doclick: function(i) {
127
-          this.add(i ? 1 : -1);
128
-          this._drawArrow(i, 3);
129
-          var self = this;
130
-          setTimeout(function(){ self._drawArrow(i, 2); }, 50);
131
-        },
132
-
133
-        add: function(x) {
134
-          val = (((val - min) + x + span) % span) + min;
135
-          this.updateNumber();
136
-          this.didChange(val);
137
-          return this;
138
-        },
139
-
140
-        min: function(v) {
141
-          if (typeof v === un) return min;
142
-          this.setRange(v,max);
143
-          return this;
144
-        },
145
-
146
-        max: function(v) {
147
-          if (typeof v === un) return max;
148
-          this.setRange(min,v);
149
-          return this;
150
-        },
151
-
152
-        val: function(v) {
153
-          if (typeof v === un) return val;
154
-          val = (((v - min) + span) % span) + min;
155
-          this.updateNumber();
156
-          return this;
157
-        },
158
-
159
-        setRange: function(lo, hi, ini) {
160
-          if (lo > hi) hi = (lo += hi -= lo) - hi;
161
-          min = lo; max = hi; span = hi - lo + 1;
162
-          if (typeof ini !== un) val = ini;
163
-          if (val < min) val = min;
164
-          if (val > max) val = max;
165
-          this.updateNumber();
166
-          return this;
167
-        },
168
-
169
-        active: function(a) {
170
-          if (typeof a === un) return active;
171
-          (active = a) ? $marq.removeClass('inactive') : $marq.addClass('inactive');
172
-          this.updateNumber();
173
-          return this;
174
-        },
175
-
176
-        disable: function() { this.active(false); return this; },
177
-        enable: function() { this.active(true); return this; },
178
-
179
-        clearPlaceholder: function() {
180
-          this.setPlaceholder(null);
181
-          return this;
182
-        },
183
-        setPlaceholder: function(p) {
184
-          placeholder = p;
185
-          if (!active) this.updateNumber();
186
-          return this;
187
-        },
188
-
189
-        didChange: onChange
190
-
191
-      };
192
-
193
-      // set hover and click for each arrow
194
-      $.each($.jstepperArrows, function(i,desc) {
195
-        var $elm = $(arrow[i]),
196
-            w = arrowWidth ? arrowWidth : $elm.width() ? $elm.width() : 15,
197
-            h = arrowHeight ? arrowHeight : $elm.height() ? $elm.height() : 24;
198
-        $elm[0]._index = i;
199
-        $elm
200
-          .css({float:'left'})
201
-          .attr({width:w,height:h,'class':desc.name})
202
-          .hover(
203
-            function(e) { $stepper[0].ui._drawArrow(e.target._index, 2); },
204
-            function(e) { $stepper[0].ui._drawArrow(e.target._index, 1); }
205
-          )
206
-          .click(function(e){
207
-            $stepper[0].ui._doclick(e.target._index);
208
-            return false;
209
-          });
210
-      });
211
-
212
-      // init the visuals first time
213
-  		$stepper[0].ui.refresh();
214
-
215
-		}); // this.each
216
-
217
-  }; // $.fn.jstepper
218
-
219
-})( jQuery );
220
-

+ 0
- 14
Marlin/configurator/js/jszip.min.js
File diff suppressed because it is too large
Näytä tiedosto


+ 115
- 0
Marlin/dac_mcp4728.cpp Näytä tiedosto

@@ -0,0 +1,115 @@
1
+/*
2
+
3
+  mcp4728.cpp - Arduino library for MicroChip MCP4728 I2C D/A converter
4
+  For implementation details, please take a look at the datasheet http://ww1.microchip.com/downloads/en/DeviceDoc/22187a.pdf
5
+  For discussion and feedback, please go to http://arduino.cc/forum/index.php/topic,51842.0.html
6
+*/
7
+
8
+
9
+/* _____PROJECT INCLUDES_____________________________________________________ */
10
+#include "dac_mcp4728.h"
11
+
12
+#if ENABLED(DAC_STEPPER_CURRENT)
13
+
14
+// Used Global variables
15
+uint16_t     mcp4728_values[4];
16
+
17
+/*
18
+Begin I2C, get current values (input register and eeprom) of mcp4728
19
+*/
20
+void mcp4728_init() {
21
+  Wire.begin();
22
+  Wire.requestFrom(int(DAC_DEV_ADDRESS), 24);
23
+  while(Wire.available()) {
24
+    int deviceID = Wire.receive();
25
+    int hiByte = Wire.receive();
26
+    int loByte = Wire.receive();
27
+
28
+    int isEEPROM = (deviceID & 0B00001000) >> 3;
29
+    int channel = (deviceID & 0B00110000) >> 4;
30
+    if (isEEPROM != 1) {
31
+      mcp4728_values[channel] = word((hiByte & 0B00001111), loByte);
32
+    }
33
+  }
34
+}
35
+
36
+/*
37
+Write input resister value to specified channel using fastwrite method.
38
+Channel : 0-3, Values : 0-4095
39
+*/
40
+uint8_t mcp4728_analogWrite(uint8_t channel, uint16_t value) {
41
+  mcp4728_values[channel] = value;
42
+  return mcp4728_fastWrite();
43
+}
44
+/*
45
+Write all input resistor values to EEPROM using SequencialWrite method.
46
+This will update both input register and EEPROM value
47
+This will also write current Vref, PowerDown, Gain settings to EEPROM
48
+*/
49
+uint8_t mcp4728_eepromWrite() {
50
+  Wire.beginTransmission(DAC_DEV_ADDRESS);
51
+  Wire.send(SEQWRITE);
52
+  for (uint8_t channel=0; channel <= 3; channel++) {
53
+    Wire.send(DAC_STEPPER_VREF << 7 | 0 << 5 | DAC_STEPPER_GAIN << 4 | highByte(mcp4728_values[channel]));
54
+    Wire.send(lowByte(mcp4728_values[channel]));
55
+  }
56
+  return Wire.endTransmission();
57
+}
58
+
59
+/*
60
+  Write Voltage reference setting to all input regiters
61
+*/
62
+uint8_t mcp4728_setVref_all(uint8_t value) {
63
+  Wire.beginTransmission(DAC_DEV_ADDRESS);
64
+  Wire.send(VREFWRITE | value << 3 | value << 2 | value << 1 | value);
65
+  return Wire.endTransmission();
66
+}
67
+/*
68
+  Write Gain setting to all input regiters
69
+*/
70
+uint8_t mcp4728_setGain_all(uint8_t value) {
71
+  Wire.beginTransmission(DAC_DEV_ADDRESS);
72
+  Wire.send(GAINWRITE | value << 3 | value << 2 | value << 1 | value);
73
+  return Wire.endTransmission();
74
+}
75
+
76
+/*
77
+  Return Input Regiter value
78
+*/
79
+uint16_t mcp4728_getValue(uint8_t channel) { return mcp4728_values[channel]; }
80
+
81
+/*
82
+// Steph: Might be useful in the future
83
+// Return Vout
84
+uint16_t mcp4728_getVout(uint8_t channel) {
85
+  uint32_t vref = 2048;
86
+  uint32_t vOut = (vref * mcp4728_values[channel] * (_DAC_STEPPER_GAIN + 1)) / 4096;
87
+  if (vOut > defaultVDD) vOut = defaultVDD;
88
+  return vOut;
89
+}
90
+*/
91
+
92
+/*
93
+FastWrite input register values - All DAC ouput update. refer to DATASHEET 5.6.1
94
+DAC Input and PowerDown bits update.
95
+No EEPROM update
96
+*/
97
+uint8_t mcp4728_fastWrite() {
98
+  Wire.beginTransmission(DAC_DEV_ADDRESS);
99
+  for (uint8_t channel=0; channel <= 3; channel++) {
100
+    Wire.send(highByte(mcp4728_values[channel]));
101
+    Wire.send(lowByte(mcp4728_values[channel]));
102
+  }
103
+  return Wire.endTransmission();
104
+}
105
+
106
+/*
107
+Common function for simple general commands
108
+*/
109
+uint8_t mcp4728_simpleCommand(byte simpleCommand) {
110
+  Wire.beginTransmission(GENERALCALL);
111
+  Wire.send(simpleCommand);
112
+  return Wire.endTransmission();
113
+}
114
+
115
+#endif // DAC_STEPPER_CURRENT

+ 44
- 0
Marlin/dac_mcp4728.h Näytä tiedosto

@@ -0,0 +1,44 @@
1
+/**
2
+Arduino library for MicroChip MCP4728 I2C D/A converter.
3
+*/
4
+
5
+#ifndef mcp4728_h
6
+#define mcp4728_h
7
+
8
+#include "Configuration.h"
9
+#include "Configuration_adv.h"
10
+
11
+#if ENABLED(DAC_STEPPER_CURRENT)
12
+#include "WProgram.h"
13
+#include "Wire.h"
14
+//#include <Wire.h>
15
+
16
+#define defaultVDD 5000
17
+#define BASE_ADDR 0x60
18
+#define RESET 0B00000110
19
+#define WAKE 0B00001001
20
+#define UPDATE 0B00001000
21
+#define MULTIWRITE 0B01000000
22
+#define SINGLEWRITE 0B01011000
23
+#define SEQWRITE 0B01010000
24
+#define VREFWRITE 0B10000000
25
+#define GAINWRITE 0B11000000
26
+#define POWERDOWNWRITE 0B10100000
27
+#define GENERALCALL 0B0000000
28
+#define GAINWRITE 0B11000000
29
+
30
+// This is taken from the original lib, makes it easy to edit if needed
31
+#define DAC_DEV_ADDRESS (BASE_ADDR | 0x00)
32
+
33
+void mcp4728_init();
34
+uint8_t mcp4728_analogWrite(uint8_t channel, uint16_t value);
35
+uint8_t mcp4728_eepromWrite();
36
+uint8_t mcp4728_setVref_all(uint8_t value);
37
+uint8_t mcp4728_setGain_all(uint8_t value);
38
+uint16_t mcp4728_getValue(uint8_t channel);
39
+uint8_t mcp4728_fastWrite();
40
+uint8_t mcp4728_simpleCommand(byte simpleCommand);
41
+
42
+#endif
43
+#endif
44
+

+ 75
- 43
Marlin/dogm_lcd_implementation.h Näytä tiedosto

@@ -22,9 +22,9 @@
22 22
   #define BLEN_A 0
23 23
   #define BLEN_B 1
24 24
   #define BLEN_C 2
25
-  #define EN_A BIT(BLEN_A)
26
-  #define EN_B BIT(BLEN_B)
27
-  #define EN_C BIT(BLEN_C)
25
+  #define EN_A (_BV(BLEN_A))
26
+  #define EN_B (_BV(BLEN_B))
27
+  #define EN_C (_BV(BLEN_C))
28 28
   #define LCD_CLICKED (buttons&EN_C)
29 29
 #endif
30 30
 
@@ -146,7 +146,6 @@
146 146
 #include "utf_mapper.h"
147 147
 
148 148
 int lcd_contrast;
149
-static unsigned char blink = 0; // Variable for visualization of fan rotation in GLCD
150 149
 static char currentfont = 0;
151 150
 
152 151
 static void lcd_setFont(char font_nr) {
@@ -170,7 +169,7 @@ char lcd_print(char c) {
170 169
   }
171 170
 }
172 171
 
173
-char lcd_print(char* str) {
172
+char lcd_print(const char* str) {
174 173
   char c;
175 174
   int i = 0;
176 175
   char n = 0;
@@ -225,14 +224,14 @@ static void lcd_implementation_init() {
225 224
   #endif
226 225
 
227 226
   #if ENABLED(SHOW_BOOTSCREEN)
228
-    int offx = (u8g.getWidth() - START_BMPWIDTH) / 2;
227
+    int offx = (u8g.getWidth() - (START_BMPWIDTH)) / 2;
229 228
     #if ENABLED(START_BMPHIGH)
230 229
       int offy = 0;
231 230
     #else
232 231
       int offy = DOG_CHAR_HEIGHT;
233 232
     #endif
234 233
 
235
-    int txt1X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE1) - 1) * DOG_CHAR_WIDTH) / 2;
234
+    int txt1X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE1) - 1) * (DOG_CHAR_WIDTH)) / 2;
236 235
 
237 236
     u8g.firstPage();
238 237
     do {
@@ -240,11 +239,11 @@ static void lcd_implementation_init() {
240 239
         u8g.drawBitmapP(offx, offy, START_BMPBYTEWIDTH, START_BMPHEIGHT, start_bmp);
241 240
         lcd_setFont(FONT_MENU);
242 241
         #ifndef STRING_SPLASH_LINE2
243
-          u8g.drawStr(txt1X, u8g.getHeight() - DOG_CHAR_HEIGHT, STRING_SPLASH_LINE1);
242
+          u8g.drawStr(txt1X, u8g.getHeight() - (DOG_CHAR_HEIGHT), STRING_SPLASH_LINE1);
244 243
         #else
245
-          int txt2X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE2) - 1) * DOG_CHAR_WIDTH) / 2;
246
-          u8g.drawStr(txt1X, u8g.getHeight() - DOG_CHAR_HEIGHT * 3 / 2, STRING_SPLASH_LINE1);
247
-          u8g.drawStr(txt2X, u8g.getHeight() - DOG_CHAR_HEIGHT * 1 / 2, STRING_SPLASH_LINE2);
244
+          int txt2X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE2) - 1) * (DOG_CHAR_WIDTH)) / 2;
245
+          u8g.drawStr(txt1X, u8g.getHeight() - (DOG_CHAR_HEIGHT) * 3 / 2, STRING_SPLASH_LINE1);
246
+          u8g.drawStr(txt2X, u8g.getHeight() - (DOG_CHAR_HEIGHT) * 1 / 2, STRING_SPLASH_LINE2);
248 247
         #endif
249 248
       }
250 249
     } while (u8g.nextPage());
@@ -270,7 +269,7 @@ static void _draw_heater_status(int x, int heater) {
270 269
   lcd_print(itostr3(int(heater >= 0 ? degHotend(heater) : degBed()) + 0.5));
271 270
 
272 271
   lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
273
-  if (!isHeatingHotend(0)) {
272
+  if (heater >= 0 ? !isHeatingHotend(heater) : !isHeatingBed()) {
274 273
     u8g.drawBox(x+7,y,2,2);
275 274
   }
276 275
   else {
@@ -284,29 +283,30 @@ static void lcd_implementation_status_screen() {
284 283
   u8g.setColorIndex(1); // black on white
285 284
 
286 285
   // Symbols menu graphics, animated fan
287
-  u8g.drawBitmapP(9,1,STATUS_SCREENBYTEWIDTH,STATUS_SCREENHEIGHT, (blink % 2) && fanSpeed ? status_screen0_bmp : status_screen1_bmp);
286
+  u8g.drawBitmapP(9,1,STATUS_SCREENBYTEWIDTH,STATUS_SCREENHEIGHT, (blink % 2) && fanSpeeds[0] ? status_screen0_bmp : status_screen1_bmp);
288 287
 
289 288
   #if ENABLED(SDSUPPORT)
290 289
     // SD Card Symbol
291
-    u8g.drawBox(42, 42 - TALL_FONT_CORRECTION, 8, 7);
292
-    u8g.drawBox(50, 44 - TALL_FONT_CORRECTION, 2, 5);
293
-    u8g.drawFrame(42, 49 - TALL_FONT_CORRECTION, 10, 4);
294
-    u8g.drawPixel(50, 43 - TALL_FONT_CORRECTION);
290
+    u8g.drawBox(42, 42 - (TALL_FONT_CORRECTION), 8, 7);
291
+    u8g.drawBox(50, 44 - (TALL_FONT_CORRECTION), 2, 5);
292
+    u8g.drawFrame(42, 49 - (TALL_FONT_CORRECTION), 10, 4);
293
+    u8g.drawPixel(50, 43 - (TALL_FONT_CORRECTION));
295 294
 
296 295
     // Progress bar frame
297
-    u8g.drawFrame(54, 49, 73, 4 - TALL_FONT_CORRECTION);
296
+    u8g.drawFrame(54, 49, 73, 4 - (TALL_FONT_CORRECTION));
298 297
 
299 298
     // SD Card Progress bar and clock
300 299
     lcd_setFont(FONT_STATUSMENU);
301 300
 
302 301
     if (IS_SD_PRINTING) {
303 302
       // Progress bar solid part
304
-      u8g.drawBox(55, 50, (unsigned int)(71.f * card.percentDone() / 100.f), 2 - TALL_FONT_CORRECTION);
303
+      u8g.drawBox(55, 50, (unsigned int)(71.f * card.percentDone() / 100.f), 2 - (TALL_FONT_CORRECTION));
305 304
     }
306 305
 
307 306
     u8g.setPrintPos(80,48);
308 307
     if (print_job_start_ms != 0) {
309
-      uint16_t time = (millis() - print_job_start_ms) / 60000;
308
+      uint16_t time = (((print_job_stop_ms > print_job_start_ms)
309
+                       ? print_job_stop_ms : millis()) - print_job_start_ms) / 60000;
310 310
       lcd_print(itostr2(time/60));
311 311
       lcd_print(':');
312 312
       lcd_print(itostr2(time%60));
@@ -325,8 +325,8 @@ static void lcd_implementation_status_screen() {
325 325
   // Fan
326 326
   lcd_setFont(FONT_STATUSMENU);
327 327
   u8g.setPrintPos(104, 27);
328
-  #if HAS_FAN
329
-    int per = ((fanSpeed + 1) * 100) / 256;
328
+  #if HAS_FAN0
329
+    int per = ((fanSpeeds[0] + 1) * 100) / 256;
330 330
     if (per) {
331 331
       lcd_print(itostr3(per));
332 332
       lcd_print('%');
@@ -338,6 +338,9 @@ static void lcd_implementation_status_screen() {
338 338
     }
339 339
 
340 340
   // X, Y, Z-Coordinates
341
+  // Before homing the axis letters are blinking 'X' <-> '?'.
342
+  // When axis is homed but axis_known_position is false the axis letters are blinking 'X' <-> ' '.
343
+  // When everything is ok you see a constant 'X'.
341 344
   #define XYZ_BASELINE 38
342 345
   lcd_setFont(FONT_STATUSMENU);
343 346
 
@@ -348,32 +351,61 @@ static void lcd_implementation_status_screen() {
348 351
   #endif
349 352
   u8g.setColorIndex(0); // white on black
350 353
   u8g.setPrintPos(2, XYZ_BASELINE);
351
-  lcd_print('X');
354
+  if (blink & 1)
355
+    lcd_printPGM(PSTR("X"));
356
+  else {
357
+    if (!axis_homed[X_AXIS])
358
+      lcd_printPGM(PSTR("?"));
359
+    else
360
+      #if DISABLED(DISABLE_REDUCED_ACCURACY_WARNING)
361
+        if (!axis_known_position[X_AXIS])
362
+          lcd_printPGM(PSTR(" "));
363
+        else
364
+      #endif
365
+      lcd_printPGM(PSTR("X"));
366
+  }
352 367
   u8g.drawPixel(8, XYZ_BASELINE - 5);
353 368
   u8g.drawPixel(8, XYZ_BASELINE - 3);
354 369
   u8g.setPrintPos(10, XYZ_BASELINE);
355
-  if (axis_known_position[X_AXIS])
356
-    lcd_print(ftostr31ns(current_position[X_AXIS]));
357
-  else
358
-    lcd_printPGM(PSTR("---"));
370
+  lcd_print(ftostr31ns(current_position[X_AXIS]));
371
+
359 372
   u8g.setPrintPos(43, XYZ_BASELINE);
360
-  lcd_print('Y');
373
+  if (blink & 1)
374
+    lcd_printPGM(PSTR("Y"));
375
+  else {
376
+    if (!axis_homed[Y_AXIS])
377
+      lcd_printPGM(PSTR("?"));
378
+    else
379
+      #if DISABLED(DISABLE_REDUCED_ACCURACY_WARNING)
380
+        if (!axis_known_position[Y_AXIS])
381
+          lcd_printPGM(PSTR(" "));
382
+        else
383
+      #endif
384
+      lcd_printPGM(PSTR("Y"));
385
+  }
361 386
   u8g.drawPixel(49, XYZ_BASELINE - 5);
362 387
   u8g.drawPixel(49, XYZ_BASELINE - 3);
363 388
   u8g.setPrintPos(51, XYZ_BASELINE);
364
-  if (axis_known_position[Y_AXIS])
365
-    lcd_print(ftostr31ns(current_position[Y_AXIS]));
366
-  else
367
-    lcd_printPGM(PSTR("---"));
389
+  lcd_print(ftostr31ns(current_position[Y_AXIS]));
390
+
368 391
   u8g.setPrintPos(83, XYZ_BASELINE);
369
-  lcd_print('Z');
392
+  if (blink & 1)
393
+    lcd_printPGM(PSTR("Z"));
394
+  else {
395
+    if (!axis_homed[Z_AXIS])
396
+      lcd_printPGM(PSTR("?"));
397
+    else
398
+      #if DISABLED(DISABLE_REDUCED_ACCURACY_WARNING)
399
+        if (!axis_known_position[Z_AXIS])
400
+          lcd_printPGM(PSTR(" "));
401
+        else
402
+      #endif
403
+      lcd_printPGM(PSTR("Z"));
404
+  }
370 405
   u8g.drawPixel(89, XYZ_BASELINE - 5);
371 406
   u8g.drawPixel(89, XYZ_BASELINE - 3);
372 407
   u8g.setPrintPos(91, XYZ_BASELINE);
373
-  if (axis_known_position[Z_AXIS])
374
-    lcd_print(ftostr32sp(current_position[Z_AXIS]));
375
-  else
376
-    lcd_printPGM(PSTR("---.--"));
408
+  lcd_print(ftostr32sp(current_position[Z_AXIS]));
377 409
   u8g.setColorIndex(1); // black on white
378 410
 
379 411
   // Feedrate
@@ -411,13 +443,13 @@ static void lcd_implementation_status_screen() {
411 443
 static void lcd_implementation_mark_as_selected(uint8_t row, bool isSelected) {
412 444
   if (isSelected) {
413 445
     u8g.setColorIndex(1);  // black on white
414
-    u8g.drawBox(0, row * DOG_CHAR_HEIGHT + 3 - TALL_FONT_CORRECTION, LCD_PIXEL_WIDTH, DOG_CHAR_HEIGHT);
446
+    u8g.drawBox(0, row * (DOG_CHAR_HEIGHT) + 3 - (TALL_FONT_CORRECTION), LCD_PIXEL_WIDTH, DOG_CHAR_HEIGHT);
415 447
     u8g.setColorIndex(0);  // following text must be white on black
416 448
   }
417 449
   else {
418 450
     u8g.setColorIndex(1); // unmarked text is black on white
419 451
   }
420
-  u8g.setPrintPos(START_ROW * DOG_CHAR_WIDTH, (row + 1) * DOG_CHAR_HEIGHT);
452
+  u8g.setPrintPos((START_ROW) * (DOG_CHAR_WIDTH), (row + 1) * (DOG_CHAR_HEIGHT));
421 453
 }
422 454
 
423 455
 static void lcd_implementation_drawmenu_generic(bool isSelected, uint8_t row, const char* pstr, char pre_char, char post_char) {
@@ -431,7 +463,7 @@ static void lcd_implementation_drawmenu_generic(bool isSelected, uint8_t row, co
431 463
     pstr++;
432 464
   }
433 465
   while (n--) lcd_print(' ');
434
-  u8g.setPrintPos(LCD_PIXEL_WIDTH - DOG_CHAR_WIDTH, (row + 1) * DOG_CHAR_HEIGHT);
466
+  u8g.setPrintPos(LCD_PIXEL_WIDTH - (DOG_CHAR_WIDTH), (row + 1) * (DOG_CHAR_HEIGHT));
435 467
   lcd_print(post_char);
436 468
   lcd_print(' ');
437 469
 }
@@ -449,7 +481,7 @@ static void _drawmenu_setting_edit_generic(bool isSelected, uint8_t row, const c
449 481
   }
450 482
   lcd_print(':');
451 483
   while (n--) lcd_print(' ');
452
-  u8g.setPrintPos(LCD_PIXEL_WIDTH - DOG_CHAR_WIDTH * vallen, (row + 1) * DOG_CHAR_HEIGHT);
484
+  u8g.setPrintPos(LCD_PIXEL_WIDTH - (DOG_CHAR_WIDTH) * vallen, (row + 1) * (DOG_CHAR_HEIGHT));
453 485
   if (pgm)  lcd_printPGM(data);  else  lcd_print((char*)data);
454 486
 }
455 487
 
@@ -477,7 +509,7 @@ static void _drawmenu_setting_edit_generic(bool isSelected, uint8_t row, const c
477 509
 #define lcd_implementation_drawmenu_setting_edit_callback_long5(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr5(*(data)))
478 510
 #define lcd_implementation_drawmenu_setting_edit_callback_bool(sel, row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))
479 511
 
480
-void lcd_implementation_drawedit(const char* pstr, char* value) {
512
+void lcd_implementation_drawedit(const char* pstr, const char* value) {
481 513
   uint8_t rows = 1;
482 514
   uint8_t lcd_width = LCD_WIDTH, char_width = DOG_CHAR_WIDTH;
483 515
   uint8_t vallen = lcd_strlen(value);
@@ -496,7 +528,7 @@ void lcd_implementation_drawedit(const char* pstr, char* value) {
496 528
 
497 529
   if (lcd_strlen_P(pstr) > LCD_WIDTH - 2 - vallen) rows = 2;
498 530
 
499
-  const float kHalfChar = DOG_CHAR_HEIGHT_EDIT / 2;
531
+  const float kHalfChar = (DOG_CHAR_HEIGHT_EDIT) / 2;
500 532
   float rowHeight = u8g.getHeight() / (rows + 1); // 1/(rows+1) = 1/2 or 1/3
501 533
 
502 534
   u8g.setPrintPos(0, rowHeight + kHalfChar);

+ 152
- 102
Marlin/example_configurations/Felix/Configuration.h Näytä tiedosto

@@ -110,6 +110,7 @@ Here are some standard links for getting your machine calibrated:
110 110
 //--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
111 111
 //
112 112
 //// Temperature sensor settings:
113
+// -3 is thermocouple with MAX31855 (only for sensor 0)
113 114
 // -2 is thermocouple with MAX6675 (only for sensor 0)
114 115
 // -1 is thermocouple with AD595
115 116
 // 0 is not used
@@ -129,6 +130,7 @@ Here are some standard links for getting your machine calibrated:
129 130
 // 13 is 100k Hisens 3950  1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
130 131
 // 20 is the PT100 circuit found in the Ultimainboard V2.x
131 132
 // 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
133
+// 70 is the 100K thermistor found in the bq Hephestos 2
132 134
 //
133 135
 //    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
134 136
 //                          (but gives greater accuracy and more stable PID)
@@ -144,7 +146,7 @@ Here are some standard links for getting your machine calibrated:
144 146
 //     Use it for Testing or Development purposes. NEVER for production machine.
145 147
 //#define DUMMY_THERMISTOR_998_VALUE 25
146 148
 //#define DUMMY_THERMISTOR_999_VALUE 100
147
-// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
149
+// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-3': "Thermocouple + MAX31855 (only for sensor 0)", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
148 150
 #define TEMP_SENSOR_0 1
149 151
 #define TEMP_SENSOR_1 0
150 152
 #define TEMP_SENSOR_2 0
@@ -178,14 +180,9 @@ Here are some standard links for getting your machine calibrated:
178 180
 #define HEATER_3_MAXTEMP 275
179 181
 #define BED_MAXTEMP 150
180 182
 
181
-// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
182
-// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
183
-// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
184
-//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
185
-
186 183
 // If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
187
-//#define EXTRUDER_WATTS (12.0*12.0/6.7) //  P=I^2/R
188
-//#define BED_WATTS (12.0*12.0/1.1)      // P=I^2/R
184
+//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
185
+//#define BED_WATTS (12.0*12.0/1.1)      // P=U^2/R
189 186
 
190 187
 //===========================================================================
191 188
 //============================= PID Settings ================================
@@ -266,16 +263,15 @@ Here are some standard links for getting your machine calibrated:
266 263
 //===========================================================================
267 264
 
268 265
 /**
269
- * Thermal Runaway Protection protects your printer from damage and fire if a
266
+ * Thermal Protection protects your printer from damage and fire if a
270 267
  * thermistor falls out or temperature sensors fail in any way.
271 268
  *
272 269
  * The issue: If a thermistor falls out or a temperature sensor fails,
273 270
  * Marlin can no longer sense the actual temperature. Since a disconnected
274 271
  * thermistor reads as a low temperature, the firmware will keep the heater on.
275 272
  *
276
- * The solution: Once the temperature reaches the target, start observing.
277
- * If the temperature stays too far below the target (hysteresis) for too long,
278
- * the firmware will halt as a safety precaution.
273
+ * If you get "Thermal Runaway" or "Heating failed" errors the
274
+ * details can be tuned in Configuration_adv.h
279 275
  */
280 276
 
281 277
 #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
@@ -323,10 +319,52 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
323 319
 #define DISABLE_MAX_ENDSTOPS
324 320
 //#define DISABLE_MIN_ENDSTOPS
325 321
 
326
-// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
327
-// This only affects a Z probe endstop if you have separate Z min endstop as well and have
328
-// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
329
-// this has no effect.
322
+//===========================================================================
323
+//============================= Z Probe Options =============================
324
+//===========================================================================
325
+
326
+// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
327
+// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
328
+//
329
+// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
330
+//
331
+// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
332
+// Example: To park the head outside the bed area when homing with G28.
333
+//
334
+// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
335
+//
336
+// For a servo-based Z probe, you must set up servo support below, including
337
+// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
338
+//
339
+// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
340
+// - Use 5V for powered (usu. inductive) sensors.
341
+// - Otherwise connect:
342
+//   - normally-closed switches to GND and D32.
343
+//   - normally-open switches to 5V and D32.
344
+//
345
+// Normally-closed switches are advised and are the default.
346
+//
347
+// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
348
+// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
349
+// default pin for all RAMPS-based boards. Some other boards map differently.
350
+// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
351
+//
352
+// WARNING:
353
+// Setting the wrong pin may have unexpected and potentially disastrous consequences.
354
+// Use with caution and do your homework.
355
+//
356
+//#define Z_MIN_PROBE_ENDSTOP
357
+
358
+// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
359
+// The Z_MIN_PIN will then be used for both Z-homing and probing.
360
+#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
361
+
362
+// To use a probe you must enable one of the two options above!
363
+
364
+// This option disables the use of the Z_MIN_PROBE_PIN
365
+// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
366
+// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
367
+// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
330 368
 //#define DISABLE_Z_MIN_PROBE_ENDSTOP
331 369
 
332 370
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
@@ -336,11 +374,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
336 374
 #define Z_ENABLE_ON 0
337 375
 #define E_ENABLE_ON 0 // For all extruders
338 376
 
339
-// Disables axis when it's not being used.
377
+// Disables axis stepper immediately when it's not being used.
340 378
 // WARNING: When motors turn off there is a chance of losing position accuracy!
341 379
 #define DISABLE_X false
342 380
 #define DISABLE_Y false
343 381
 #define DISABLE_Z false
382
+// Warn on display about possibly reduced accuracy
383
+//#define DISABLE_REDUCED_ACCURACY_WARNING
344 384
 
345 385
 // @section extruder
346 386
 
@@ -363,6 +403,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
363 403
 #define INVERT_E3_DIR false
364 404
 
365 405
 // @section homing
406
+//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
407
+                                    // Be sure you have this distance over your Z_MAX_POS in case.
366 408
 
367 409
 // ENDSTOP SETTINGS:
368 410
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
@@ -398,24 +440,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
398 440
 #endif
399 441
 
400 442
 //===========================================================================
401
-//=========================== Manual Bed Leveling ===========================
443
+//============================ Mesh Bed Leveling ============================
402 444
 //===========================================================================
403 445
 
404
-//#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
405 446
 //#define MESH_BED_LEVELING    // Enable mesh bed leveling.
406 447
 
407
-#if ENABLED(MANUAL_BED_LEVELING)
408
-  #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
409
-#endif  // MANUAL_BED_LEVELING
410
-
411 448
 #if ENABLED(MESH_BED_LEVELING)
412 449
   #define MESH_MIN_X 10
413
-  #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
450
+  #define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
414 451
   #define MESH_MIN_Y 10
415
-  #define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
452
+  #define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
416 453
   #define MESH_NUM_X_POINTS 3  // Don't use more than 7 points per axis, implementation limited.
417 454
   #define MESH_NUM_Y_POINTS 3
418 455
   #define MESH_HOME_SEARCH_Z 4  // Z after Home, bed somewhere below but above 0.0.
456
+
457
+  //#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
458
+
459
+  #if ENABLED(MANUAL_BED_LEVELING)
460
+    #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
461
+  #endif  // MANUAL_BED_LEVELING
462
+
419 463
 #endif  // MESH_BED_LEVELING
420 464
 
421 465
 //===========================================================================
@@ -426,7 +470,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
426 470
 
427 471
 //#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
428 472
 //#define DEBUG_LEVELING_FEATURE
429
-//#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
473
+//#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
430 474
 
431 475
 #if ENABLED(AUTO_BED_LEVELING_FEATURE)
432 476
 
@@ -438,7 +482,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
438 482
   //   This mode is preferred because there are more measurements.
439 483
   //
440 484
   // - "3-point" mode
441
-  //   Probe 3 arbitrary points on the bed (that aren't colinear)
485
+  //   Probe 3 arbitrary points on the bed (that aren't collinear)
442 486
   //   You specify the XY coordinates of all 3 points.
443 487
 
444 488
   // Enable this to sample the bed in a grid (least squares solution).
@@ -452,7 +496,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
452 496
     #define FRONT_PROBE_BED_POSITION 20
453 497
     #define BACK_PROBE_BED_POSITION 180
454 498
 
455
-    #define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
499
+    #define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
456 500
 
457 501
     // Set the number of grid points per dimension.
458 502
     // You probably don't need more than 3 (squared=9).
@@ -460,25 +504,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
460 504
 
461 505
   #else  // !AUTO_BED_LEVELING_GRID
462 506
 
463
-      // Arbitrary points to probe.
464
-      // A simple cross-product is used to estimate the plane of the bed.
465
-      #define ABL_PROBE_PT_1_X 15
466
-      #define ABL_PROBE_PT_1_Y 180
467
-      #define ABL_PROBE_PT_2_X 15
468
-      #define ABL_PROBE_PT_2_Y 20
469
-      #define ABL_PROBE_PT_3_X 170
470
-      #define ABL_PROBE_PT_3_Y 20
507
+    // Arbitrary points to probe.
508
+    // A simple cross-product is used to estimate the plane of the bed.
509
+    #define ABL_PROBE_PT_1_X 15
510
+    #define ABL_PROBE_PT_1_Y 180
511
+    #define ABL_PROBE_PT_2_X 15
512
+    #define ABL_PROBE_PT_2_Y 20
513
+    #define ABL_PROBE_PT_3_X 170
514
+    #define ABL_PROBE_PT_3_Y 20
471 515
 
472 516
   #endif // AUTO_BED_LEVELING_GRID
473 517
 
474
-  // Offsets to the Z probe relative to the nozzle tip.
518
+  // Z Probe to nozzle (X,Y) offset, relative to (0, 0).
475 519
   // X and Y offsets must be integers.
476
-  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // Z probe to nozzle X offset: -left  +right
477
-  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Z probe to nozzle Y offset: -front +behind
478
-  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z probe to nozzle Z offset: -below (always!)
479
-
480
-  #define Z_RAISE_BEFORE_HOMING 4       // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
481
-                                        // Be sure you have this distance over your Z_MAX_POS in case.
520
+  //
521
+  // In the following example the X and Y offsets are both positive:
522
+  // #define X_PROBE_OFFSET_FROM_EXTRUDER 10
523
+  // #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
524
+  //
525
+  //    +-- BACK ---+
526
+  //    |           |
527
+  //  L |    (+) P  | R <-- probe (20,20)
528
+  //  E |           | I
529
+  //  F | (-) N (+) | G <-- nozzle (10,10)
530
+  //  T |           | H
531
+  //    |    (-)    | T
532
+  //    |           |
533
+  //    O-- FRONT --+
534
+  //  (0,0)
535
+  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // X offset: -left  [of the nozzle] +right
536
+  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Y offset: -front [of the nozzle] +behind
537
+  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z offset: -below [the nozzle] (always negative!)
482 538
 
483 539
   #define XY_TRAVEL_SPEED 8000         // X and Y axis travel speed between probes, in mm/min.
484 540
 
@@ -486,16 +542,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
486 542
   #define Z_RAISE_BETWEEN_PROBINGS 5  // How much the Z axis will be raised when traveling from between next probing points.
487 543
   #define Z_RAISE_AFTER_PROBING 15    // How much the Z axis will be raised after the last probing point.
488 544
 
489
-//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
490
-                                                                            // Useful to retract a deployable Z probe.
545
+  //#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
546
+                                                                             // Useful to retract a deployable Z probe.
547
+
548
+  // Probes are sensors/switches that need to be activated before they can be used
549
+  // and deactivated after the use.
550
+  // Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
551
+
552
+  // A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
553
+  // when the hardware endstops are active.
554
+  //#define FIX_MOUNTED_PROBE
555
+
556
+  // A Servo Probe can be defined in the servo section below.
491 557
 
492
-  //#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
558
+  // An Allen Key Probe is currently predefined only in the delta example configurations.
559
+
560
+  //#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
493 561
   //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
494 562
 
495
-// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
496
-// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
563
+  // If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
564
+  // it is highly recommended you leave Z_SAFE_HOMING enabled!
497 565
 
498
-  #define Z_SAFE_HOMING   // This feature is meant to avoid Z homing with Z probe outside the bed area.
566
+  #define Z_SAFE_HOMING   // Use the z-min-probe for homing to z-min - not the z-min-endstop.
567
+                          // This feature is meant to avoid Z homing with Z probe outside the bed area.
499 568
                           // When defined, it will:
500 569
                           // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
501 570
                           // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
@@ -509,37 +578,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
509 578
 
510 579
   #endif
511 580
 
512
-  // Support for a dedicated Z probe endstop separate from the Z min endstop.
513
-  // If you would like to use both a Z probe and a Z min endstop together,
514
-  // uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
515
-  // If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
516
-  // Example: To park the head outside the bed area when homing with G28.
517
-  //
518
-  // WARNING:
519
-  // The Z min endstop will need to set properly as it would without a Z probe
520
-  // to prevent head crashes and premature stopping during a print.
521
-  //
522
-  // To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
523
-  // defined in the pins_XXXXX.h file for your control board.
524
-  // If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
525
-  // Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
526
-  // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
527
-  // in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
528
-  // otherwise connect to ground and D32 for normally closed configuration
529
-  // and 5V and D32 for normally open configurations.
530
-  // Normally closed configuration is advised and assumed.
531
-  // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
532
-  // Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
533
-  // Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
534
-  // D32 is currently selected in the RAMPS 1.3/1.4 pin file.
535
-  // All other boards will need changes to the respective pins_XXXXX.h file.
536
-  //
537
-  // WARNING:
538
-  // Setting the wrong pin may have unexpected and potentially disastrous outcomes.
539
-  // Use with caution and do your homework.
540
-  //
541
-  //#define Z_MIN_PROBE_ENDSTOP
542
-
543 581
 #endif // AUTO_BED_LEVELING_FEATURE
544 582
 
545 583
 
@@ -571,10 +609,10 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
571 609
 // default steps per unit for Felix 2.0/3.0: 0.00249mm x/y rounding error with 3mm pitch HTD belt and 14 tooth pulleys. 0 z error.
572 610
 #define DEFAULT_AXIS_STEPS_PER_UNIT   {76.190476, 76.190476, 1600, 164}
573 611
 #define DEFAULT_MAX_FEEDRATE          {500, 500, 5, 25}    // (mm/sec)
574
-#define DEFAULT_MAX_ACCELERATION      {5000,5000,100,80000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot.
612
+#define DEFAULT_MAX_ACCELERATION      {5000,5000,100,80000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
575 613
 
576 614
 #define DEFAULT_ACCELERATION          1750 //1500    // X, Y, Z and E max acceleration in mm/s^2 for printing moves
577
-#define DEFAULT_RETRACT_ACCELERATION  5000 // X, Y, Z and E max acceleration in mm/s^2 for r retracts
615
+#define DEFAULT_RETRACT_ACCELERATION  5000 // E acceleration in mm/s^2 for retracts
578 616
 #define DEFAULT_TRAVEL_ACCELERATION   3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
579 617
 
580 618
 // The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
@@ -615,6 +653,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
615 653
 #endif
616 654
 
617 655
 //
656
+// Host Keepalive
657
+//
658
+// By default Marlin will send a busy status message to the host
659
+// every 2 seconds when it can't accept commands.
660
+//
661
+//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
662
+
663
+//
618 664
 // M100 Free Memory Watcher
619 665
 //
620 666
 //#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
@@ -634,13 +680,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
634 680
 // @section lcd
635 681
 
636 682
 // Define your display language below. Replace (en) with your language code and uncomment.
637
-// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
683
+// en, pl, fr, de, es, ru, bg, it, pt, pt_utf8, pt-br, pt-br_utf8, fi, an, nl, ca, eu, kana, kana_utf8, cn, cz, test
638 684
 // See also language.h
639 685
 //#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
640 686
 
641 687
 // Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
642 688
 // To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
643
-// See also documentation/LCDLanguageFont.md
689
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
644 690
   #define DISPLAY_CHARSET_HD44780_JAPAN        // this is the most common hardware
645 691
   //#define DISPLAY_CHARSET_HD44780_WESTERN
646 692
   //#define DISPLAY_CHARSET_HD44780_CYRILLIC
@@ -648,12 +694,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
648 694
 //#define ULTRA_LCD  //general LCD support, also 16x2
649 695
 //#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
650 696
 //#define SDSUPPORT // Enable SD Card Support in Hardware Console
651
-// Changed behaviour! If you need SDSUPPORT uncomment it!
652
-//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
653
-//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
697
+                    // Changed behaviour! If you need SDSUPPORT uncomment it!
698
+//#define SPI_SPEED SPI_HALF_SPEED // (also SPI_QUARTER_SPEED, SPI_EIGHTH_SPEED) Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
654 699
 //#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
655 700
 //#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
656 701
 //#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
702
+//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
657 703
 //#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
658 704
 //#define ULTIPANEL  //the UltiPanel as on Thingiverse
659 705
 //#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
@@ -670,13 +716,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
670 716
 
671 717
 // The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
672 718
 // http://panucatt.com
673
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
719
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
674 720
 //#define VIKI2
675 721
 //#define miniVIKI
676 722
 
677 723
 // This is a new controller currently under development.  https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
678 724
 //
679
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
725
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
680 726
 //#define ELB_FULL_GRAPHIC_CONTROLLER
681 727
 //#define SD_DETECT_INVERTED
682 728
 
@@ -691,7 +737,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
691 737
 // The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
692 738
 // http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
693 739
 //
694
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
740
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
695 741
 //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
696 742
 
697 743
 // The RepRapWorld REPRAPWORLD_KEYPAD v1.1
@@ -714,6 +760,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
714 760
 
715 761
 //#define LCD_I2C_SAINSMART_YWROBOT
716 762
 
763
+//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
764
+
717 765
 // PANELOLU2 LCD with status LEDs, separate encoder and click inputs
718 766
 //
719 767
 // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
@@ -727,7 +775,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
727 775
 //#define LCD_I2C_VIKI
728 776
 
729 777
 // SSD1306 OLED generic display support
730
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
778
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
731 779
 //#define U8GLIB_SSD1306
732 780
 
733 781
 // Shift register panels
@@ -739,7 +787,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
739 787
 
740 788
 // @section extras
741 789
 
742
-// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
790
+// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
743 791
 #define FAST_PWM_FAN
744 792
 
745 793
 // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
@@ -821,19 +869,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
821 869
 // Uncomment below to enable
822 870
 //#define FILAMENT_SENSOR
823 871
 
824
-#define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
825
-#define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
826
-
827 872
 #define DEFAULT_NOMINAL_FILAMENT_DIA 3.00  //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
828
-#define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
829
-#define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
830
-#define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
831 873
 
832
-//defines used in the code
833
-#define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
874
+#if ENABLED(FILAMENT_SENSOR)
875
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
876
+  #define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
877
+
878
+  #define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
879
+  #define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
880
+  #define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
834 881
 
835
-//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
836
-//#define FILAMENT_LCD_DISPLAY
882
+  #define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
883
+
884
+  //When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
885
+  //#define FILAMENT_LCD_DISPLAY
886
+#endif
837 887
 
838 888
 #include "Configuration_adv.h"
839 889
 #include "thermistortables.h"

+ 200
- 117
Marlin/example_configurations/Felix/Configuration_DUAL.h Näytä tiedosto

@@ -61,6 +61,7 @@ Here are some standard links for getting your machine calibrated:
61 61
 #define SERIAL_PORT 0
62 62
 
63 63
 // This determines the communication speed of the printer
64
+// :[2400,9600,19200,38400,57600,115200,250000]
64 65
 #define BAUDRATE 250000
65 66
 
66 67
 // Enable the Bluetooth serial interface on AT90USB devices
@@ -81,17 +82,27 @@ Here are some standard links for getting your machine calibrated:
81 82
 //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
82 83
 
83 84
 // This defines the number of extruders
85
+// :[1,2,3,4]
84 86
 #define EXTRUDERS 2
85 87
 
88
+// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
89
+// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder).
90
+// For the other hotends it is their distance from the extruder 0 hotend.
91
+//#define EXTRUDER_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
92
+//#define EXTRUDER_OFFSET_Y {0.0, 5.00}  // (in mm) for each extruder, offset of the hotend on the Y axis
93
+
86 94
 //// The following define selects which power supply you have. Please choose the one that matches your setup
87 95
 // 1 = ATX
88 96
 // 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
97
+// :{1:'ATX',2:'X-Box 360'}
89 98
 
90 99
 #define POWER_SUPPLY 1
91 100
 
92 101
 // Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
93 102
 #define PS_DEFAULT_OFF
94 103
 
104
+// @section temperature
105
+
95 106
 //===========================================================================
96 107
 //============================= Thermal Settings ============================
97 108
 //===========================================================================
@@ -99,6 +110,7 @@ Here are some standard links for getting your machine calibrated:
99 110
 //--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
100 111
 //
101 112
 //// Temperature sensor settings:
113
+// -3 is thermocouple with MAX31855 (only for sensor 0)
102 114
 // -2 is thermocouple with MAX6675 (only for sensor 0)
103 115
 // -1 is thermocouple with AD595
104 116
 // 0 is not used
@@ -118,6 +130,7 @@ Here are some standard links for getting your machine calibrated:
118 130
 // 13 is 100k Hisens 3950  1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
119 131
 // 20 is the PT100 circuit found in the Ultimainboard V2.x
120 132
 // 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
133
+// 70 is the 100K thermistor found in the bq Hephestos 2
121 134
 //
122 135
 //    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
123 136
 //                          (but gives greater accuracy and more stable PID)
@@ -133,7 +146,7 @@ Here are some standard links for getting your machine calibrated:
133 146
 //     Use it for Testing or Development purposes. NEVER for production machine.
134 147
 //#define DUMMY_THERMISTOR_998_VALUE 25
135 148
 //#define DUMMY_THERMISTOR_999_VALUE 100
136
-// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
149
+// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-3': "Thermocouple + MAX31855 (only for sensor 0)", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
137 150
 #define TEMP_SENSOR_0 1
138 151
 #define TEMP_SENSOR_1 1
139 152
 #define TEMP_SENSOR_2 0
@@ -167,14 +180,9 @@ Here are some standard links for getting your machine calibrated:
167 180
 #define HEATER_3_MAXTEMP 275
168 181
 #define BED_MAXTEMP 150
169 182
 
170
-// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
171
-// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
172
-// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
173
-//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
174
-
175 183
 // If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
176
-//#define EXTRUDER_WATTS (12.0*12.0/6.7) //  P=I^2/R
177
-//#define BED_WATTS (12.0*12.0/1.1)      // P=I^2/R
184
+//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
185
+//#define BED_WATTS (12.0*12.0/1.1)      // P=U^2/R
178 186
 
179 187
 //===========================================================================
180 188
 //============================= PID Settings ================================
@@ -228,14 +236,15 @@ Here are some standard links for getting your machine calibrated:
228 236
 //#define PID_BED_DEBUG // Sends debug data to the serial port.
229 237
 
230 238
 #if ENABLED(PIDTEMPBED)
231
-// Felix Foil Heater
232
-   #define DEFAULT_bedKp 103.37
233
-   #define DEFAULT_bedKi 2.79
234
-   #define DEFAULT_bedKd 956.94
239
+  // Felix Foil Heater
240
+  #define DEFAULT_bedKp 103.37
241
+  #define DEFAULT_bedKi 2.79
242
+  #define DEFAULT_bedKd 956.94
235 243
 
236
-// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
244
+  // FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
237 245
 #endif // PIDTEMPBED
238 246
 
247
+// @section extruder
239 248
 
240 249
 //this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
241 250
 //can be software-disabled for whatever purposes by
@@ -251,16 +260,15 @@ Here are some standard links for getting your machine calibrated:
251 260
 //===========================================================================
252 261
 
253 262
 /**
254
- * Thermal Runaway Protection protects your printer from damage and fire if a
263
+ * Thermal Protection protects your printer from damage and fire if a
255 264
  * thermistor falls out or temperature sensors fail in any way.
256 265
  *
257 266
  * The issue: If a thermistor falls out or a temperature sensor fails,
258 267
  * Marlin can no longer sense the actual temperature. Since a disconnected
259 268
  * thermistor reads as a low temperature, the firmware will keep the heater on.
260 269
  *
261
- * The solution: Once the temperature reaches the target, start observing.
262
- * If the temperature stays too far below the target (hysteresis) for too long,
263
- * the firmware will halt as a safety precaution.
270
+ * If you get "Thermal Runaway" or "Heating failed" errors the
271
+ * details can be tuned in Configuration_adv.h
264 272
  */
265 273
 
266 274
 #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
@@ -308,37 +316,96 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
308 316
 #define DISABLE_MAX_ENDSTOPS
309 317
 //#define DISABLE_MIN_ENDSTOPS
310 318
 
311
-// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
312
-// This only affects a Z probe endstop if you have separate Z min endstop as well and have
313
-// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
314
-// this has no effect.
319
+//===========================================================================
320
+//============================= Z Probe Options =============================
321
+//===========================================================================
322
+
323
+// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
324
+// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
325
+//
326
+// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
327
+//
328
+// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
329
+// Example: To park the head outside the bed area when homing with G28.
330
+//
331
+// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
332
+//
333
+// For a servo-based Z probe, you must set up servo support below, including
334
+// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
335
+//
336
+// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
337
+// - Use 5V for powered (usu. inductive) sensors.
338
+// - Otherwise connect:
339
+//   - normally-closed switches to GND and D32.
340
+//   - normally-open switches to 5V and D32.
341
+//
342
+// Normally-closed switches are advised and are the default.
343
+//
344
+// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
345
+// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
346
+// default pin for all RAMPS-based boards. Some other boards map differently.
347
+// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
348
+//
349
+// WARNING:
350
+// Setting the wrong pin may have unexpected and potentially disastrous consequences.
351
+// Use with caution and do your homework.
352
+//
353
+//#define Z_MIN_PROBE_ENDSTOP
354
+
355
+// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
356
+// The Z_MIN_PIN will then be used for both Z-homing and probing.
357
+#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
358
+
359
+// To use a probe you must enable one of the two options above!
360
+
361
+// This option disables the use of the Z_MIN_PROBE_PIN
362
+// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
363
+// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
364
+// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
315 365
 //#define DISABLE_Z_MIN_PROBE_ENDSTOP
316 366
 
317 367
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
368
+// :{0:'Low',1:'High'}
318 369
 #define X_ENABLE_ON 0
319 370
 #define Y_ENABLE_ON 0
320 371
 #define Z_ENABLE_ON 0
321 372
 #define E_ENABLE_ON 0 // For all extruders
322 373
 
323
-// Disables axis when it's not being used.
374
+// Disables axis stepper immediately when it's not being used.
324 375
 // WARNING: When motors turn off there is a chance of losing position accuracy!
325 376
 #define DISABLE_X false
326 377
 #define DISABLE_Y false
327 378
 #define DISABLE_Z false
379
+// Warn on display about possibly reduced accuracy
380
+//#define DISABLE_REDUCED_ACCURACY_WARNING
381
+
382
+// @section extruder
383
+
328 384
 #define DISABLE_E false // For all extruders
329 385
 #define DISABLE_INACTIVE_EXTRUDER true //disable only inactive extruders and keep active extruder enabled
330 386
 
387
+// @section machine
388
+
331 389
 // Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way.
332 390
 #define INVERT_X_DIR true
333 391
 #define INVERT_Y_DIR true
334 392
 #define INVERT_Z_DIR true
393
+
394
+// @section extruder
395
+
396
+// For direct drive extruder v9 set to true, for geared extruder set to false.
335 397
 #define INVERT_E0_DIR false
336 398
 #define INVERT_E1_DIR true
337 399
 #define INVERT_E2_DIR false
338 400
 #define INVERT_E3_DIR false
339 401
 
402
+// @section homing
403
+//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
404
+                                    // Be sure you have this distance over your Z_MAX_POS in case.
405
+
340 406
 // ENDSTOP SETTINGS:
341 407
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
408
+// :[-1,1]
342 409
 #define X_HOME_DIR -1
343 410
 #define Y_HOME_DIR -1
344 411
 #define Z_HOME_DIR -1
@@ -346,6 +413,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
346 413
 #define min_software_endstops true // If true, axis won't move to coordinates less than HOME_POS.
347 414
 #define max_software_endstops true  // If true, axis won't move to coordinates greater than the defined lengths below.
348 415
 
416
+// @section machine
417
+
349 418
 // Travel limits after homing (units are in mm)
350 419
 #define X_MIN_POS 0
351 420
 #define Y_MIN_POS 0
@@ -368,24 +437,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
368 437
 #endif
369 438
 
370 439
 //===========================================================================
371
-//=========================== Manual Bed Leveling ===========================
440
+//============================ Mesh Bed Leveling ============================
372 441
 //===========================================================================
373 442
 
374
-//#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
375 443
 //#define MESH_BED_LEVELING    // Enable mesh bed leveling.
376 444
 
377
-#if ENABLED(MANUAL_BED_LEVELING)
378
-  #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
379
-#endif  // MANUAL_BED_LEVELING
380
-
381 445
 #if ENABLED(MESH_BED_LEVELING)
382 446
   #define MESH_MIN_X 10
383
-  #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
447
+  #define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
384 448
   #define MESH_MIN_Y 10
385
-  #define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
449
+  #define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
386 450
   #define MESH_NUM_X_POINTS 3  // Don't use more than 7 points per axis, implementation limited.
387 451
   #define MESH_NUM_Y_POINTS 3
388 452
   #define MESH_HOME_SEARCH_Z 4  // Z after Home, bed somewhere below but above 0.0.
453
+
454
+  //#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
455
+
456
+  #if ENABLED(MANUAL_BED_LEVELING)
457
+    #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
458
+  #endif  // MANUAL_BED_LEVELING
459
+
389 460
 #endif  // MESH_BED_LEVELING
390 461
 
391 462
 //===========================================================================
@@ -394,10 +465,9 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
394 465
 
395 466
 // @section bedlevel
396 467
 
397
-
398 468
 //#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
399 469
 //#define DEBUG_LEVELING_FEATURE
400
-//#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
470
+//#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
401 471
 
402 472
 #if ENABLED(AUTO_BED_LEVELING_FEATURE)
403 473
 
@@ -409,7 +479,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
409 479
   //   This mode is preferred because there are more measurements.
410 480
   //
411 481
   // - "3-point" mode
412
-  //   Probe 3 arbitrary points on the bed (that aren't colinear)
482
+  //   Probe 3 arbitrary points on the bed (that aren't collinear)
413 483
   //   You specify the XY coordinates of all 3 points.
414 484
 
415 485
   // Enable this to sample the bed in a grid (least squares solution).
@@ -423,7 +493,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
423 493
     #define FRONT_PROBE_BED_POSITION 20
424 494
     #define BACK_PROBE_BED_POSITION 180
425 495
 
426
-    #define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
496
+    #define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
427 497
 
428 498
     // Set the number of grid points per dimension.
429 499
     // You probably don't need more than 3 (squared=9).
@@ -431,25 +501,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
431 501
 
432 502
   #else  // !AUTO_BED_LEVELING_GRID
433 503
 
434
-      // Arbitrary points to probe.
435
-      // A simple cross-product is used to estimate the plane of the bed.
436
-      #define ABL_PROBE_PT_1_X 15
437
-      #define ABL_PROBE_PT_1_Y 180
438
-      #define ABL_PROBE_PT_2_X 15
439
-      #define ABL_PROBE_PT_2_Y 20
440
-      #define ABL_PROBE_PT_3_X 170
441
-      #define ABL_PROBE_PT_3_Y 20
504
+    // Arbitrary points to probe.
505
+    // A simple cross-product is used to estimate the plane of the bed.
506
+    #define ABL_PROBE_PT_1_X 15
507
+    #define ABL_PROBE_PT_1_Y 180
508
+    #define ABL_PROBE_PT_2_X 15
509
+    #define ABL_PROBE_PT_2_Y 20
510
+    #define ABL_PROBE_PT_3_X 170
511
+    #define ABL_PROBE_PT_3_Y 20
442 512
 
443 513
   #endif // AUTO_BED_LEVELING_GRID
444 514
 
445
-  // Offsets to the Z probe relative to the nozzle tip.
515
+  // Z Probe to nozzle (X,Y) offset, relative to (0, 0).
446 516
   // X and Y offsets must be integers.
447
-  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // Z probe to nozzle X offset: -left  +right
448
-  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Z probe to nozzle Y offset: -front +behind
449
-  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z probe to nozzle Z offset: -below (always!)
450
-
451
-  #define Z_RAISE_BEFORE_HOMING 4       // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
452
-                                        // Be sure you have this distance over your Z_MAX_POS in case.
517
+  //
518
+  // In the following example the X and Y offsets are both positive:
519
+  // #define X_PROBE_OFFSET_FROM_EXTRUDER 10
520
+  // #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
521
+  //
522
+  //    +-- BACK ---+
523
+  //    |           |
524
+  //  L |    (+) P  | R <-- probe (20,20)
525
+  //  E |           | I
526
+  //  F | (-) N (+) | G <-- nozzle (10,10)
527
+  //  T |           | H
528
+  //    |    (-)    | T
529
+  //    |           |
530
+  //    O-- FRONT --+
531
+  //  (0,0)
532
+  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // X offset: -left  [of the nozzle] +right
533
+  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Y offset: -front [of the nozzle] +behind
534
+  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z offset: -below [the nozzle] (always negative!)
453 535
 
454 536
   #define XY_TRAVEL_SPEED 8000         // X and Y axis travel speed between probes, in mm/min.
455 537
 
@@ -457,16 +539,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
457 539
   #define Z_RAISE_BETWEEN_PROBINGS 5  // How much the Z axis will be raised when traveling from between next probing points.
458 540
   #define Z_RAISE_AFTER_PROBING 15    // How much the Z axis will be raised after the last probing point.
459 541
 
460
-//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
461
-                                                                            // Useful to retract a deployable Z probe.
542
+  //#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
543
+                                                                             // Useful to retract a deployable Z probe.
462 544
 
463
-  //#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
545
+  // Probes are sensors/switches that need to be activated before they can be used
546
+  // and deactivated after the use.
547
+  // Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
548
+
549
+  // A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
550
+  // when the hardware endstops are active.
551
+  //#define FIX_MOUNTED_PROBE
552
+
553
+  // A Servo Probe can be defined in the servo section below.
554
+
555
+  // An Allen Key Probe is currently predefined only in the delta example configurations.
556
+
557
+  //#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
464 558
   //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
465 559
 
466
-// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
467
-// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
560
+  // If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
561
+  // it is highly recommended you leave Z_SAFE_HOMING enabled!
468 562
 
469
-  #define Z_SAFE_HOMING   // This feature is meant to avoid Z homing with Z probe outside the bed area.
563
+  #define Z_SAFE_HOMING   // Use the z-min-probe for homing to z-min - not the z-min-endstop.
564
+                          // This feature is meant to avoid Z homing with Z probe outside the bed area.
470 565
                           // When defined, it will:
471 566
                           // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
472 567
                           // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
@@ -480,40 +575,11 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
480 575
 
481 576
   #endif
482 577
 
483
-  // Support for a dedicated Z probe endstop separate from the Z min endstop.
484
-  // If you would like to use both a Z probe and a Z min endstop together,
485
-  // uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
486
-  // If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
487
-  // Example: To park the head outside the bed area when homing with G28.
488
-  //
489
-  // WARNING:
490
-  // The Z min endstop will need to set properly as it would without a Z probe
491
-  // to prevent head crashes and premature stopping during a print.
492
-  //
493
-  // To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
494
-  // defined in the pins_XXXXX.h file for your control board.
495
-  // If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
496
-  // Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
497
-  // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
498
-  // in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
499
-  // otherwise connect to ground and D32 for normally closed configuration
500
-  // and 5V and D32 for normally open configurations.
501
-  // Normally closed configuration is advised and assumed.
502
-  // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
503
-  // Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
504
-  // Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
505
-  // D32 is currently selected in the RAMPS 1.3/1.4 pin file.
506
-  // All other boards will need changes to the respective pins_XXXXX.h file.
507
-  //
508
-  // WARNING:
509
-  // Setting the wrong pin may have unexpected and potentially disastrous outcomes.
510
-  // Use with caution and do your homework.
511
-  //
512
-  //#define Z_MIN_PROBE_ENDSTOP
513
-
514 578
 #endif // AUTO_BED_LEVELING_FEATURE
515 579
 
516 580
 
581
+// @section homing
582
+
517 583
 // The position of the homing switches
518 584
 //#define MANUAL_HOME_POSITIONS  // If defined, MANUAL_*_HOME_POS below will be used
519 585
 //#define BED_CENTER_AT_0_0  // If defined, the center of the bed is at (X=0, Y=0)
@@ -527,6 +593,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
527 593
   //#define MANUAL_Z_HOME_POS 402 // For delta: Distance between nozzle and print surface after homing.
528 594
 #endif
529 595
 
596
+// @section movement
597
+
530 598
 /**
531 599
  * MOVEMENT SETTINGS
532 600
  */
@@ -538,18 +606,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
538 606
 // default steps per unit for Felix 2.0/3.0: 0.00249mm x/y rounding error with 3mm pitch HTD belt and 14 tooth pulleys. 0 z error.
539 607
 #define DEFAULT_AXIS_STEPS_PER_UNIT   {76.190476, 76.190476, 1600, 164}
540 608
 #define DEFAULT_MAX_FEEDRATE          {500, 500, 5, 25}    // (mm/sec)
541
-#define DEFAULT_MAX_ACCELERATION      {5000,5000,100,80000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot.
609
+#define DEFAULT_MAX_ACCELERATION      {5000,5000,100,80000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
542 610
 
543 611
 #define DEFAULT_ACCELERATION          1750 //1500    // X, Y, Z and E max acceleration in mm/s^2 for printing moves
544
-#define DEFAULT_RETRACT_ACCELERATION  5000 // X, Y, Z and E max acceleration in mm/s^2 for r retracts
612
+#define DEFAULT_RETRACT_ACCELERATION  5000 // E acceleration in mm/s^2 for retracts
545 613
 #define DEFAULT_TRAVEL_ACCELERATION   3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
546 614
 
547
-// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
548
-// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder).
549
-// For the other hotends it is their distance from the extruder 0 hotend.
550
-//#define EXTRUDER_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
551
-//#define EXTRUDER_OFFSET_Y {0.0, 5.00}  // (in mm) for each extruder, offset of the hotend on the Y axis
552
-
553 615
 // The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
554 616
 #define DEFAULT_XYJERK                10   // (mm/sec)
555 617
 #define DEFAULT_ZJERK                 0.3  //0.4   // (mm/sec)
@@ -560,6 +622,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
560 622
 //============================= Additional Features ===========================
561 623
 //=============================================================================
562 624
 
625
+// @section more
626
+
563 627
 // Custom M code points
564 628
 #define CUSTOM_M_CODES
565 629
 #if ENABLED(CUSTOM_M_CODES)
@@ -570,6 +634,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
570 634
   #endif
571 635
 #endif
572 636
 
637
+// @section extras
573 638
 
574 639
 // EEPROM
575 640
 // The microcontroller can store settings in the EEPROM, e.g. max velocity...
@@ -581,10 +646,18 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
581 646
 
582 647
 #if ENABLED(EEPROM_SETTINGS)
583 648
   // To disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
584
-  #define EEPROM_CHITCHAT // please keep turned on if you can.
649
+  #define EEPROM_CHITCHAT // Please keep turned on if you can.
585 650
 #endif
586 651
 
587 652
 //
653
+// Host Keepalive
654
+//
655
+// By default Marlin will send a busy status message to the host
656
+// every 2 seconds when it can't accept commands.
657
+//
658
+//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
659
+
660
+//
588 661
 // M100 Free Memory Watcher
589 662
 //
590 663
 //#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
@@ -601,15 +674,16 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
601 674
 #define ABS_PREHEAT_FAN_SPEED 255   // Insert Value between 0 and 255
602 675
 
603 676
 //==============================LCD and SD support=============================
677
+// @section lcd
604 678
 
605 679
 // Define your display language below. Replace (en) with your language code and uncomment.
606
-// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
680
+// en, pl, fr, de, es, ru, bg, it, pt, pt_utf8, pt-br, pt-br_utf8, fi, an, nl, ca, eu, kana, kana_utf8, cn, cz, test
607 681
 // See also language.h
608 682
 //#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
609 683
 
610 684
 // Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
611 685
 // To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
612
-// See also documentation/LCDLanguageFont.md
686
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
613 687
   #define DISPLAY_CHARSET_HD44780_JAPAN        // this is the most common hardware
614 688
   //#define DISPLAY_CHARSET_HD44780_WESTERN
615 689
   //#define DISPLAY_CHARSET_HD44780_CYRILLIC
@@ -617,19 +691,18 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
617 691
 //#define ULTRA_LCD  //general LCD support, also 16x2
618 692
 //#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
619 693
 //#define SDSUPPORT // Enable SD Card Support in Hardware Console
620
-// Changed behaviour! If you need SDSUPPORT uncomment it!
621
-//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
622
-//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
694
+                    // Changed behaviour! If you need SDSUPPORT uncomment it!
695
+//#define SPI_SPEED SPI_HALF_SPEED // (also SPI_QUARTER_SPEED, SPI_EIGHTH_SPEED) Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
623 696
 //#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
624 697
 //#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
625 698
 //#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
699
+//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
626 700
 //#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
627 701
 //#define ULTIPANEL  //the UltiPanel as on Thingiverse
628 702
 //#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
629 703
 //#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
630 704
 //#define LCD_FEEDBACK_FREQUENCY_HZ 1000         // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
631 705
                                                  // 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
632
-
633 706
 // PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
634 707
 // http://reprap.org/wiki/PanelOne
635 708
 //#define PANEL_ONE
@@ -640,13 +713,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
640 713
 
641 714
 // The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
642 715
 // http://panucatt.com
643
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
716
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
644 717
 //#define VIKI2
645 718
 //#define miniVIKI
646 719
 
647 720
 // This is a new controller currently under development.  https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
648 721
 //
649
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
722
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
650 723
 //#define ELB_FULL_GRAPHIC_CONTROLLER
651 724
 //#define SD_DETECT_INVERTED
652 725
 
@@ -661,7 +734,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
661 734
 // The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
662 735
 // http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
663 736
 //
664
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
737
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
665 738
 //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
666 739
 
667 740
 // The RepRapWorld REPRAPWORLD_KEYPAD v1.1
@@ -684,6 +757,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
684 757
 
685 758
 //#define LCD_I2C_SAINSMART_YWROBOT
686 759
 
760
+//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
761
+
687 762
 // PANELOLU2 LCD with status LEDs, separate encoder and click inputs
688 763
 //
689 764
 // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
@@ -696,14 +771,20 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
696 771
 // Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs
697 772
 //#define LCD_I2C_VIKI
698 773
 
774
+// SSD1306 OLED generic display support
775
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
776
+//#define U8GLIB_SSD1306
777
+
699 778
 // Shift register panels
700 779
 // ---------------------
701 780
 // 2 wire Non-latching LCD SR from:
702 781
 // https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
703
-
782
+// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
704 783
 //#define SAV_3DLCD
705 784
 
706
-// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
785
+// @section extras
786
+
787
+// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
707 788
 #define FAST_PWM_FAN
708 789
 
709 790
 // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
@@ -726,7 +807,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
726 807
 // Data from: http://www.doc-diy.net/photo/rc-1_hacked/
727 808
 //#define PHOTOGRAPH_PIN     23
728 809
 
729
-// SF send wrong arc g-codes when using Arc Point as fillet procedure
810
+// SkeinForge sends the wrong arc g-codes when using Arc Point as fillet procedure
730 811
 //#define SF_ARC_FIX
731 812
 
732 813
 // Support for the BariCUDA Paste Extruder.
@@ -785,19 +866,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
785 866
 // Uncomment below to enable
786 867
 //#define FILAMENT_SENSOR
787 868
 
788
-#define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
789
-#define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
790
-
791 869
 #define DEFAULT_NOMINAL_FILAMENT_DIA 3.00  //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
792
-#define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
793
-#define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
794
-#define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
795 870
 
796
-//defines used in the code
797
-#define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
871
+#if ENABLED(FILAMENT_SENSOR)
872
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
873
+  #define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
874
+
875
+  #define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
876
+  #define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
877
+  #define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
798 878
 
799
-//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
800
-//#define FILAMENT_LCD_DISPLAY
879
+  #define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
880
+
881
+  //When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
882
+  //#define FILAMENT_LCD_DISPLAY
883
+#endif
801 884
 
802 885
 #include "Configuration_adv.h"
803 886
 #include "thermistortables.h"

+ 83
- 58
Marlin/example_configurations/Felix/Configuration_adv.h Näytä tiedosto

@@ -17,6 +17,20 @@
17 17
 /**
18 18
  * Thermal Protection parameters
19 19
  */
20
+  /**
21
+   * Thermal Protection protects your printer from damage and fire if a
22
+   * thermistor falls out or temperature sensors fail in any way.
23
+   *
24
+   * The issue: If a thermistor falls out or a temperature sensor fails,
25
+   * Marlin can no longer sense the actual temperature. Since a disconnected
26
+   * thermistor reads as a low temperature, the firmware will keep the heater on.
27
+   *
28
+   * The solution: Once the temperature reaches the target, start observing.
29
+   * If the temperature stays too far below the target (hysteresis) for too long (period),
30
+   * the firmware will halt the machine as a safety precaution.
31
+   *
32
+   * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
33
+   */
20 34
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
21 35
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
22 36
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
@@ -26,26 +40,24 @@
26 40
    * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
27 41
    * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
28 42
    * but only if the current temperature is far enough below the target for a reliable test.
43
+   *
44
+   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
45
+   * WATCH_TEMP_INCREASE should not be below 2.
29 46
    */
30 47
   #define WATCH_TEMP_PERIOD 16                // Seconds
31 48
   #define WATCH_TEMP_INCREASE 4               // Degrees Celsius
32 49
 #endif
33 50
 
51
+  /**
52
+   * Thermal Protection parameters for the bed
53
+   * are like the above for the hotends.
54
+   * WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
55
+   */
34 56
 #if ENABLED(THERMAL_PROTECTION_BED)
35 57
   #define THERMAL_PROTECTION_BED_PERIOD 20    // Seconds
36 58
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
37 59
 #endif
38 60
 
39
-/**
40
- * Automatic Temperature:
41
- * The hotend target temperature is calculated by all the buffered lines of gcode.
42
- * The maximum buffered steps/sec of the extruder motor is called "se".
43
- * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
44
- * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
45
- * mintemp and maxtemp. Turn this off by excuting M109 without F*
46
- * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
47
- * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
48
- */
49 61
 #if ENABLED(PIDTEMP)
50 62
   // this adds an experimental additional term to the heating power, proportional to the extrusion speed.
51 63
   // if Kc is chosen well, the additional required power due to increased melting should be compensated.
@@ -56,14 +68,16 @@
56 68
   #endif
57 69
 #endif
58 70
 
59
-
60
-//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
61
-//The maximum buffered steps/sec of the extruder motor are called "se".
62
-//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
63
-// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
64
-// you exit the value by any M109 without F*
65
-// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
66
-// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
71
+/**
72
+ * Automatic Temperature:
73
+ * The hotend target temperature is calculated by all the buffered lines of gcode.
74
+ * The maximum buffered steps/sec of the extruder motor is called "se".
75
+ * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
76
+ * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
77
+ * mintemp and maxtemp. Turn this off by executing M109 without F*
78
+ * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
79
+ * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
80
+ */
67 81
 #define AUTOTEMP
68 82
 #if ENABLED(AUTOTEMP)
69 83
   #define AUTOTEMP_OLDWEIGHT 0.98
@@ -240,7 +254,13 @@
240 254
 #define INVERT_E_STEP_PIN false
241 255
 
242 256
 // Default stepper release if idle. Set to 0 to deactivate.
257
+// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
258
+// Time can be set by M18 and M84.
243 259
 #define DEFAULT_STEPPER_DEACTIVE_TIME 60
260
+#define DISABLE_INACTIVE_X true
261
+#define DISABLE_INACTIVE_Y true
262
+#define DISABLE_INACTIVE_Z true  // set to false if the nozzle will fall down on your printed part when print has finished.
263
+#define DISABLE_INACTIVE_E true
244 264
 
245 265
 #define DEFAULT_MINIMUMFEEDRATE       0.0     // minimum feedrate
246 266
 #define DEFAULT_MINTRAVELFEEDRATE     0.0
@@ -276,6 +296,9 @@
276 296
 // Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
277 297
 #define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
278 298
 
299
+// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
300
+//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
301
+
279 302
 // uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
280 303
 //#define DIGIPOT_I2C
281 304
 // Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
@@ -349,17 +372,16 @@
349 372
   //#define USE_SMALL_INFOFONT
350 373
 #endif // DOGLCD
351 374
 
352
-
353 375
 // @section more
354 376
 
355 377
 // The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
356
-//#define USE_WATCHDOG
378
+#define USE_WATCHDOG
357 379
 
358 380
 #if ENABLED(USE_WATCHDOG)
359
-// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
360
-// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
361
-//  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
362
-//#define WATCHDOG_RESET_MANUAL
381
+  // If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
382
+  // The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
383
+  //  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
384
+  //#define WATCHDOG_RESET_MANUAL
363 385
 #endif
364 386
 
365 387
 // @section lcd
@@ -370,6 +392,7 @@
370 392
 //#define BABYSTEPPING
371 393
 #if ENABLED(BABYSTEPPING)
372 394
   #define BABYSTEP_XY  //not only z, but also XY in the menu. more clutter, more functions
395
+                       //not implemented for deltabots!
373 396
   #define BABYSTEP_INVERT_Z false  //true for inverse movements in Z
374 397
   #define BABYSTEP_MULTIPLICATOR 1 //faster movements
375 398
 #endif
@@ -388,7 +411,6 @@
388 411
 #if ENABLED(ADVANCE)
389 412
   #define EXTRUDER_ADVANCE_K .0
390 413
   #define D_FILAMENT 2.85
391
-  #define STEPS_MM_E 836
392 414
 #endif
393 415
 
394 416
 // @section extras
@@ -397,7 +419,7 @@
397 419
 #define MM_PER_ARC_SEGMENT 1
398 420
 #define N_ARC_CORRECTION 25
399 421
 
400
-const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
422
+const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
401 423
 
402 424
 // @section temperature
403 425
 
@@ -462,12 +484,15 @@ const unsigned int dropsegments=5; //everything with less than this number of st
462 484
     #define FILAMENTCHANGE_ZADD 10
463 485
     #define FILAMENTCHANGE_FIRSTRETRACT -2
464 486
     #define FILAMENTCHANGE_FINALRETRACT -100
487
+    #define AUTO_FILAMENT_CHANGE                //This extrude filament until you press the button on LCD
488
+    #define AUTO_FILAMENT_CHANGE_LENGTH 0.04    //Extrusion length on automatic extrusion loop
489
+    #define AUTO_FILAMENT_CHANGE_FEEDRATE 300   //Extrusion feedrate (mm/min) on automatic extrusion loop
465 490
   #endif
466 491
 #endif
467 492
 
468 493
 /******************************************************************************\
469 494
  * enable this section if you have TMC26X motor drivers.
470
- * you need to import the TMC26XStepper library into the arduino IDE for this
495
+ * you need to import the TMC26XStepper library into the Arduino IDE for this
471 496
  ******************************************************************************/
472 497
 
473 498
 // @section tmc
@@ -475,52 +500,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
475 500
 //#define HAVE_TMCDRIVER
476 501
 #if ENABLED(HAVE_TMCDRIVER)
477 502
 
478
-//#define X_IS_TMC
503
+  //#define X_IS_TMC
479 504
   #define X_MAX_CURRENT 1000  //in mA
480 505
   #define X_SENSE_RESISTOR 91 //in mOhms
481 506
   #define X_MICROSTEPS 16     //number of microsteps
482 507
 
483
-//#define X2_IS_TMC
508
+  //#define X2_IS_TMC
484 509
   #define X2_MAX_CURRENT 1000  //in mA
485 510
   #define X2_SENSE_RESISTOR 91 //in mOhms
486 511
   #define X2_MICROSTEPS 16     //number of microsteps
487 512
 
488
-//#define Y_IS_TMC
513
+  //#define Y_IS_TMC
489 514
   #define Y_MAX_CURRENT 1000  //in mA
490 515
   #define Y_SENSE_RESISTOR 91 //in mOhms
491 516
   #define Y_MICROSTEPS 16     //number of microsteps
492 517
 
493
-//#define Y2_IS_TMC
518
+  //#define Y2_IS_TMC
494 519
   #define Y2_MAX_CURRENT 1000  //in mA
495 520
   #define Y2_SENSE_RESISTOR 91 //in mOhms
496 521
   #define Y2_MICROSTEPS 16     //number of microsteps
497 522
 
498
-//#define Z_IS_TMC
523
+  //#define Z_IS_TMC
499 524
   #define Z_MAX_CURRENT 1000  //in mA
500 525
   #define Z_SENSE_RESISTOR 91 //in mOhms
501 526
   #define Z_MICROSTEPS 16     //number of microsteps
502 527
 
503
-//#define Z2_IS_TMC
528
+  //#define Z2_IS_TMC
504 529
   #define Z2_MAX_CURRENT 1000  //in mA
505 530
   #define Z2_SENSE_RESISTOR 91 //in mOhms
506 531
   #define Z2_MICROSTEPS 16     //number of microsteps
507 532
 
508
-//#define E0_IS_TMC
533
+  //#define E0_IS_TMC
509 534
   #define E0_MAX_CURRENT 1000  //in mA
510 535
   #define E0_SENSE_RESISTOR 91 //in mOhms
511 536
   #define E0_MICROSTEPS 16     //number of microsteps
512 537
 
513
-//#define E1_IS_TMC
538
+  //#define E1_IS_TMC
514 539
   #define E1_MAX_CURRENT 1000  //in mA
515 540
   #define E1_SENSE_RESISTOR 91 //in mOhms
516 541
   #define E1_MICROSTEPS 16     //number of microsteps
517 542
 
518
-//#define E2_IS_TMC
543
+  //#define E2_IS_TMC
519 544
   #define E2_MAX_CURRENT 1000  //in mA
520 545
   #define E2_SENSE_RESISTOR 91 //in mOhms
521 546
   #define E2_MICROSTEPS 16     //number of microsteps
522 547
 
523
-//#define E3_IS_TMC
548
+  //#define E3_IS_TMC
524 549
   #define E3_MAX_CURRENT 1000  //in mA
525 550
   #define E3_SENSE_RESISTOR 91 //in mOhms
526 551
   #define E3_MICROSTEPS 16     //number of microsteps
@@ -529,7 +554,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
529 554
 
530 555
 /******************************************************************************\
531 556
  * enable this section if you have L6470  motor drivers.
532
- * you need to import the L6470 library into the arduino IDE for this
557
+ * you need to import the L6470 library into the Arduino IDE for this
533 558
  ******************************************************************************/
534 559
 
535 560
 // @section l6470
@@ -537,63 +562,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
537 562
 //#define HAVE_L6470DRIVER
538 563
 #if ENABLED(HAVE_L6470DRIVER)
539 564
 
540
-//#define X_IS_L6470
565
+  //#define X_IS_L6470
541 566
   #define X_MICROSTEPS 16     //number of microsteps
542
-  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
567
+  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
543 568
   #define X_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
544 569
   #define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
545 570
 
546
-//#define X2_IS_L6470
571
+  //#define X2_IS_L6470
547 572
   #define X2_MICROSTEPS 16     //number of microsteps
548
-  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
573
+  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
549 574
   #define X2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
550 575
   #define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
551 576
 
552
-//#define Y_IS_L6470
577
+  //#define Y_IS_L6470
553 578
   #define Y_MICROSTEPS 16     //number of microsteps
554
-  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
579
+  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
555 580
   #define Y_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
556 581
   #define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
557 582
 
558
-//#define Y2_IS_L6470
583
+  //#define Y2_IS_L6470
559 584
   #define Y2_MICROSTEPS 16     //number of microsteps
560
-  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
585
+  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
561 586
   #define Y2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
562 587
   #define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
563 588
 
564
-//#define Z_IS_L6470
589
+  //#define Z_IS_L6470
565 590
   #define Z_MICROSTEPS 16     //number of microsteps
566
-  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
591
+  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
567 592
   #define Z_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
568 593
   #define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
569 594
 
570
-//#define Z2_IS_L6470
595
+  //#define Z2_IS_L6470
571 596
   #define Z2_MICROSTEPS 16     //number of microsteps
572
-  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
597
+  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
573 598
   #define Z2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
574 599
   #define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
575 600
 
576
-//#define E0_IS_L6470
601
+  //#define E0_IS_L6470
577 602
   #define E0_MICROSTEPS 16     //number of microsteps
578
-  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
603
+  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
579 604
   #define E0_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
580 605
   #define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
581 606
 
582
-//#define E1_IS_L6470
607
+  //#define E1_IS_L6470
583 608
   #define E1_MICROSTEPS 16     //number of microsteps
584
-  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
609
+  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
585 610
   #define E1_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
586 611
   #define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
587 612
 
588
-//#define E2_IS_L6470
613
+  //#define E2_IS_L6470
589 614
   #define E2_MICROSTEPS 16     //number of microsteps
590
-  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
615
+  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
591 616
   #define E2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
592 617
   #define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
593 618
 
594
-//#define E3_IS_L6470
619
+  //#define E3_IS_L6470
595 620
   #define E3_MICROSTEPS 16     //number of microsteps
596
-  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
621
+  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
597 622
   #define E3_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
598 623
   #define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
599 624
 

+ 156
- 103
Marlin/example_configurations/Hephestos/Configuration.h Näytä tiedosto

@@ -70,7 +70,7 @@ Here are some standard links for getting your machine calibrated:
70 70
 // The following define selects which electronics board you have.
71 71
 // Please choose the name from boards.h that matches your setup
72 72
 #ifndef MOTHERBOARD
73
-  #define MOTHERBOARD BOARD_RAMPS_13_EFB
73
+  #define MOTHERBOARD BOARD_RAMPS_14_EFB
74 74
 #endif
75 75
 
76 76
 // Optional custom name for your RepStrap or other custom machine
@@ -113,6 +113,7 @@ Here are some standard links for getting your machine calibrated:
113 113
 //--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
114 114
 //
115 115
 //// Temperature sensor settings:
116
+// -3 is thermocouple with MAX31855 (only for sensor 0)
116 117
 // -2 is thermocouple with MAX6675 (only for sensor 0)
117 118
 // -1 is thermocouple with AD595
118 119
 // 0 is not used
@@ -132,6 +133,7 @@ Here are some standard links for getting your machine calibrated:
132 133
 // 13 is 100k Hisens 3950  1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
133 134
 // 20 is the PT100 circuit found in the Ultimainboard V2.x
134 135
 // 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
136
+// 70 is the 100K thermistor found in the bq Hephestos 2
135 137
 //
136 138
 //    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
137 139
 //                          (but gives greater accuracy and more stable PID)
@@ -147,7 +149,7 @@ Here are some standard links for getting your machine calibrated:
147 149
 //     Use it for Testing or Development purposes. NEVER for production machine.
148 150
 //#define DUMMY_THERMISTOR_998_VALUE 25
149 151
 //#define DUMMY_THERMISTOR_999_VALUE 100
150
-// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
152
+// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-3': "Thermocouple + MAX31855 (only for sensor 0)", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
151 153
 #define TEMP_SENSOR_0 1
152 154
 #define TEMP_SENSOR_1 0
153 155
 #define TEMP_SENSOR_2 0
@@ -181,14 +183,9 @@ Here are some standard links for getting your machine calibrated:
181 183
 #define HEATER_3_MAXTEMP 260
182 184
 #define BED_MAXTEMP 150
183 185
 
184
-// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
185
-// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
186
-// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
187
-//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
188
-
189 186
 // If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
190
-//#define EXTRUDER_WATTS (12.0*12.0/6.7) //  P=I^2/R
191
-//#define BED_WATTS (12.0*12.0/1.1)      // P=I^2/R
187
+//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
188
+//#define BED_WATTS (12.0*12.0/1.1)      // P=U^2/R
192 189
 
193 190
 //===========================================================================
194 191
 //============================= PID Settings ================================
@@ -245,13 +242,13 @@ Here are some standard links for getting your machine calibrated:
245 242
 
246 243
   #define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
247 244
 
248
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
245
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
249 246
   //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
250 247
   #define  DEFAULT_bedKp 10.00
251 248
   #define  DEFAULT_bedKi .023
252 249
   #define  DEFAULT_bedKd 305.4
253 250
 
254
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
251
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
255 252
   //from pidautotune
256 253
   //#define  DEFAULT_bedKp 97.1
257 254
   //#define  DEFAULT_bedKi 1.41
@@ -276,16 +273,15 @@ Here are some standard links for getting your machine calibrated:
276 273
 //===========================================================================
277 274
 
278 275
 /**
279
- * Thermal Runaway Protection protects your printer from damage and fire if a
276
+ * Thermal Protection protects your printer from damage and fire if a
280 277
  * thermistor falls out or temperature sensors fail in any way.
281 278
  *
282 279
  * The issue: If a thermistor falls out or a temperature sensor fails,
283 280
  * Marlin can no longer sense the actual temperature. Since a disconnected
284 281
  * thermistor reads as a low temperature, the firmware will keep the heater on.
285 282
  *
286
- * The solution: Once the temperature reaches the target, start observing.
287
- * If the temperature stays too far below the target (hysteresis) for too long,
288
- * the firmware will halt as a safety precaution.
283
+ * If you get "Thermal Runaway" or "Heating failed" errors the
284
+ * details can be tuned in Configuration_adv.h
289 285
  */
290 286
 
291 287
 #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
@@ -333,10 +329,52 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
333 329
 //#define DISABLE_MAX_ENDSTOPS
334 330
 //#define DISABLE_MIN_ENDSTOPS
335 331
 
336
-// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
337
-// This only affects a Z probe endstop if you have separate Z min endstop as well and have
338
-// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
339
-// this has no effect.
332
+//===========================================================================
333
+//============================= Z Probe Options =============================
334
+//===========================================================================
335
+
336
+// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
337
+// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
338
+//
339
+// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
340
+//
341
+// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
342
+// Example: To park the head outside the bed area when homing with G28.
343
+//
344
+// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
345
+//
346
+// For a servo-based Z probe, you must set up servo support below, including
347
+// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
348
+//
349
+// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
350
+// - Use 5V for powered (usu. inductive) sensors.
351
+// - Otherwise connect:
352
+//   - normally-closed switches to GND and D32.
353
+//   - normally-open switches to 5V and D32.
354
+//
355
+// Normally-closed switches are advised and are the default.
356
+//
357
+// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
358
+// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
359
+// default pin for all RAMPS-based boards. Some other boards map differently.
360
+// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
361
+//
362
+// WARNING:
363
+// Setting the wrong pin may have unexpected and potentially disastrous consequences.
364
+// Use with caution and do your homework.
365
+//
366
+//#define Z_MIN_PROBE_ENDSTOP
367
+
368
+// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
369
+// The Z_MIN_PIN will then be used for both Z-homing and probing.
370
+#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
371
+
372
+// To use a probe you must enable one of the two options above!
373
+
374
+// This option disables the use of the Z_MIN_PROBE_PIN
375
+// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
376
+// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
377
+// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
340 378
 //#define DISABLE_Z_MIN_PROBE_ENDSTOP
341 379
 
342 380
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
@@ -346,11 +384,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
346 384
 #define Z_ENABLE_ON 0
347 385
 #define E_ENABLE_ON 0 // For all extruders
348 386
 
349
-// Disables axis when it's not being used.
387
+// Disables axis stepper immediately when it's not being used.
350 388
 // WARNING: When motors turn off there is a chance of losing position accuracy!
351 389
 #define DISABLE_X false
352 390
 #define DISABLE_Y false
353 391
 #define DISABLE_Z false
392
+// Warn on display about possibly reduced accuracy
393
+//#define DISABLE_REDUCED_ACCURACY_WARNING
354 394
 
355 395
 // @section extruder
356 396
 
@@ -373,6 +413,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
373 413
 #define INVERT_E3_DIR false
374 414
 
375 415
 // @section homing
416
+//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
417
+                                    // Be sure you have this distance over your Z_MAX_POS in case.
376 418
 
377 419
 // ENDSTOP SETTINGS:
378 420
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
@@ -408,24 +450,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
408 450
 #endif
409 451
 
410 452
 //===========================================================================
411
-//=========================== Manual Bed Leveling ===========================
453
+//============================ Mesh Bed Leveling ============================
412 454
 //===========================================================================
413 455
 
414
-//#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
415 456
 //#define MESH_BED_LEVELING    // Enable mesh bed leveling.
416 457
 
417
-#if ENABLED(MANUAL_BED_LEVELING)
418
-  #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
419
-#endif  // MANUAL_BED_LEVELING
420
-
421 458
 #if ENABLED(MESH_BED_LEVELING)
422 459
   #define MESH_MIN_X 10
423
-  #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
460
+  #define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
424 461
   #define MESH_MIN_Y 10
425
-  #define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
462
+  #define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
426 463
   #define MESH_NUM_X_POINTS 3  // Don't use more than 7 points per axis, implementation limited.
427 464
   #define MESH_NUM_Y_POINTS 3
428 465
   #define MESH_HOME_SEARCH_Z 4  // Z after Home, bed somewhere below but above 0.0.
466
+
467
+  //#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
468
+
469
+  #if ENABLED(MANUAL_BED_LEVELING)
470
+    #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
471
+  #endif  // MANUAL_BED_LEVELING
472
+
429 473
 #endif  // MESH_BED_LEVELING
430 474
 
431 475
 //===========================================================================
@@ -434,10 +478,9 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
434 478
 
435 479
 // @section bedlevel
436 480
 
437
-
438 481
 //#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
439 482
 //#define DEBUG_LEVELING_FEATURE
440
-#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
483
+#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
441 484
 
442 485
 #if ENABLED(AUTO_BED_LEVELING_FEATURE)
443 486
 
@@ -449,7 +492,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
449 492
   //   This mode is preferred because there are more measurements.
450 493
   //
451 494
   // - "3-point" mode
452
-  //   Probe 3 arbitrary points on the bed (that aren't colinear)
495
+  //   Probe 3 arbitrary points on the bed (that aren't collinear)
453 496
   //   You specify the XY coordinates of all 3 points.
454 497
 
455 498
   // Enable this to sample the bed in a grid (least squares solution).
@@ -463,7 +506,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
463 506
     #define FRONT_PROBE_BED_POSITION 20
464 507
     #define BACK_PROBE_BED_POSITION 170
465 508
 
466
-    #define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
509
+    #define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
467 510
 
468 511
     // Set the number of grid points per dimension.
469 512
     // You probably don't need more than 3 (squared=9).
@@ -471,25 +514,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
471 514
 
472 515
   #else  // !AUTO_BED_LEVELING_GRID
473 516
 
474
-      // Arbitrary points to probe.
475
-      // A simple cross-product is used to estimate the plane of the bed.
476
-      #define ABL_PROBE_PT_1_X 15
477
-      #define ABL_PROBE_PT_1_Y 180
478
-      #define ABL_PROBE_PT_2_X 15
479
-      #define ABL_PROBE_PT_2_Y 20
480
-      #define ABL_PROBE_PT_3_X 170
481
-      #define ABL_PROBE_PT_3_Y 20
517
+    // Arbitrary points to probe.
518
+    // A simple cross-product is used to estimate the plane of the bed.
519
+    #define ABL_PROBE_PT_1_X 15
520
+    #define ABL_PROBE_PT_1_Y 180
521
+    #define ABL_PROBE_PT_2_X 15
522
+    #define ABL_PROBE_PT_2_Y 20
523
+    #define ABL_PROBE_PT_3_X 170
524
+    #define ABL_PROBE_PT_3_Y 20
482 525
 
483 526
   #endif // AUTO_BED_LEVELING_GRID
484 527
 
485
-  // Offsets to the Z probe relative to the nozzle tip.
528
+  // Z Probe to nozzle (X,Y) offset, relative to (0, 0).
486 529
   // X and Y offsets must be integers.
487
-  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // Z probe to nozzle X offset: -left  +right
488
-  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Z probe to nozzle Y offset: -front +behind
489
-  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z probe to nozzle Z offset: -below (always!)
490
-
491
-  #define Z_RAISE_BEFORE_HOMING 4       // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
492
-                                        // Be sure you have this distance over your Z_MAX_POS in case.
530
+  //
531
+  // In the following example the X and Y offsets are both positive:
532
+  // #define X_PROBE_OFFSET_FROM_EXTRUDER 10
533
+  // #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
534
+  //
535
+  //    +-- BACK ---+
536
+  //    |           |
537
+  //  L |    (+) P  | R <-- probe (20,20)
538
+  //  E |           | I
539
+  //  F | (-) N (+) | G <-- nozzle (10,10)
540
+  //  T |           | H
541
+  //    |    (-)    | T
542
+  //    |           |
543
+  //    O-- FRONT --+
544
+  //  (0,0)
545
+  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // X offset: -left  [of the nozzle] +right
546
+  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Y offset: -front [of the nozzle] +behind
547
+  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z offset: -below [the nozzle] (always negative!)
493 548
 
494 549
   #define XY_TRAVEL_SPEED 8000         // X and Y axis travel speed between probes, in mm/min.
495 550
 
@@ -497,16 +552,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
497 552
   #define Z_RAISE_BETWEEN_PROBINGS 5  // How much the Z axis will be raised when traveling from between next probing points.
498 553
   #define Z_RAISE_AFTER_PROBING 15    // How much the Z axis will be raised after the last probing point.
499 554
 
500
-//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
501
-                                                                            // Useful to retract a deployable Z probe.
555
+  //#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
556
+                                                                             // Useful to retract a deployable Z probe.
557
+
558
+  // Probes are sensors/switches that need to be activated before they can be used
559
+  // and deactivated after the use.
560
+  // Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
561
+
562
+  // A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
563
+  // when the hardware endstops are active.
564
+  //#define FIX_MOUNTED_PROBE
565
+
566
+  // A Servo Probe can be defined in the servo section below.
567
+
568
+  // An Allen Key Probe is currently predefined only in the delta example configurations.
502 569
 
503
-  //#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
570
+  //#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
504 571
   //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
505 572
 
506
-// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
507
-// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
573
+  // If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
574
+  // it is highly recommended you leave Z_SAFE_HOMING enabled!
508 575
 
509
-  #define Z_SAFE_HOMING   // This feature is meant to avoid Z homing with Z probe outside the bed area.
576
+  #define Z_SAFE_HOMING   // Use the z-min-probe for homing to z-min - not the z-min-endstop.
577
+                          // This feature is meant to avoid Z homing with Z probe outside the bed area.
510 578
                           // When defined, it will:
511 579
                           // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
512 580
                           // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
@@ -520,37 +588,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
520 588
 
521 589
   #endif
522 590
 
523
-  // Support for a dedicated Z probe endstop separate from the Z min endstop.
524
-  // If you would like to use both a Z probe and a Z min endstop together,
525
-  // uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
526
-  // If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
527
-  // Example: To park the head outside the bed area when homing with G28.
528
-  //
529
-  // WARNING:
530
-  // The Z min endstop will need to set properly as it would without a Z probe
531
-  // to prevent head crashes and premature stopping during a print.
532
-  //
533
-  // To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
534
-  // defined in the pins_XXXXX.h file for your control board.
535
-  // If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
536
-  // Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
537
-  // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
538
-  // in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
539
-  // otherwise connect to ground and D32 for normally closed configuration
540
-  // and 5V and D32 for normally open configurations.
541
-  // Normally closed configuration is advised and assumed.
542
-  // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
543
-  // Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
544
-  // Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
545
-  // D32 is currently selected in the RAMPS 1.3/1.4 pin file.
546
-  // All other boards will need changes to the respective pins_XXXXX.h file.
547
-  //
548
-  // WARNING:
549
-  // Setting the wrong pin may have unexpected and potentially disastrous outcomes.
550
-  // Use with caution and do your homework.
551
-  //
552
-  //#define Z_MIN_PROBE_ENDSTOP
553
-
554 591
 #endif // AUTO_BED_LEVELING_FEATURE
555 592
 
556 593
 
@@ -625,6 +662,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
625 662
 #endif
626 663
 
627 664
 //
665
+// Host Keepalive
666
+//
667
+// By default Marlin will send a busy status message to the host
668
+// every 2 seconds when it can't accept commands.
669
+//
670
+//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
671
+
672
+//
628 673
 // M100 Free Memory Watcher
629 674
 //
630 675
 //#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
@@ -644,13 +689,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
644 689
 // @section lcd
645 690
 
646 691
 // Define your display language below. Replace (en) with your language code and uncomment.
647
-// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
692
+// en, pl, fr, de, es, ru, bg, it, pt, pt_utf8, pt-br, pt-br_utf8, fi, an, nl, ca, eu, kana, kana_utf8, cn, cz, test
648 693
 // See also language.h
649 694
 //#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
650 695
 
651 696
 // Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
652 697
 // To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
653
-// See also documentation/LCDLanguageFont.md
698
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
654 699
   #define DISPLAY_CHARSET_HD44780_JAPAN        // this is the most common hardware
655 700
   //#define DISPLAY_CHARSET_HD44780_WESTERN
656 701
   //#define DISPLAY_CHARSET_HD44780_CYRILLIC
@@ -658,11 +703,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
658 703
 #define ULTRA_LCD  //general LCD support, also 16x2
659 704
 //#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
660 705
 #define SDSUPPORT // Enable SD Card Support in Hardware Console
661
-//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
662
-//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
706
+                  // Changed behaviour! If you need SDSUPPORT uncomment it!
707
+//#define SPI_SPEED SPI_HALF_SPEED // (also SPI_QUARTER_SPEED, SPI_EIGHTH_SPEED) Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
663 708
 //#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
664 709
 //#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
665 710
 //#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
711
+//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
666 712
 //#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
667 713
 //#define ULTIPANEL  //the UltiPanel as on Thingiverse
668 714
 //#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
@@ -679,13 +725,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
679 725
 
680 726
 // The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
681 727
 // http://panucatt.com
682
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
728
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
683 729
 //#define VIKI2
684 730
 //#define miniVIKI
685 731
 
686 732
 // This is a new controller currently under development.  https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
687 733
 //
688
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
734
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
689 735
 //#define ELB_FULL_GRAPHIC_CONTROLLER
690 736
 //#define SD_DETECT_INVERTED
691 737
 
@@ -700,7 +746,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
700 746
 // The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
701 747
 // http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
702 748
 //
703
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
749
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
704 750
 //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
705 751
 
706 752
 // The RepRapWorld REPRAPWORLD_KEYPAD v1.1
@@ -717,12 +763,17 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
717 763
 // http://reprap.org/wiki/Mini_panel
718 764
 //#define MINIPANEL
719 765
 
766
+// BQ SMART FULL GRAPHIC CONTROLLER
767
+//#define BQ_LCD_SMART_CONTROLLER
768
+
720 769
 /**
721 770
  * I2C Panels
722 771
  */
723 772
 
724 773
 //#define LCD_I2C_SAINSMART_YWROBOT
725 774
 
775
+//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
776
+
726 777
 // PANELOLU2 LCD with status LEDs, separate encoder and click inputs
727 778
 //
728 779
 // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
@@ -736,7 +787,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
736 787
 //#define LCD_I2C_VIKI
737 788
 
738 789
 // SSD1306 OLED generic display support
739
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
790
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
740 791
 //#define U8GLIB_SSD1306
741 792
 
742 793
 // Shift register panels
@@ -748,7 +799,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
748 799
 
749 800
 // @section extras
750 801
 
751
-// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
802
+// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
752 803
 //#define FAST_PWM_FAN
753 804
 
754 805
 // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
@@ -830,19 +881,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
830 881
 // Uncomment below to enable
831 882
 //#define FILAMENT_SENSOR
832 883
 
833
-#define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
834
-#define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
835
-
836 884
 #define DEFAULT_NOMINAL_FILAMENT_DIA 3.00  //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
837
-#define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
838
-#define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
839
-#define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
840 885
 
841
-//defines used in the code
842
-#define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
886
+#if ENABLED(FILAMENT_SENSOR)
887
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
888
+  #define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
889
+
890
+  #define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
891
+  #define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
892
+  #define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
843 893
 
844
-//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
845
-//#define FILAMENT_LCD_DISPLAY
894
+  #define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
895
+
896
+  //When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
897
+  //#define FILAMENT_LCD_DISPLAY
898
+#endif
846 899
 
847 900
 #include "Configuration_adv.h"
848 901
 #include "thermistortables.h"

+ 85
- 60
Marlin/example_configurations/Hephestos/Configuration_adv.h Näytä tiedosto

@@ -17,6 +17,20 @@
17 17
 /**
18 18
  * Thermal Protection parameters
19 19
  */
20
+  /**
21
+   * Thermal Protection protects your printer from damage and fire if a
22
+   * thermistor falls out or temperature sensors fail in any way.
23
+   *
24
+   * The issue: If a thermistor falls out or a temperature sensor fails,
25
+   * Marlin can no longer sense the actual temperature. Since a disconnected
26
+   * thermistor reads as a low temperature, the firmware will keep the heater on.
27
+   *
28
+   * The solution: Once the temperature reaches the target, start observing.
29
+   * If the temperature stays too far below the target (hysteresis) for too long (period),
30
+   * the firmware will halt the machine as a safety precaution.
31
+   *
32
+   * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
33
+   */
20 34
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
21 35
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
22 36
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
@@ -26,26 +40,24 @@
26 40
    * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
27 41
    * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
28 42
    * but only if the current temperature is far enough below the target for a reliable test.
43
+   *
44
+   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
45
+   * WATCH_TEMP_INCREASE should not be below 2.
29 46
    */
30 47
   #define WATCH_TEMP_PERIOD 16                // Seconds
31 48
   #define WATCH_TEMP_INCREASE 4               // Degrees Celsius
32 49
 #endif
33 50
 
51
+  /**
52
+   * Thermal Protection parameters for the bed
53
+   * are like the above for the hotends.
54
+   * WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
55
+   */
34 56
 #if ENABLED(THERMAL_PROTECTION_BED)
35 57
   #define THERMAL_PROTECTION_BED_PERIOD 20    // Seconds
36 58
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
37 59
 #endif
38 60
 
39
-/**
40
- * Automatic Temperature:
41
- * The hotend target temperature is calculated by all the buffered lines of gcode.
42
- * The maximum buffered steps/sec of the extruder motor is called "se".
43
- * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
44
- * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
45
- * mintemp and maxtemp. Turn this off by excuting M109 without F*
46
- * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
47
- * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
48
- */
49 61
 #if ENABLED(PIDTEMP)
50 62
   // this adds an experimental additional term to the heating power, proportional to the extrusion speed.
51 63
   // if Kc is chosen well, the additional required power due to increased melting should be compensated.
@@ -56,14 +68,16 @@
56 68
   #endif
57 69
 #endif
58 70
 
59
-
60
-//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
61
-//The maximum buffered steps/sec of the extruder motor are called "se".
62
-//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
63
-// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
64
-// you exit the value by any M109 without F*
65
-// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
66
-// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
71
+/**
72
+ * Automatic Temperature:
73
+ * The hotend target temperature is calculated by all the buffered lines of gcode.
74
+ * The maximum buffered steps/sec of the extruder motor is called "se".
75
+ * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
76
+ * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
77
+ * mintemp and maxtemp. Turn this off by executing M109 without F*
78
+ * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
79
+ * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
80
+ */
67 81
 #define AUTOTEMP
68 82
 #if ENABLED(AUTOTEMP)
69 83
   #define AUTOTEMP_OLDWEIGHT 0.98
@@ -240,7 +254,13 @@
240 254
 #define INVERT_E_STEP_PIN false
241 255
 
242 256
 // Default stepper release if idle. Set to 0 to deactivate.
257
+// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
258
+// Time can be set by M18 and M84.
243 259
 #define DEFAULT_STEPPER_DEACTIVE_TIME 60
260
+#define DISABLE_INACTIVE_X true
261
+#define DISABLE_INACTIVE_Y true
262
+#define DISABLE_INACTIVE_Z true  // set to false if the nozzle will fall down on your printed part when print has finished.
263
+#define DISABLE_INACTIVE_E true
244 264
 
245 265
 #define DEFAULT_MINIMUMFEEDRATE       0.0     // minimum feedrate
246 266
 #define DEFAULT_MINTRAVELFEEDRATE     0.0
@@ -276,6 +296,9 @@
276 296
 // Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
277 297
 #define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
278 298
 
299
+// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
300
+//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
301
+
279 302
 // uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
280 303
 //#define DIGIPOT_I2C
281 304
 // Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
@@ -349,17 +372,16 @@
349 372
   //#define USE_SMALL_INFOFONT
350 373
 #endif // DOGLCD
351 374
 
352
-
353 375
 // @section more
354 376
 
355 377
 // The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
356
-//#define USE_WATCHDOG
378
+#define USE_WATCHDOG
357 379
 
358 380
 #if ENABLED(USE_WATCHDOG)
359
-// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
360
-// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
361
-//  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
362
-//#define WATCHDOG_RESET_MANUAL
381
+  // If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
382
+  // The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
383
+  //  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
384
+  //#define WATCHDOG_RESET_MANUAL
363 385
 #endif
364 386
 
365 387
 // @section lcd
@@ -370,6 +392,7 @@
370 392
 //#define BABYSTEPPING
371 393
 #if ENABLED(BABYSTEPPING)
372 394
   #define BABYSTEP_XY  //not only z, but also XY in the menu. more clutter, more functions
395
+                       //not implemented for deltabots!
373 396
   #define BABYSTEP_INVERT_Z false  //true for inverse movements in Z
374 397
   #define BABYSTEP_MULTIPLICATOR 1 //faster movements
375 398
 #endif
@@ -388,7 +411,6 @@
388 411
 #if ENABLED(ADVANCE)
389 412
   #define EXTRUDER_ADVANCE_K .0
390 413
   #define D_FILAMENT 1.75
391
-  #define STEPS_MM_E 100.47095761381482
392 414
 #endif
393 415
 
394 416
 // @section extras
@@ -397,7 +419,7 @@
397 419
 #define MM_PER_ARC_SEGMENT 1
398 420
 #define N_ARC_CORRECTION 25
399 421
 
400
-const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
422
+const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
401 423
 
402 424
 // @section temperature
403 425
 
@@ -446,11 +468,11 @@ const unsigned int dropsegments=5; //everything with less than this number of st
446 468
   #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
447 469
   #define RETRACT_LENGTH 3               //default retract length (positive mm)
448 470
   #define RETRACT_LENGTH_SWAP 13         //default swap retract length (positive mm), for extruder change
449
-  #define RETRACT_FEEDRATE 80*60         //default feedrate for retracting (mm/s)
471
+  #define RETRACT_FEEDRATE 80            //default feedrate for retracting (mm/s)
450 472
   #define RETRACT_ZLIFT 0                //default retract Z-lift
451 473
   #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
452 474
   //#define RETRACT_RECOVER_LENGTH_SWAP 0  //default additional swap recover length (mm, added to retract length when recovering from extruder change)
453
-  #define RETRACT_RECOVER_FEEDRATE 8*60  //default feedrate for recovering from retraction (mm/s)
475
+  #define RETRACT_RECOVER_FEEDRATE 8     //default feedrate for recovering from retraction (mm/s)
454 476
 #endif
455 477
 
456 478
 // Add support for experimental filament exchange support M600; requires display
@@ -462,12 +484,15 @@ const unsigned int dropsegments=5; //everything with less than this number of st
462 484
     #define FILAMENTCHANGE_ZADD 10
463 485
     #define FILAMENTCHANGE_FIRSTRETRACT -2
464 486
     #define FILAMENTCHANGE_FINALRETRACT -100
487
+    #define AUTO_FILAMENT_CHANGE                //This extrude filament until you press the button on LCD
488
+    #define AUTO_FILAMENT_CHANGE_LENGTH 0.04    //Extrusion length on automatic extrusion loop
489
+    #define AUTO_FILAMENT_CHANGE_FEEDRATE 300   //Extrusion feedrate (mm/min) on automatic extrusion loop
465 490
   #endif
466 491
 #endif
467 492
 
468 493
 /******************************************************************************\
469 494
  * enable this section if you have TMC26X motor drivers.
470
- * you need to import the TMC26XStepper library into the arduino IDE for this
495
+ * you need to import the TMC26XStepper library into the Arduino IDE for this
471 496
  ******************************************************************************/
472 497
 
473 498
 // @section tmc
@@ -475,52 +500,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
475 500
 //#define HAVE_TMCDRIVER
476 501
 #if ENABLED(HAVE_TMCDRIVER)
477 502
 
478
-//#define X_IS_TMC
503
+  //#define X_IS_TMC
479 504
   #define X_MAX_CURRENT 1000  //in mA
480 505
   #define X_SENSE_RESISTOR 91 //in mOhms
481 506
   #define X_MICROSTEPS 16     //number of microsteps
482 507
 
483
-//#define X2_IS_TMC
508
+  //#define X2_IS_TMC
484 509
   #define X2_MAX_CURRENT 1000  //in mA
485 510
   #define X2_SENSE_RESISTOR 91 //in mOhms
486 511
   #define X2_MICROSTEPS 16     //number of microsteps
487 512
 
488
-//#define Y_IS_TMC
513
+  //#define Y_IS_TMC
489 514
   #define Y_MAX_CURRENT 1000  //in mA
490 515
   #define Y_SENSE_RESISTOR 91 //in mOhms
491 516
   #define Y_MICROSTEPS 16     //number of microsteps
492 517
 
493
-//#define Y2_IS_TMC
518
+  //#define Y2_IS_TMC
494 519
   #define Y2_MAX_CURRENT 1000  //in mA
495 520
   #define Y2_SENSE_RESISTOR 91 //in mOhms
496 521
   #define Y2_MICROSTEPS 16     //number of microsteps
497 522
 
498
-//#define Z_IS_TMC
523
+  //#define Z_IS_TMC
499 524
   #define Z_MAX_CURRENT 1000  //in mA
500 525
   #define Z_SENSE_RESISTOR 91 //in mOhms
501 526
   #define Z_MICROSTEPS 16     //number of microsteps
502 527
 
503
-//#define Z2_IS_TMC
528
+  //#define Z2_IS_TMC
504 529
   #define Z2_MAX_CURRENT 1000  //in mA
505 530
   #define Z2_SENSE_RESISTOR 91 //in mOhms
506 531
   #define Z2_MICROSTEPS 16     //number of microsteps
507 532
 
508
-//#define E0_IS_TMC
533
+  //#define E0_IS_TMC
509 534
   #define E0_MAX_CURRENT 1000  //in mA
510 535
   #define E0_SENSE_RESISTOR 91 //in mOhms
511 536
   #define E0_MICROSTEPS 16     //number of microsteps
512 537
 
513
-//#define E1_IS_TMC
538
+  //#define E1_IS_TMC
514 539
   #define E1_MAX_CURRENT 1000  //in mA
515 540
   #define E1_SENSE_RESISTOR 91 //in mOhms
516 541
   #define E1_MICROSTEPS 16     //number of microsteps
517 542
 
518
-//#define E2_IS_TMC
543
+  //#define E2_IS_TMC
519 544
   #define E2_MAX_CURRENT 1000  //in mA
520 545
   #define E2_SENSE_RESISTOR 91 //in mOhms
521 546
   #define E2_MICROSTEPS 16     //number of microsteps
522 547
 
523
-//#define E3_IS_TMC
548
+  //#define E3_IS_TMC
524 549
   #define E3_MAX_CURRENT 1000  //in mA
525 550
   #define E3_SENSE_RESISTOR 91 //in mOhms
526 551
   #define E3_MICROSTEPS 16     //number of microsteps
@@ -529,7 +554,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
529 554
 
530 555
 /******************************************************************************\
531 556
  * enable this section if you have L6470  motor drivers.
532
- * you need to import the L6470 library into the arduino IDE for this
557
+ * you need to import the L6470 library into the Arduino IDE for this
533 558
  ******************************************************************************/
534 559
 
535 560
 // @section l6470
@@ -537,63 +562,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
537 562
 //#define HAVE_L6470DRIVER
538 563
 #if ENABLED(HAVE_L6470DRIVER)
539 564
 
540
-//#define X_IS_L6470
565
+  //#define X_IS_L6470
541 566
   #define X_MICROSTEPS 16     //number of microsteps
542
-  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
567
+  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
543 568
   #define X_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
544 569
   #define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
545 570
 
546
-//#define X2_IS_L6470
571
+  //#define X2_IS_L6470
547 572
   #define X2_MICROSTEPS 16     //number of microsteps
548
-  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
573
+  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
549 574
   #define X2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
550 575
   #define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
551 576
 
552
-//#define Y_IS_L6470
577
+  //#define Y_IS_L6470
553 578
   #define Y_MICROSTEPS 16     //number of microsteps
554
-  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
579
+  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
555 580
   #define Y_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
556 581
   #define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
557 582
 
558
-//#define Y2_IS_L6470
583
+  //#define Y2_IS_L6470
559 584
   #define Y2_MICROSTEPS 16     //number of microsteps
560
-  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
585
+  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
561 586
   #define Y2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
562 587
   #define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
563 588
 
564
-//#define Z_IS_L6470
589
+  //#define Z_IS_L6470
565 590
   #define Z_MICROSTEPS 16     //number of microsteps
566
-  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
591
+  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
567 592
   #define Z_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
568 593
   #define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
569 594
 
570
-//#define Z2_IS_L6470
595
+  //#define Z2_IS_L6470
571 596
   #define Z2_MICROSTEPS 16     //number of microsteps
572
-  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
597
+  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
573 598
   #define Z2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
574 599
   #define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
575 600
 
576
-//#define E0_IS_L6470
601
+  //#define E0_IS_L6470
577 602
   #define E0_MICROSTEPS 16     //number of microsteps
578
-  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
603
+  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
579 604
   #define E0_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
580 605
   #define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
581 606
 
582
-//#define E1_IS_L6470
607
+  //#define E1_IS_L6470
583 608
   #define E1_MICROSTEPS 16     //number of microsteps
584
-  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
609
+  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
585 610
   #define E1_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
586 611
   #define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
587 612
 
588
-//#define E2_IS_L6470
613
+  //#define E2_IS_L6470
589 614
   #define E2_MICROSTEPS 16     //number of microsteps
590
-  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
615
+  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
591 616
   #define E2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
592 617
   #define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
593 618
 
594
-//#define E3_IS_L6470
619
+  //#define E3_IS_L6470
595 620
   #define E3_MICROSTEPS 16     //number of microsteps
596
-  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
621
+  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
597 622
   #define E3_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
598 623
   #define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
599 624
 

Marlin/configurator/config/Configuration.h → Marlin/example_configurations/Hephestos_2/Configuration.h Näytä tiedosto

@@ -47,7 +47,7 @@ Here are some standard links for getting your machine calibrated:
47 47
 // User-specified version info of this build to display in [Pronterface, etc] terminal window during
48 48
 // startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
49 49
 // build by the user have been successfully uploaded into firmware.
50
-#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
50
+#define STRING_CONFIG_H_AUTHOR "@jbrazio" // Who made the changes.
51 51
 #define SHOW_BOOTSCREEN
52 52
 #define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
53 53
 //#define STRING_SPLASH_LINE2 STRING_DISTRIBUTION_DATE // will be shown during bootup in line 2
@@ -70,16 +70,16 @@ Here are some standard links for getting your machine calibrated:
70 70
 // The following define selects which electronics board you have.
71 71
 // Please choose the name from boards.h that matches your setup
72 72
 #ifndef MOTHERBOARD
73
-  #define MOTHERBOARD BOARD_RAMPS_13_EFB
73
+  #define MOTHERBOARD BOARD_BQ_ZUM_MEGA_3D
74 74
 #endif
75 75
 
76 76
 // Optional custom name for your RepStrap or other custom machine
77 77
 // Displayed in the LCD "Ready" message
78
-//#define CUSTOM_MACHINE_NAME "3D Printer"
78
+#define CUSTOM_MACHINE_NAME "BQ Hephestos 2"
79 79
 
80 80
 // Define this to set a unique identifier for this printer, (Used by some programs to differentiate between machines)
81 81
 // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4)
82
-//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
82
+#define MACHINE_UUID "8d083632-40c5-4649-85b8-43d9ae6c5d55" // BQ Hephestos 2 standard config
83 83
 
84 84
 // This defines the number of extruders
85 85
 // :[1,2,3,4]
@@ -110,6 +110,7 @@ Here are some standard links for getting your machine calibrated:
110 110
 //--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
111 111
 //
112 112
 //// Temperature sensor settings:
113
+// -3 is thermocouple with MAX31855 (only for sensor 0)
113 114
 // -2 is thermocouple with MAX6675 (only for sensor 0)
114 115
 // -1 is thermocouple with AD595
115 116
 // 0 is not used
@@ -129,6 +130,7 @@ Here are some standard links for getting your machine calibrated:
129 130
 // 13 is 100k Hisens 3950  1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
130 131
 // 20 is the PT100 circuit found in the Ultimainboard V2.x
131 132
 // 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
133
+// 70 is the 100K thermistor found in the bq Hephestos 2
132 134
 //
133 135
 //    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
134 136
 //                          (but gives greater accuracy and more stable PID)
@@ -144,8 +146,8 @@ Here are some standard links for getting your machine calibrated:
144 146
 //     Use it for Testing or Development purposes. NEVER for production machine.
145 147
 //#define DUMMY_THERMISTOR_998_VALUE 25
146 148
 //#define DUMMY_THERMISTOR_999_VALUE 100
147
-// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
148
-#define TEMP_SENSOR_0 1
149
+// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-3': "Thermocouple + MAX31855 (only for sensor 0)", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
150
+#define TEMP_SENSOR_0 70
149 151
 #define TEMP_SENSOR_1 0
150 152
 #define TEMP_SENSOR_2 0
151 153
 #define TEMP_SENSOR_3 0
@@ -172,20 +174,15 @@ Here are some standard links for getting your machine calibrated:
172 174
 // When temperature exceeds max temp, your heater will be switched off.
173 175
 // This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure!
174 176
 // You should use MINTEMP for thermistor short/failure protection.
175
-#define HEATER_0_MAXTEMP 275
177
+#define HEATER_0_MAXTEMP 250
176 178
 #define HEATER_1_MAXTEMP 275
177 179
 #define HEATER_2_MAXTEMP 275
178 180
 #define HEATER_3_MAXTEMP 275
179 181
 #define BED_MAXTEMP 150
180 182
 
181
-// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
182
-// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
183
-// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
184
-//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
185
-
186 183
 // If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
187
-//#define EXTRUDER_WATTS (12.0*12.0/6.7) //  P=I^2/R
188
-//#define BED_WATTS (12.0*12.0/1.1)      // P=I^2/R
184
+//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
185
+//#define BED_WATTS (12.0*12.0/1.1)      // P=U^2/R
189 186
 
190 187
 //===========================================================================
191 188
 //============================= PID Settings ================================
@@ -202,26 +199,20 @@ Here are some standard links for getting your machine calibrated:
202 199
   //#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay
203 200
   //#define PID_PARAMS_PER_EXTRUDER // Uses separate PID parameters for each extruder (useful for mismatched extruders)
204 201
                                     // Set/get with gcode: M301 E[extruder number, 0-2]
205
-  #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
206
-                                  // is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
202
+  #define PID_FUNCTIONAL_RANGE 250  // If the temperature difference between the target temperature and the actual temperature
203
+                                    // is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
207 204
   #define PID_INTEGRAL_DRIVE_MAX PID_MAX  //limit for the integral term
208 205
   #define K1 0.95 //smoothing factor within the PID
209 206
 
210
-  // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
211
-  // Ultimaker
212
-  #define  DEFAULT_Kp 22.2
213
-  #define  DEFAULT_Ki 1.08
214
-  #define  DEFAULT_Kd 114
215
-
216
-  // MakerGear
217
-  //#define  DEFAULT_Kp 7.0
218
-  //#define  DEFAULT_Ki 0.1
219
-  //#define  DEFAULT_Kd 12
207
+  // Tuned PID values using M303
208
+  #define  DEFAULT_Kp 19.18
209
+  #define  DEFAULT_Ki 1.36
210
+  #define  DEFAULT_Kd 67.42
220 211
 
221
-  // Mendel Parts V9 on 12V
222
-  //#define  DEFAULT_Kp 63.0
223
-  //#define  DEFAULT_Ki 2.25
224
-  //#define  DEFAULT_Kd 440
212
+  // BQ firmware stock PID values
213
+  //#define  DEFAULT_Kp 10.7
214
+  //#define  DEFAULT_Ki 0.45
215
+  //#define  DEFAULT_Kd 3
225 216
 
226 217
 #endif // PIDTEMP
227 218
 
@@ -253,13 +244,13 @@ Here are some standard links for getting your machine calibrated:
253 244
 
254 245
   #define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
255 246
 
256
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
247
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
257 248
   //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
258 249
   #define  DEFAULT_bedKp 10.00
259 250
   #define  DEFAULT_bedKi .023
260 251
   #define  DEFAULT_bedKd 305.4
261 252
 
262
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
253
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
263 254
   //from pidautotune
264 255
   //#define  DEFAULT_bedKp 97.1
265 256
   //#define  DEFAULT_bedKi 1.41
@@ -284,16 +275,15 @@ Here are some standard links for getting your machine calibrated:
284 275
 //===========================================================================
285 276
 
286 277
 /**
287
- * Thermal Runaway Protection protects your printer from damage and fire if a
278
+ * Thermal Protection protects your printer from damage and fire if a
288 279
  * thermistor falls out or temperature sensors fail in any way.
289 280
  *
290 281
  * The issue: If a thermistor falls out or a temperature sensor fails,
291 282
  * Marlin can no longer sense the actual temperature. Since a disconnected
292 283
  * thermistor reads as a low temperature, the firmware will keep the heater on.
293 284
  *
294
- * The solution: Once the temperature reaches the target, start observing.
295
- * If the temperature stays too far below the target (hysteresis) for too long,
296
- * the firmware will halt as a safety precaution.
285
+ * If you get "Thermal Runaway" or "Heating failed" errors the
286
+ * details can be tuned in Configuration_adv.h
297 287
  */
298 288
 
299 289
 #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
@@ -331,20 +321,62 @@ Here are some standard links for getting your machine calibrated:
331 321
 #endif
332 322
 
333 323
 // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
334
-const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
335
-const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
324
+const bool X_MIN_ENDSTOP_INVERTING = true;  // set to true to invert the logic of the endstop.
325
+const bool Y_MIN_ENDSTOP_INVERTING = true;  // set to true to invert the logic of the endstop.
336 326
 const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
337
-const bool X_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
338
-const bool Y_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
339
-const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
327
+const bool X_MAX_ENDSTOP_INVERTING = true;  // set to true to invert the logic of the endstop.
328
+const bool Y_MAX_ENDSTOP_INVERTING = true;  // set to true to invert the logic of the endstop.
329
+const bool Z_MAX_ENDSTOP_INVERTING = true;  // set to true to invert the logic of the endstop.
340 330
 const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
341
-//#define DISABLE_MAX_ENDSTOPS
331
+#define DISABLE_MAX_ENDSTOPS
342 332
 //#define DISABLE_MIN_ENDSTOPS
343 333
 
344
-// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
345
-// This only affects a Z probe endstop if you have separate Z min endstop as well and have
346
-// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
347
-// this has no effect.
334
+//===========================================================================
335
+//============================= Z Probe Options =============================
336
+//===========================================================================
337
+
338
+// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
339
+// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
340
+//
341
+// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
342
+//
343
+// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
344
+// Example: To park the head outside the bed area when homing with G28.
345
+//
346
+// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
347
+//
348
+// For a servo-based Z probe, you must set up servo support below, including
349
+// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
350
+//
351
+// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
352
+// - Use 5V for powered (usu. inductive) sensors.
353
+// - Otherwise connect:
354
+//   - normally-closed switches to GND and D32.
355
+//   - normally-open switches to 5V and D32.
356
+//
357
+// Normally-closed switches are advised and are the default.
358
+//
359
+// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
360
+// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
361
+// default pin for all RAMPS-based boards. Some other boards map differently.
362
+// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
363
+//
364
+// WARNING:
365
+// Setting the wrong pin may have unexpected and potentially disastrous consequences.
366
+// Use with caution and do your homework.
367
+//
368
+//#define Z_MIN_PROBE_ENDSTOP
369
+
370
+// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
371
+// The Z_MIN_PIN will then be used for both Z-homing and probing.
372
+#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
373
+
374
+// To use a probe you must enable one of the two options above!
375
+
376
+// This option disables the use of the Z_MIN_PROBE_PIN
377
+// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
378
+// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
379
+// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
348 380
 //#define DISABLE_Z_MIN_PROBE_ENDSTOP
349 381
 
350 382
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
@@ -354,11 +386,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
354 386
 #define Z_ENABLE_ON 0
355 387
 #define E_ENABLE_ON 0 // For all extruders
356 388
 
357
-// Disables axis when it's not being used.
389
+// Disables axis stepper immediately when it's not being used.
358 390
 // WARNING: When motors turn off there is a chance of losing position accuracy!
359 391
 #define DISABLE_X false
360 392
 #define DISABLE_Y false
361 393
 #define DISABLE_Z false
394
+// Warn on display about possibly reduced accuracy
395
+//#define DISABLE_REDUCED_ACCURACY_WARNING
362 396
 
363 397
 // @section extruder
364 398
 
@@ -368,19 +402,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
368 402
 // @section machine
369 403
 
370 404
 // Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way.
371
-#define INVERT_X_DIR false
405
+#define INVERT_X_DIR true
372 406
 #define INVERT_Y_DIR true
373
-#define INVERT_Z_DIR false
407
+#define INVERT_Z_DIR true
374 408
 
375 409
 // @section extruder
376 410
 
377 411
 // For direct drive extruder v9 set to true, for geared extruder set to false.
378
-#define INVERT_E0_DIR false
412
+#define INVERT_E0_DIR true
379 413
 #define INVERT_E1_DIR false
380 414
 #define INVERT_E2_DIR false
381 415
 #define INVERT_E3_DIR false
382 416
 
383 417
 // @section homing
418
+#define MIN_Z_HEIGHT_FOR_HOMING 5   // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
419
+                                    // Be sure you have this distance over your Z_MAX_POS in case.
384 420
 
385 421
 // ENDSTOP SETTINGS:
386 422
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
@@ -389,8 +425,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
389 425
 #define Y_HOME_DIR -1
390 426
 #define Z_HOME_DIR -1
391 427
 
392
-#define min_software_endstops true // If true, axis won't move to coordinates less than HOME_POS.
393
-#define max_software_endstops true  // If true, axis won't move to coordinates greater than the defined lengths below.
428
+#define min_software_endstops false // If true, axis won't move to coordinates less than HOME_POS.
429
+#define max_software_endstops false // If true, axis won't move to coordinates greater than the defined lengths below.
394 430
 
395 431
 // @section machine
396 432
 
@@ -398,9 +434,9 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
398 434
 #define X_MIN_POS 0
399 435
 #define Y_MIN_POS 0
400 436
 #define Z_MIN_POS 0
401
-#define X_MAX_POS 200
402
-#define Y_MAX_POS 200
403
-#define Z_MAX_POS 200
437
+#define X_MAX_POS 210
438
+#define Y_MAX_POS 297
439
+#define Z_MAX_POS 210
404 440
 
405 441
 //===========================================================================
406 442
 //========================= Filament Runout Sensor ==========================
@@ -416,16 +452,11 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
416 452
 #endif
417 453
 
418 454
 //===========================================================================
419
-//=========================== Manual Bed Leveling ===========================
455
+//============================ Mesh Bed Leveling ============================
420 456
 //===========================================================================
421 457
 
422
-//#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
423 458
 //#define MESH_BED_LEVELING    // Enable mesh bed leveling.
424 459
 
425
-#if ENABLED(MANUAL_BED_LEVELING)
426
-  #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
427
-#endif  // MANUAL_BED_LEVELING
428
-
429 460
 #if ENABLED(MESH_BED_LEVELING)
430 461
   #define MESH_MIN_X 10
431 462
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
@@ -434,6 +465,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
434 465
   #define MESH_NUM_X_POINTS 3  // Don't use more than 7 points per axis, implementation limited.
435 466
   #define MESH_NUM_Y_POINTS 3
436 467
   #define MESH_HOME_SEARCH_Z 4  // Z after Home, bed somewhere below but above 0.0.
468
+
469
+  //#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
470
+
471
+  #if ENABLED(MANUAL_BED_LEVELING)
472
+    #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
473
+  #endif  // MANUAL_BED_LEVELING
474
+
437 475
 #endif  // MESH_BED_LEVELING
438 476
 
439 477
 //===========================================================================
@@ -442,9 +480,9 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
442 480
 
443 481
 // @section bedlevel
444 482
 
445
-//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
483
+#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
446 484
 //#define DEBUG_LEVELING_FEATURE
447
-#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
485
+#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
448 486
 
449 487
 #if ENABLED(AUTO_BED_LEVELING_FEATURE)
450 488
 
@@ -456,7 +494,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
456 494
   //   This mode is preferred because there are more measurements.
457 495
   //
458 496
   // - "3-point" mode
459
-  //   Probe 3 arbitrary points on the bed (that aren't colinear)
497
+  //   Probe 3 arbitrary points on the bed (that aren't collinear)
460 498
   //   You specify the XY coordinates of all 3 points.
461 499
 
462 500
   // Enable this to sample the bed in a grid (least squares solution).
@@ -465,12 +503,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
465 503
 
466 504
   #if ENABLED(AUTO_BED_LEVELING_GRID)
467 505
 
468
-    #define LEFT_PROBE_BED_POSITION 15
469
-    #define RIGHT_PROBE_BED_POSITION 170
470
-    #define FRONT_PROBE_BED_POSITION 20
471
-    #define BACK_PROBE_BED_POSITION 170
506
+    #define LEFT_PROBE_BED_POSITION  X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER
507
+    #define RIGHT_PROBE_BED_POSITION X_MAX_POS - X_PROBE_OFFSET_FROM_EXTRUDER
508
+    #define FRONT_PROBE_BED_POSITION Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER
509
+    #define BACK_PROBE_BED_POSITION  Y_MAX_POS - Y_PROBE_OFFSET_FROM_EXTRUDER
472 510
 
473
-    #define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
511
+    #define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
474 512
 
475 513
     // Set the number of grid points per dimension.
476 514
     // You probably don't need more than 3 (squared=9).
@@ -478,42 +516,67 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
478 516
 
479 517
   #else  // !AUTO_BED_LEVELING_GRID
480 518
 
481
-      // Arbitrary points to probe.
482
-      // A simple cross-product is used to estimate the plane of the bed.
483
-      #define ABL_PROBE_PT_1_X 15
484
-      #define ABL_PROBE_PT_1_Y 180
485
-      #define ABL_PROBE_PT_2_X 15
486
-      #define ABL_PROBE_PT_2_Y 20
487
-      #define ABL_PROBE_PT_3_X 170
488
-      #define ABL_PROBE_PT_3_Y 20
519
+    // Arbitrary points to probe.
520
+    // A simple cross-product is used to estimate the plane of the bed.
521
+    #define ABL_PROBE_PT_1_X X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER
522
+    #define ABL_PROBE_PT_1_Y Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER
523
+    #define ABL_PROBE_PT_2_X X_MAX_POS - X_PROBE_OFFSET_FROM_EXTRUDER
524
+    #define ABL_PROBE_PT_2_Y Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER
525
+    #define ABL_PROBE_PT_3_X ((X_MIN_POS + X_MAX_POS) / 2)
526
+    #define ABL_PROBE_PT_3_Y Y_MAX_POS - Y_PROBE_OFFSET_FROM_EXTRUDER
489 527
 
490 528
   #endif // AUTO_BED_LEVELING_GRID
491 529
 
492
-  // Offsets to the Z probe relative to the nozzle tip.
530
+  // Z Probe to nozzle (X,Y) offset, relative to (0, 0).
493 531
   // X and Y offsets must be integers.
494
-  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // Z probe to nozzle X offset: -left  +right
495
-  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Z probe to nozzle Y offset: -front +behind
496
-  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z probe to nozzle Z offset: -below (always!)
497
-
498
-  #define Z_RAISE_BEFORE_HOMING 4       // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
499
-                                        // Be sure you have this distance over your Z_MAX_POS in case.
532
+  //
533
+  // In the following example the X and Y offsets are both positive:
534
+  // #define X_PROBE_OFFSET_FROM_EXTRUDER 10
535
+  // #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
536
+  //
537
+  //    +-- BACK ---+
538
+  //    |           |
539
+  //  L |    (+) P  | R <-- probe (20,20)
540
+  //  E |           | I
541
+  //  F | (-) N (+) | G <-- nozzle (10,10)
542
+  //  T |           | H
543
+  //    |    (-)    | T
544
+  //    |           |
545
+  //    O-- FRONT --+
546
+  //  (0,0)
547
+  #define X_PROBE_OFFSET_FROM_EXTRUDER 34  // X offset: -left  [of the nozzle] +right
548
+  #define Y_PROBE_OFFSET_FROM_EXTRUDER 15  // Y offset: -front [of the nozzle] +behind
549
+  #define Z_PROBE_OFFSET_FROM_EXTRUDER 0   // Z offset: -below [the nozzle] (always negative!)
500 550
 
501 551
   #define XY_TRAVEL_SPEED 8000         // X and Y axis travel speed between probes, in mm/min.
502 552
 
503
-  #define Z_RAISE_BEFORE_PROBING 15   // How much the Z axis will be raised before traveling to the first probing point.
504
-  #define Z_RAISE_BETWEEN_PROBINGS 5  // How much the Z axis will be raised when traveling from between next probing points.
505
-  #define Z_RAISE_AFTER_PROBING 15    // How much the Z axis will be raised after the last probing point.
553
+  #define Z_RAISE_BEFORE_PROBING   5  // How much the Z axis will be raised before traveling to the first probing point.
554
+  #define Z_RAISE_BETWEEN_PROBINGS 2  // How much the Z axis will be raised when traveling from between next probing points.
555
+  #define Z_RAISE_AFTER_PROBING    5  // How much the Z axis will be raised after the last probing point.
556
+
557
+  //#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
558
+                                                                             // Useful to retract a deployable Z probe.
559
+
560
+  // Probes are sensors/switches that need to be activated before they can be used
561
+  // and deactivated after the use.
562
+  // Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
563
+
564
+  // A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
565
+  // when the hardware endstops are active.
566
+  #define FIX_MOUNTED_PROBE
506 567
 
507
-//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
508
-                                                                            // Useful to retract a deployable Z probe.
568
+  // A Servo Probe can be defined in the servo section below.
509 569
 
510
-  //#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
570
+  // An Allen Key Probe is currently predefined only in the delta example configurations.
571
+
572
+  //#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
511 573
   //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
512 574
 
513
-// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
514
-// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
575
+  // If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
576
+  // it is highly recommended you leave Z_SAFE_HOMING enabled!
515 577
 
516
-  #define Z_SAFE_HOMING   // This feature is meant to avoid Z homing with Z probe outside the bed area.
578
+  #define Z_SAFE_HOMING   // Use the z-min-probe for homing to z-min - not the z-min-endstop.
579
+                          // This feature is meant to avoid Z homing with Z probe outside the bed area.
517 580
                           // When defined, it will:
518 581
                           // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
519 582
                           // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
@@ -527,37 +590,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
527 590
 
528 591
   #endif
529 592
 
530
-  // Support for a dedicated Z probe endstop separate from the Z min endstop.
531
-  // If you would like to use both a Z probe and a Z min endstop together,
532
-  // uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
533
-  // If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
534
-  // Example: To park the head outside the bed area when homing with G28.
535
-  //
536
-  // WARNING:
537
-  // The Z min endstop will need to set properly as it would without a Z probe
538
-  // to prevent head crashes and premature stopping during a print.
539
-  //
540
-  // To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
541
-  // defined in the pins_XXXXX.h file for your control board.
542
-  // If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
543
-  // Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
544
-  // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
545
-  // in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
546
-  // otherwise connect to ground and D32 for normally closed configuration
547
-  // and 5V and D32 for normally open configurations.
548
-  // Normally closed configuration is advised and assumed.
549
-  // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
550
-  // Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
551
-  // Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
552
-  // D32 is currently selected in the RAMPS 1.3/1.4 pin file.
553
-  // All other boards will need changes to the respective pins_XXXXX.h file.
554
-  //
555
-  // WARNING:
556
-  // Setting the wrong pin may have unexpected and potentially disastrous outcomes.
557
-  // Use with caution and do your homework.
558
-  //
559
-  //#define Z_MIN_PROBE_ENDSTOP
560
-
561 593
 #endif // AUTO_BED_LEVELING_FEATURE
562 594
 
563 595
 
@@ -582,22 +614,22 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
582 614
  * MOVEMENT SETTINGS
583 615
  */
584 616
 
585
-#define HOMING_FEEDRATE {50*60, 50*60, 4*60, 0}  // set the homing speeds (mm/min)
617
+#define HOMING_FEEDRATE {150*60, 150*60, 3.3*60, 0}  // set the homing speeds (mm/min)
586 618
 
587 619
 // default settings
588 620
 
589
-#define DEFAULT_AXIS_STEPS_PER_UNIT   {80,80,4000,500}  // default steps per unit for Ultimaker
590
-#define DEFAULT_MAX_FEEDRATE          {300, 300, 5, 25}    // (mm/sec)
591
-#define DEFAULT_MAX_ACCELERATION      {3000,3000,100,10000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
621
+#define DEFAULT_AXIS_STEPS_PER_UNIT   {160, 160, 8000, 204.146} // default steps per unit for Ultimaker
622
+#define DEFAULT_MAX_FEEDRATE          {200, 200, 3.3, 200}      // (mm/sec)
623
+#define DEFAULT_MAX_ACCELERATION      {1000, 1000, 100, 3000}   // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
592 624
 
593
-#define DEFAULT_ACCELERATION          3000    // X, Y, Z and E acceleration in mm/s^2 for printing moves
625
+#define DEFAULT_ACCELERATION          1000    // X, Y, Z and E acceleration in mm/s^2 for printing moves
594 626
 #define DEFAULT_RETRACT_ACCELERATION  3000    // E acceleration in mm/s^2 for retracts
595
-#define DEFAULT_TRAVEL_ACCELERATION   3000    // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
627
+#define DEFAULT_TRAVEL_ACCELERATION   1000    // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
596 628
 
597 629
 // The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
598
-#define DEFAULT_XYJERK                20.0    // (mm/sec)
630
+#define DEFAULT_XYJERK                15.0    // (mm/sec)
599 631
 #define DEFAULT_ZJERK                 0.4     // (mm/sec)
600
-#define DEFAULT_EJERK                 5.0    // (mm/sec)
632
+#define DEFAULT_EJERK                 2.0     // (mm/sec)
601 633
 
602 634
 
603 635
 //=============================================================================
@@ -611,8 +643,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
611 643
 #if ENABLED(CUSTOM_M_CODES)
612 644
   #if ENABLED(AUTO_BED_LEVELING_FEATURE)
613 645
     #define CUSTOM_M_CODE_SET_Z_PROBE_OFFSET 851
614
-    #define Z_PROBE_OFFSET_RANGE_MIN -20
615
-    #define Z_PROBE_OFFSET_RANGE_MAX 20
646
+    #define Z_PROBE_OFFSET_RANGE_MIN -5
647
+    #define Z_PROBE_OFFSET_RANGE_MAX  0
616 648
   #endif
617 649
 #endif
618 650
 
@@ -624,7 +656,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
624 656
 // M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
625 657
 // M502 - reverts to the default "factory settings".  You still need to store them in EEPROM afterwards if you want to.
626 658
 //define this to enable EEPROM support
627
-//#define EEPROM_SETTINGS
659
+#define EEPROM_SETTINGS
628 660
 
629 661
 #if ENABLED(EEPROM_SETTINGS)
630 662
   // To disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
@@ -632,6 +664,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
632 664
 #endif
633 665
 
634 666
 //
667
+// Host Keepalive
668
+//
669
+// By default Marlin will send a busy status message to the host
670
+// every 2 seconds when it can't accept commands.
671
+//
672
+//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
673
+
674
+//
635 675
 // M100 Free Memory Watcher
636 676
 //
637 677
 //#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
@@ -639,38 +679,38 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
639 679
 // @section temperature
640 680
 
641 681
 // Preheat Constants
642
-#define PLA_PREHEAT_HOTEND_TEMP 180
643
-#define PLA_PREHEAT_HPB_TEMP 70
644
-#define PLA_PREHEAT_FAN_SPEED 0   // Insert Value between 0 and 255
682
+#define PLA_PREHEAT_HOTEND_TEMP 210
683
+#define PLA_PREHEAT_HPB_TEMP    70
684
+#define PLA_PREHEAT_FAN_SPEED   0   // Insert Value between 0 and 255
645 685
 
646 686
 #define ABS_PREHEAT_HOTEND_TEMP 240
647
-#define ABS_PREHEAT_HPB_TEMP 110
648
-#define ABS_PREHEAT_FAN_SPEED 0   // Insert Value between 0 and 255
687
+#define ABS_PREHEAT_HPB_TEMP    110
688
+#define ABS_PREHEAT_FAN_SPEED   0   // Insert Value between 0 and 255
649 689
 
650 690
 //==============================LCD and SD support=============================
651 691
 // @section lcd
652 692
 
653 693
 // Define your display language below. Replace (en) with your language code and uncomment.
654
-// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
694
+// en, pl, fr, de, es, ru, bg, it, pt, pt_utf8, pt-br, pt-br_utf8, fi, an, nl, ca, eu, kana, kana_utf8, cn, cz, test
655 695
 // See also language.h
656 696
 #define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
657 697
 
658 698
 // Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
659 699
 // To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
660
-// See also documentation/LCDLanguageFont.md
700
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
661 701
   #define DISPLAY_CHARSET_HD44780_JAPAN        // this is the most common hardware
662 702
   //#define DISPLAY_CHARSET_HD44780_WESTERN
663 703
   //#define DISPLAY_CHARSET_HD44780_CYRILLIC
664 704
 
665 705
 //#define ULTRA_LCD  //general LCD support, also 16x2
666 706
 //#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
667
-//#define SDSUPPORT // Enable SD Card Support in Hardware Console
668
-// Changed behaviour! If you need SDSUPPORT uncomment it!
669
-//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
670
-//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
707
+#define SDSUPPORT // Enable SD Card Support in Hardware Console
708
+                  // Changed behaviour! If you need SDSUPPORT uncomment it!
709
+//#define SPI_SPEED SPI_HALF_SPEED // (also SPI_QUARTER_SPEED, SPI_EIGHTH_SPEED) Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
671 710
 //#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
672 711
 //#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
673 712
 //#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
713
+//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
674 714
 //#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
675 715
 //#define ULTIPANEL  //the UltiPanel as on Thingiverse
676 716
 //#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
@@ -687,13 +727,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
687 727
 
688 728
 // The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
689 729
 // http://panucatt.com
690
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
730
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
691 731
 //#define VIKI2
692 732
 //#define miniVIKI
693 733
 
694 734
 // This is a new controller currently under development.  https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
695 735
 //
696
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
736
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
697 737
 //#define ELB_FULL_GRAPHIC_CONTROLLER
698 738
 //#define SD_DETECT_INVERTED
699 739
 
@@ -708,7 +748,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
708 748
 // The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
709 749
 // http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
710 750
 //
711
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
751
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
712 752
 //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
713 753
 
714 754
 // The RepRapWorld REPRAPWORLD_KEYPAD v1.1
@@ -725,12 +765,17 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
725 765
 // http://reprap.org/wiki/Mini_panel
726 766
 //#define MINIPANEL
727 767
 
768
+// BQ SMART FULL GRAPHIC CONTROLLER
769
+#define BQ_LCD_SMART_CONTROLLER
770
+
728 771
 /**
729 772
  * I2C Panels
730 773
  */
731 774
 
732 775
 //#define LCD_I2C_SAINSMART_YWROBOT
733 776
 
777
+//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
778
+
734 779
 // PANELOLU2 LCD with status LEDs, separate encoder and click inputs
735 780
 //
736 781
 // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
@@ -742,9 +787,9 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
742 787
 
743 788
 // Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs
744 789
 //#define LCD_I2C_VIKI
745
-  
790
+
746 791
 // SSD1306 OLED generic display support
747
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
792
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
748 793
 //#define U8GLIB_SSD1306
749 794
 
750 795
 // Shift register panels
@@ -756,13 +801,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
756 801
 
757 802
 // @section extras
758 803
 
759
-// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
804
+// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
760 805
 //#define FAST_PWM_FAN
761 806
 
762 807
 // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
763 808
 // which is not as annoying as with the hardware PWM. On the other hand, if this frequency
764 809
 // is too low, you should also increment SOFT_PWM_SCALE.
765
-//#define FAN_SOFT_PWM
810
+#define FAN_SOFT_PWM
766 811
 
767 812
 // Incrementing this by 1 will double the software PWM frequency,
768 813
 // affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
@@ -838,19 +883,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
838 883
 // Uncomment below to enable
839 884
 //#define FILAMENT_SENSOR
840 885
 
841
-#define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
842
-#define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
886
+#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
843 887
 
844
-#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00  //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
845
-#define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
846
-#define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
847
-#define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
888
+#if ENABLED(FILAMENT_SENSOR)
889
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
890
+  #define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
848 891
 
849
-//defines used in the code
850
-#define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
892
+  #define MEASURED_UPPER_LIMIT         2.00  //upper limit factor used for sensor reading validation in mm
893
+  #define MEASURED_LOWER_LIMIT         1.60  //lower limit factor for sensor reading validation in mm
894
+  #define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
851 895
 
852
-//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
853
-//#define FILAMENT_LCD_DISPLAY
896
+  #define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
897
+
898
+  //When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
899
+  //#define FILAMENT_LCD_DISPLAY
900
+#endif
854 901
 
855 902
 #include "Configuration_adv.h"
856 903
 #include "thermistortables.h"

+ 630
- 0
Marlin/example_configurations/Hephestos_2/Configuration_adv.h Näytä tiedosto

@@ -0,0 +1,630 @@
1
+#ifndef CONFIGURATION_ADV_H
2
+#define CONFIGURATION_ADV_H
3
+
4
+#include "Conditionals.h"
5
+
6
+// @section temperature
7
+
8
+//===========================================================================
9
+//=============================Thermal Settings  ============================
10
+//===========================================================================
11
+
12
+#if ENABLED(BED_LIMIT_SWITCHING)
13
+  #define BED_HYSTERESIS 2 //only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
14
+#endif
15
+#define BED_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
16
+
17
+/**
18
+ * Thermal Protection parameters
19
+ */
20
+  /**
21
+   * Thermal Protection protects your printer from damage and fire if a
22
+   * thermistor falls out or temperature sensors fail in any way.
23
+   *
24
+   * The issue: If a thermistor falls out or a temperature sensor fails,
25
+   * Marlin can no longer sense the actual temperature. Since a disconnected
26
+   * thermistor reads as a low temperature, the firmware will keep the heater on.
27
+   *
28
+   * The solution: Once the temperature reaches the target, start observing.
29
+   * If the temperature stays too far below the target (hysteresis) for too long (period),
30
+   * the firmware will halt the machine as a safety precaution.
31
+   *
32
+   * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
33
+   */
34
+#if ENABLED(THERMAL_PROTECTION_HOTENDS)
35
+  #define THERMAL_PROTECTION_PERIOD 40        // Seconds
36
+  #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
37
+
38
+  /**
39
+   * Whenever an M104 or M109 increases the target temperature the firmware will wait for the
40
+   * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
41
+   * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
42
+   * but only if the current temperature is far enough below the target for a reliable test.
43
+   *
44
+   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
45
+   * WATCH_TEMP_INCREASE should not be below 2.
46
+   */
47
+  #define WATCH_TEMP_PERIOD 16                // Seconds
48
+  #define WATCH_TEMP_INCREASE 4               // Degrees Celsius
49
+#endif
50
+
51
+  /**
52
+   * Thermal Protection parameters for the bed
53
+   * are like the above for the hotends.
54
+   * WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
55
+   */
56
+#if ENABLED(THERMAL_PROTECTION_BED)
57
+  #define THERMAL_PROTECTION_BED_PERIOD 20    // Seconds
58
+  #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
59
+#endif
60
+
61
+#if ENABLED(PIDTEMP)
62
+  // this adds an experimental additional term to the heating power, proportional to the extrusion speed.
63
+  // if Kc is chosen well, the additional required power due to increased melting should be compensated.
64
+  #define PID_ADD_EXTRUSION_RATE
65
+  #if ENABLED(PID_ADD_EXTRUSION_RATE)
66
+    #define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
67
+    #define LPQ_MAX_LEN 50
68
+  #endif
69
+#endif
70
+
71
+/**
72
+ * Automatic Temperature:
73
+ * The hotend target temperature is calculated by all the buffered lines of gcode.
74
+ * The maximum buffered steps/sec of the extruder motor is called "se".
75
+ * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
76
+ * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
77
+ * mintemp and maxtemp. Turn this off by executing M109 without F*
78
+ * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
79
+ * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
80
+ */
81
+#define AUTOTEMP
82
+#if ENABLED(AUTOTEMP)
83
+  #define AUTOTEMP_OLDWEIGHT 0.98
84
+#endif
85
+
86
+//Show Temperature ADC value
87
+//The M105 command return, besides traditional information, the ADC value read from temperature sensors.
88
+//#define SHOW_TEMP_ADC_VALUES
89
+
90
+// @section extruder
91
+
92
+//  extruder run-out prevention.
93
+//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
94
+//#define EXTRUDER_RUNOUT_PREVENT
95
+#define EXTRUDER_RUNOUT_MINTEMP 190
96
+#define EXTRUDER_RUNOUT_SECONDS 30.
97
+#define EXTRUDER_RUNOUT_ESTEPS 14. //mm filament
98
+#define EXTRUDER_RUNOUT_SPEED 1500.  //extrusion speed
99
+#define EXTRUDER_RUNOUT_EXTRUDE 100
100
+
101
+// @section temperature
102
+
103
+//These defines help to calibrate the AD595 sensor in case you get wrong temperature measurements.
104
+//The measured temperature is defined as "actualTemp = (measuredTemp * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET"
105
+#define TEMP_SENSOR_AD595_OFFSET 0.0
106
+#define TEMP_SENSOR_AD595_GAIN   1.0
107
+
108
+//This is for controlling a fan to cool down the stepper drivers
109
+//it will turn on when any driver is enabled
110
+//and turn off after the set amount of seconds from last driver being disabled again
111
+#define CONTROLLERFAN_PIN -1 //Pin used for the fan to cool controller (-1 to disable)
112
+#define CONTROLLERFAN_SECS 60 //How many seconds, after all motors were disabled, the fan should run
113
+#define CONTROLLERFAN_SPEED 255  // == full speed
114
+
115
+// When first starting the main fan, run it at full speed for the
116
+// given number of milliseconds.  This gets the fan spinning reliably
117
+// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
118
+//#define FAN_KICKSTART_TIME 100
119
+
120
+// This defines the minimal speed for the main fan, run in PWM mode
121
+// to enable uncomment and set minimal PWM speed for reliable running (1-255)
122
+// if fan speed is [1 - (FAN_MIN_PWM-1)] it is set to FAN_MIN_PWM
123
+//#define FAN_MIN_PWM 50
124
+
125
+// @section extruder
126
+
127
+// Extruder cooling fans
128
+// Configure fan pin outputs to automatically turn on/off when the associated
129
+// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
130
+// Multiple extruders can be assigned to the same pin in which case
131
+// the fan will turn on when any selected extruder is above the threshold.
132
+#define EXTRUDER_0_AUTO_FAN_PIN 11
133
+#define EXTRUDER_1_AUTO_FAN_PIN  6
134
+#define EXTRUDER_2_AUTO_FAN_PIN -1
135
+#define EXTRUDER_3_AUTO_FAN_PIN -1
136
+#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
137
+#define EXTRUDER_AUTO_FAN_SPEED   255  // == full speed
138
+
139
+
140
+//===========================================================================
141
+//=============================Mechanical Settings===========================
142
+//===========================================================================
143
+
144
+// @section homing
145
+
146
+#define ENDSTOPS_ONLY_FOR_HOMING // If defined the endstops will only be used for homing
147
+
148
+// @section extras
149
+
150
+//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
151
+
152
+// A single Z stepper driver is usually used to drive 2 stepper motors.
153
+// Uncomment this define to utilize a separate stepper driver for each Z axis motor.
154
+// Only a few motherboards support this, like RAMPS, which have dual extruder support (the 2nd, often unused, extruder driver is used
155
+// to control the 2nd Z axis stepper motor). The pins are currently only defined for a RAMPS motherboards.
156
+// On a RAMPS (or other 5 driver) motherboard, using this feature will limit you to using 1 extruder.
157
+//#define Z_DUAL_STEPPER_DRIVERS
158
+
159
+#if ENABLED(Z_DUAL_STEPPER_DRIVERS)
160
+
161
+  // 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.
162
+  // That way the machine is capable to align the bed during home, since both Z steppers are homed.
163
+  // There is also an implementation of M666 (software endstops adjustment) to this feature.
164
+  // After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
165
+  // 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.
166
+  // 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.
167
+  // Play a little bit with small adjustments (0.5mm) and check the behaviour.
168
+  // The M119 (endstops report) will start reporting the Z2 Endstop as well.
169
+
170
+  //#define Z_DUAL_ENDSTOPS
171
+
172
+  #if ENABLED(Z_DUAL_ENDSTOPS)
173
+    #define Z2_MAX_PIN 36                     //Endstop used for Z2 axis. In this case I'm using XMAX in a Rumba Board (pin 36)
174
+    const bool Z2_MAX_ENDSTOP_INVERTING = false;
175
+    #define DISABLE_XMAX_ENDSTOP              //Better to disable the XMAX to avoid conflict. Just rename "XMAX_ENDSTOP" by the endstop you are using for Z2 axis.
176
+  #endif
177
+
178
+#endif // Z_DUAL_STEPPER_DRIVERS
179
+
180
+// Same again but for Y Axis.
181
+//#define Y_DUAL_STEPPER_DRIVERS
182
+
183
+#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
184
+  // Define if the two Y drives need to rotate in opposite directions
185
+  #define INVERT_Y2_VS_Y_DIR true
186
+#endif
187
+
188
+// Enable this for dual x-carriage printers.
189
+// A dual x-carriage design has the advantage that the inactive extruder can be parked which
190
+// prevents hot-end ooze contaminating the print. It also reduces the weight of each x-carriage
191
+// allowing faster printing speeds.
192
+//#define DUAL_X_CARRIAGE
193
+#if ENABLED(DUAL_X_CARRIAGE)
194
+  // Configuration for second X-carriage
195
+  // Note: the first x-carriage is defined as the x-carriage which homes to the minimum endstop;
196
+  // the second x-carriage always homes to the maximum endstop.
197
+  #define X2_MIN_POS 80     // set minimum to ensure second x-carriage doesn't hit the parked first X-carriage
198
+  #define X2_MAX_POS 353    // set maximum to the distance between toolheads when both heads are homed
199
+  #define X2_HOME_DIR 1     // the second X-carriage always homes to the maximum endstop position
200
+  #define X2_HOME_POS X2_MAX_POS // default home position is the maximum carriage position
201
+      // However: In this mode the EXTRUDER_OFFSET_X value for the second extruder provides a software
202
+      // override for X2_HOME_POS. This also allow recalibration of the distance between the two endstops
203
+      // without modifying the firmware (through the "M218 T1 X???" command).
204
+      // Remember: you should set the second extruder x-offset to 0 in your slicer.
205
+
206
+  // Pins for second x-carriage stepper driver (defined here to avoid further complicating pins.h)
207
+  #define X2_ENABLE_PIN 29
208
+  #define X2_STEP_PIN 25
209
+  #define X2_DIR_PIN 23
210
+
211
+  // There are a few selectable movement modes for dual x-carriages using M605 S<mode>
212
+  //    Mode 0: Full control. The slicer has full control over both x-carriages and can achieve optimal travel results
213
+  //                           as long as it supports dual x-carriages. (M605 S0)
214
+  //    Mode 1: Auto-park mode. The firmware will automatically park and unpark the x-carriages on tool changes so
215
+  //                           that additional slicer support is not required. (M605 S1)
216
+  //    Mode 2: Duplication mode. The firmware will transparently make the second x-carriage and extruder copy all
217
+  //                           actions of the first x-carriage. This allows the printer to print 2 arbitrary items at
218
+  //                           once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
219
+
220
+  // This is the default power-up mode which can be later using M605.
221
+  #define DEFAULT_DUAL_X_CARRIAGE_MODE 0
222
+
223
+  // Default settings in "Auto-park Mode"
224
+  #define TOOLCHANGE_PARK_ZLIFT   0.2      // the distance to raise Z axis when parking an extruder
225
+  #define TOOLCHANGE_UNPARK_ZLIFT 1        // the distance to raise Z axis when unparking an extruder
226
+
227
+  // Default x offset in duplication mode (typically set to half print bed width)
228
+  #define DEFAULT_DUPLICATION_X_OFFSET 100
229
+
230
+#endif //DUAL_X_CARRIAGE
231
+
232
+// @section homing
233
+
234
+//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
235
+#define X_HOME_BUMP_MM 5
236
+#define Y_HOME_BUMP_MM 5
237
+#define Z_HOME_BUMP_MM 2
238
+#define HOMING_BUMP_DIVISOR {2, 2, 4}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
239
+//#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
240
+
241
+// When G28 is called, this option will make Y home before X
242
+//#define HOME_Y_BEFORE_X
243
+
244
+// @section machine
245
+
246
+#define AXIS_RELATIVE_MODES {false, false, false, false}
247
+
248
+// @section machine
249
+
250
+//By default pololu step drivers require an active high signal. However, some high power drivers require an active low signal as step.
251
+#define INVERT_X_STEP_PIN false
252
+#define INVERT_Y_STEP_PIN false
253
+#define INVERT_Z_STEP_PIN false
254
+#define INVERT_E_STEP_PIN false
255
+
256
+// Default stepper release if idle. Set to 0 to deactivate.
257
+// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
258
+// Time can be set by M18 and M84.
259
+#define DEFAULT_STEPPER_DEACTIVE_TIME 60
260
+#define DISABLE_INACTIVE_X true
261
+#define DISABLE_INACTIVE_Y true
262
+#define DISABLE_INACTIVE_Z true  // set to false if the nozzle will fall down on your printed part when print has finished.
263
+#define DISABLE_INACTIVE_E true
264
+
265
+#define DEFAULT_MINIMUMFEEDRATE       0.0     // minimum feedrate
266
+#define DEFAULT_MINTRAVELFEEDRATE     0.0
267
+
268
+// @section lcd
269
+
270
+#if ENABLED(ULTIPANEL)
271
+  #define MANUAL_FEEDRATE {50*60, 50*60, 4*60, 60} // Feedrates for manual moves along X, Y, Z, E from panel
272
+  #define ULTIPANEL_FEEDMULTIPLY  // Comment to disable setting feedrate multiplier via encoder
273
+#endif
274
+
275
+// @section extras
276
+
277
+// minimum time in microseconds that a movement needs to take if the buffer is emptied.
278
+#define DEFAULT_MINSEGMENTTIME        20000
279
+
280
+// If defined the movements slow down when the look ahead buffer is only half full
281
+#define SLOWDOWN
282
+
283
+// Frequency limit
284
+// See nophead's blog for more info
285
+// Not working O
286
+//#define XY_FREQUENCY_LIMIT  15
287
+
288
+// Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
289
+// of the buffer and all stops. This should not be much greater than zero and should only be changed
290
+// if unwanted behavior is observed on a user's machine when running at very slow speeds.
291
+#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
292
+
293
+// Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
294
+#define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
295
+
296
+// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
297
+#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])
298
+
299
+// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
300
+//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
301
+
302
+// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
303
+//#define DIGIPOT_I2C
304
+// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
305
+#define DIGIPOT_I2C_NUM_CHANNELS 8
306
+// actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
307
+#define DIGIPOT_I2C_MOTOR_CURRENTS {1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0}
308
+
309
+//===========================================================================
310
+//=============================Additional Features===========================
311
+//===========================================================================
312
+
313
+#define ENCODER_RATE_MULTIPLIER         // If defined, certain menu edit operations automatically multiply the steps when the encoder is moved quickly
314
+#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
315
+#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
316
+
317
+//#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/
318
+#define CHDK_DELAY 50 //How long in ms the pin should stay HIGH before going LOW again
319
+
320
+// @section lcd
321
+
322
+#if ENABLED(SDSUPPORT)
323
+
324
+  // Some RAMPS and other boards don't detect when an SD card is inserted. You can work
325
+  // around this by connecting a push button or single throw switch to the pin defined
326
+  // as SD_DETECT_PIN in your board's pins definitions.
327
+  // This setting should be disabled unless you are using a push button, pulling the pin to ground.
328
+  // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
329
+  #define SD_DETECT_INVERTED
330
+
331
+  #define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
332
+  #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
333
+
334
+  #define SDCARD_RATHERRECENTFIRST  //reverse file order of sd card menu display. Its sorted practically after the file system block order.
335
+  // 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.
336
+  // using:
337
+  #define MENU_ADDAUTOSTART
338
+
339
+  // Show a progress bar on HD44780 LCDs for SD printing
340
+  //#define LCD_PROGRESS_BAR
341
+
342
+  #if ENABLED(LCD_PROGRESS_BAR)
343
+    // Amount of time (ms) to show the bar
344
+    #define PROGRESS_BAR_BAR_TIME 2000
345
+    // Amount of time (ms) to show the status message
346
+    #define PROGRESS_BAR_MSG_TIME 3000
347
+    // Amount of time (ms) to retain the status message (0=forever)
348
+    #define PROGRESS_MSG_EXPIRE   0
349
+    // Enable this to show messages for MSG_TIME then hide them
350
+    //#define PROGRESS_MSG_ONCE
351
+  #endif
352
+
353
+  // This allows hosts to request long names for files and folders with M33
354
+  #define LONG_FILENAME_HOST_SUPPORT
355
+
356
+  // This option allows you to abort SD printing when any endstop is triggered.
357
+  // This feature must be enabled with "M540 S1" or from the LCD menu.
358
+  // To have any effect, endstops must be enabled during SD printing.
359
+  // With ENDSTOPS_ONLY_FOR_HOMING you must send "M120" to enable endstops.
360
+  //#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
361
+
362
+#endif // SDSUPPORT
363
+
364
+// for dogm lcd displays you can choose some additional fonts:
365
+#if ENABLED(DOGLCD)
366
+  // save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
367
+  // we don't have a big font for Cyrillic, Kana
368
+  //#define USE_BIG_EDIT_FONT
369
+
370
+  // If you have spare 2300Byte of progmem and want to use a
371
+  // smaller font on the Info-screen uncomment the next line.
372
+  #define USE_SMALL_INFOFONT
373
+#endif // DOGLCD
374
+
375
+// @section more
376
+
377
+// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
378
+#define USE_WATCHDOG
379
+
380
+#if ENABLED(USE_WATCHDOG)
381
+  // If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
382
+  // The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
383
+  //  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
384
+  //#define WATCHDOG_RESET_MANUAL
385
+#endif
386
+
387
+// @section lcd
388
+
389
+// Babystepping enables the user to control the axis in tiny amounts, independently from the normal printing process
390
+// it can e.g. be used to change z-positions in the print startup phase in real-time
391
+// does not respect endstops!
392
+//#define BABYSTEPPING
393
+#if ENABLED(BABYSTEPPING)
394
+  #define BABYSTEP_XY  //not only z, but also XY in the menu. more clutter, more functions
395
+                       //not implemented for deltabots!
396
+  #define BABYSTEP_INVERT_Z false  //true for inverse movements in Z
397
+  #define BABYSTEP_MULTIPLICATOR 1 //faster movements
398
+#endif
399
+
400
+// @section extruder
401
+
402
+// extruder advance constant (s2/mm3)
403
+//
404
+// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
405
+//
406
+// Hooke's law says:    force = k * distance
407
+// Bernoulli's principle says:  v ^ 2 / 2 + g . h + pressure / density = constant
408
+// so: v ^ 2 is proportional to number of steps we advance the extruder
409
+//#define ADVANCE
410
+
411
+#if ENABLED(ADVANCE)
412
+  #define EXTRUDER_ADVANCE_K .0
413
+  #define D_FILAMENT 2.85
414
+#endif
415
+
416
+// @section extras
417
+
418
+// Arc interpretation settings:
419
+#define MM_PER_ARC_SEGMENT 1
420
+#define N_ARC_CORRECTION 25
421
+
422
+const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
423
+
424
+// @section temperature
425
+
426
+// Control heater 0 and heater 1 in parallel.
427
+//#define HEATERS_PARALLEL
428
+
429
+//===========================================================================
430
+//================================= Buffers =================================
431
+//===========================================================================
432
+
433
+// @section hidden
434
+
435
+// The number of linear motions that can be in the plan at any give time.
436
+// 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.
437
+#if ENABLED(SDSUPPORT)
438
+  #define BLOCK_BUFFER_SIZE 16   // SD,LCD,Buttons take more memory, block buffer needs to be smaller
439
+#else
440
+  #define BLOCK_BUFFER_SIZE 16 // maximize block buffer
441
+#endif
442
+
443
+// @section more
444
+
445
+//The ASCII buffer for receiving from the serial:
446
+#define MAX_CMD_SIZE 96
447
+#define BUFSIZE 4
448
+
449
+// Bad Serial-connections can miss a received command by sending an 'ok'
450
+// Therefore some clients abort after 30 seconds in a timeout.
451
+// Some other clients start sending commands while receiving a 'wait'.
452
+// This "wait" is only sent when the buffer is empty. 1 second is a good value here.
453
+//#define NO_TIMEOUTS 1000 // Milliseconds
454
+
455
+// Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary.
456
+//#define ADVANCED_OK
457
+
458
+// @section fwretract
459
+
460
+// Firmware based and LCD controlled retract
461
+// M207 and M208 can be used to define parameters for the retraction.
462
+// The retraction can be called by the slicer using G10 and G11
463
+// until then, intended retractions can be detected by moves that only extrude and the direction.
464
+// the moves are than replaced by the firmware controlled ones.
465
+
466
+//#define FWRETRACT  //ONLY PARTIALLY TESTED
467
+#if ENABLED(FWRETRACT)
468
+  #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
469
+  #define RETRACT_LENGTH 3               //default retract length (positive mm)
470
+  #define RETRACT_LENGTH_SWAP 13         //default swap retract length (positive mm), for extruder change
471
+  #define RETRACT_FEEDRATE 45            //default feedrate for retracting (mm/s)
472
+  #define RETRACT_ZLIFT 0                //default retract Z-lift
473
+  #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
474
+  #define RETRACT_RECOVER_LENGTH_SWAP 0  //default additional swap recover length (mm, added to retract length when recovering from extruder change)
475
+  #define RETRACT_RECOVER_FEEDRATE 8     //default feedrate for recovering from retraction (mm/s)
476
+#endif
477
+
478
+// Add support for experimental filament exchange support M600; requires display
479
+#if ENABLED(ULTIPANEL)
480
+  //#define FILAMENTCHANGEENABLE
481
+  #if ENABLED(FILAMENTCHANGEENABLE)
482
+    #define FILAMENTCHANGE_XPOS 3
483
+    #define FILAMENTCHANGE_YPOS 3
484
+    #define FILAMENTCHANGE_ZADD 10
485
+    #define FILAMENTCHANGE_FIRSTRETRACT -2
486
+    #define FILAMENTCHANGE_FINALRETRACT -100
487
+    #define AUTO_FILAMENT_CHANGE                //This extrude filament until you press the button on LCD
488
+    #define AUTO_FILAMENT_CHANGE_LENGTH 0.04    //Extrusion length on automatic extrusion loop
489
+    #define AUTO_FILAMENT_CHANGE_FEEDRATE 300   //Extrusion feedrate (mm/min) on automatic extrusion loop
490
+  #endif
491
+#endif
492
+
493
+/******************************************************************************\
494
+ * enable this section if you have TMC26X motor drivers.
495
+ * you need to import the TMC26XStepper library into the Arduino IDE for this
496
+ ******************************************************************************/
497
+
498
+// @section tmc
499
+
500
+//#define HAVE_TMCDRIVER
501
+#if ENABLED(HAVE_TMCDRIVER)
502
+
503
+  //#define X_IS_TMC
504
+  #define X_MAX_CURRENT 1000  //in mA
505
+  #define X_SENSE_RESISTOR 91 //in mOhms
506
+  #define X_MICROSTEPS 16     //number of microsteps
507
+
508
+  //#define X2_IS_TMC
509
+  #define X2_MAX_CURRENT 1000  //in mA
510
+  #define X2_SENSE_RESISTOR 91 //in mOhms
511
+  #define X2_MICROSTEPS 16     //number of microsteps
512
+
513
+  //#define Y_IS_TMC
514
+  #define Y_MAX_CURRENT 1000  //in mA
515
+  #define Y_SENSE_RESISTOR 91 //in mOhms
516
+  #define Y_MICROSTEPS 16     //number of microsteps
517
+
518
+  //#define Y2_IS_TMC
519
+  #define Y2_MAX_CURRENT 1000  //in mA
520
+  #define Y2_SENSE_RESISTOR 91 //in mOhms
521
+  #define Y2_MICROSTEPS 16     //number of microsteps
522
+
523
+  //#define Z_IS_TMC
524
+  #define Z_MAX_CURRENT 1000  //in mA
525
+  #define Z_SENSE_RESISTOR 91 //in mOhms
526
+  #define Z_MICROSTEPS 16     //number of microsteps
527
+
528
+  //#define Z2_IS_TMC
529
+  #define Z2_MAX_CURRENT 1000  //in mA
530
+  #define Z2_SENSE_RESISTOR 91 //in mOhms
531
+  #define Z2_MICROSTEPS 16     //number of microsteps
532
+
533
+  //#define E0_IS_TMC
534
+  #define E0_MAX_CURRENT 1000  //in mA
535
+  #define E0_SENSE_RESISTOR 91 //in mOhms
536
+  #define E0_MICROSTEPS 16     //number of microsteps
537
+
538
+  //#define E1_IS_TMC
539
+  #define E1_MAX_CURRENT 1000  //in mA
540
+  #define E1_SENSE_RESISTOR 91 //in mOhms
541
+  #define E1_MICROSTEPS 16     //number of microsteps
542
+
543
+  //#define E2_IS_TMC
544
+  #define E2_MAX_CURRENT 1000  //in mA
545
+  #define E2_SENSE_RESISTOR 91 //in mOhms
546
+  #define E2_MICROSTEPS 16     //number of microsteps
547
+
548
+  //#define E3_IS_TMC
549
+  #define E3_MAX_CURRENT 1000  //in mA
550
+  #define E3_SENSE_RESISTOR 91 //in mOhms
551
+  #define E3_MICROSTEPS 16     //number of microsteps
552
+
553
+#endif
554
+
555
+/******************************************************************************\
556
+ * enable this section if you have L6470  motor drivers.
557
+ * you need to import the L6470 library into the Arduino IDE for this
558
+ ******************************************************************************/
559
+
560
+// @section l6470
561
+
562
+//#define HAVE_L6470DRIVER
563
+#if ENABLED(HAVE_L6470DRIVER)
564
+
565
+  //#define X_IS_L6470
566
+  #define X_MICROSTEPS 16     //number of microsteps
567
+  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
568
+  #define X_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
569
+  #define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
570
+
571
+  //#define X2_IS_L6470
572
+  #define X2_MICROSTEPS 16     //number of microsteps
573
+  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
574
+  #define X2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
575
+  #define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
576
+
577
+  //#define Y_IS_L6470
578
+  #define Y_MICROSTEPS 16     //number of microsteps
579
+  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
580
+  #define Y_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
581
+  #define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
582
+
583
+  //#define Y2_IS_L6470
584
+  #define Y2_MICROSTEPS 16     //number of microsteps
585
+  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
586
+  #define Y2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
587
+  #define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
588
+
589
+  //#define Z_IS_L6470
590
+  #define Z_MICROSTEPS 16     //number of microsteps
591
+  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
592
+  #define Z_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
593
+  #define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
594
+
595
+  //#define Z2_IS_L6470
596
+  #define Z2_MICROSTEPS 16     //number of microsteps
597
+  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
598
+  #define Z2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
599
+  #define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
600
+
601
+  //#define E0_IS_L6470
602
+  #define E0_MICROSTEPS 16     //number of microsteps
603
+  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
604
+  #define E0_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
605
+  #define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
606
+
607
+  //#define E1_IS_L6470
608
+  #define E1_MICROSTEPS 16     //number of microsteps
609
+  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
610
+  #define E1_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
611
+  #define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
612
+
613
+  //#define E2_IS_L6470
614
+  #define E2_MICROSTEPS 16     //number of microsteps
615
+  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
616
+  #define E2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
617
+  #define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
618
+
619
+  //#define E3_IS_L6470
620
+  #define E3_MICROSTEPS 16     //number of microsteps
621
+  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
622
+  #define E3_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
623
+  #define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
624
+
625
+#endif
626
+
627
+#include "Conditionals.h"
628
+#include "SanityCheck.h"
629
+
630
+#endif //CONFIGURATION_ADV_H

+ 8
- 0
Marlin/example_configurations/Hephestos_2/readme.md Näytä tiedosto

@@ -0,0 +1,8 @@
1
+# Example Configuration for BQ [Hephestos 2](http://www.bq.com/uk/hephestos-2)
2
+This configuration file is based on the original configuration file shipped with the heavily modified Marlin fork by BQ. The original firmware and configuration file can be found at [BQ Github repository](https://github.com/bq/Marlin).
3
+
4
+NOTE: The look and feel of the Hephestos 2 while navigating the LCD menu will change by using the original Marlin firmware.
5
+
6
+## Changelog
7
+ * 2016/03/01 - Initial release
8
+ * 2016/03/21 - Activated four point auto leveling by default; updated miscellaneous z-probe values

+ 192
- 115
Marlin/example_configurations/K8200/Configuration.h Näytä tiedosto

@@ -1,7 +1,7 @@
1
-// Example configuration file for Vellemann K8200
1
+// Sample configuration file for Vellemann K8200
2 2
 // tested on K8200 with VM8201 (Display)
3
-// and Arduino 1.6.1 (Win) by @CONSULitAS, 2015-04-14
4
-// https://github.com/CONSULitAS/Marlin-K8200/archive/K8200_stable_2015-04-14.zip
3
+// and Arduino 1.6.8 (Mac) by @CONSULitAS, 2016-02-21
4
+// https://github.com/CONSULitAS/Marlin-K8200/archive/K8200_stable_2016-02-21.zip
5 5
 
6 6
 #ifndef CONFIGURATION_H
7 7
 #define CONFIGURATION_H
@@ -52,7 +52,7 @@ Here are some standard links for getting your machine calibrated:
52 52
 // User-specified version info of this build to display in [Pronterface, etc] terminal window during
53 53
 // startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
54 54
 // build by the user have been successfully uploaded into firmware.
55
-#define STRING_CONFIG_H_AUTHOR "(K8200, CONSULitAS)" // Who made the changes.
55
+#define STRING_CONFIG_H_AUTHOR "(K8200, @CONSULitAS)" // Who made the changes.
56 56
 #define SHOW_BOOTSCREEN
57 57
 #define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
58 58
 //#define STRING_SPLASH_LINE2 STRING_DISTRIBUTION_DATE // will be shown during bootup in line 2
@@ -80,11 +80,11 @@ Here are some standard links for getting your machine calibrated:
80 80
 
81 81
 // Optional custom name for your RepStrap or other custom machine
82 82
 // Displayed in the LCD "Ready" message
83
-//#define CUSTOM_MACHINE_NAME "3D Printer"
83
+#define CUSTOM_MACHINE_NAME "K8200"
84 84
 
85 85
 // Define this to set a unique identifier for this printer, (Used by some programs to differentiate between machines)
86 86
 // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4)
87
-//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
87
+#define MACHINE_UUID "2b7dea3b-844e-4ab1-aa96-bb6406607d6e" // K8200 standard config with VM8201 (Display)
88 88
 
89 89
 // This defines the number of extruders
90 90
 // :[1,2,3,4]
@@ -115,6 +115,7 @@ Here are some standard links for getting your machine calibrated:
115 115
 //--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
116 116
 //
117 117
 //// Temperature sensor settings:
118
+// -3 is thermocouple with MAX31855 (only for sensor 0)
118 119
 // -2 is thermocouple with MAX6675 (only for sensor 0)
119 120
 // -1 is thermocouple with AD595
120 121
 // 0 is not used
@@ -134,6 +135,7 @@ Here are some standard links for getting your machine calibrated:
134 135
 // 13 is 100k Hisens 3950  1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
135 136
 // 20 is the PT100 circuit found in the Ultimainboard V2.x
136 137
 // 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
138
+// 70 is the 100K thermistor found in the bq Hephestos 2
137 139
 //
138 140
 //    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
139 141
 //                          (but gives greater accuracy and more stable PID)
@@ -149,7 +151,7 @@ Here are some standard links for getting your machine calibrated:
149 151
 //     Use it for Testing or Development purposes. NEVER for production machine.
150 152
 //#define DUMMY_THERMISTOR_998_VALUE 25
151 153
 //#define DUMMY_THERMISTOR_999_VALUE 100
152
-// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
154
+// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-3': "Thermocouple + MAX31855 (only for sensor 0)", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
153 155
 #define TEMP_SENSOR_0 5
154 156
 #define TEMP_SENSOR_1 0
155 157
 #define TEMP_SENSOR_2 0
@@ -183,14 +185,9 @@ Here are some standard links for getting your machine calibrated:
183 185
 #define HEATER_3_MAXTEMP 275
184 186
 #define BED_MAXTEMP 150
185 187
 
186
-// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
187
-// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
188
-// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
189
-//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
190
-
191 188
 // If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
192
-//#define EXTRUDER_WATTS (12.0*12.0/6.7) //  P=I^2/R
193
-//#define BED_WATTS (12.0*12.0/1.1)      // P=I^2/R
189
+//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
190
+//#define BED_WATTS (12.0*12.0/1.1)      // P=U^2/R
194 191
 
195 192
 //===========================================================================
196 193
 //============================= PID Settings ================================
@@ -212,11 +209,26 @@ Here are some standard links for getting your machine calibrated:
212 209
   #define PID_INTEGRAL_DRIVE_MAX PID_MAX  //limit for the integral term
213 210
   #define K1 0.95 //smoothing factor within the PID
214 211
 
212
+  // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
213
+  // Ultimaker
214
+  //#define  DEFAULT_Kp 22.2
215
+  //#define  DEFAULT_Ki 1.08
216
+  //#define  DEFAULT_Kd 114
217
+
218
+  // MakerGear
219
+  //#define  DEFAULT_Kp 7.0
220
+  //#define  DEFAULT_Ki 0.1
221
+  //#define  DEFAULT_Kd 12
222
+
223
+  // Mendel Parts V9 on 12V
224
+  //#define  DEFAULT_Kp 63.0
225
+  //#define  DEFAULT_Ki 2.25
226
+  //#define  DEFAULT_Kd 440
227
+
215 228
   // Vellemann K8200 Extruder - calculated with PID Autotune and tested
216 229
   #define  DEFAULT_Kp 24.29
217 230
   #define  DEFAULT_Ki 1.58
218 231
   #define  DEFAULT_Kd 93.51
219
-
220 232
 #endif // PIDTEMP
221 233
 
222 234
 //===========================================================================
@@ -231,7 +243,7 @@ Here are some standard links for getting your machine calibrated:
231 243
 // If your configuration is significantly different than this and you don't understand the issues involved, you probably
232 244
 // shouldn't use bed PID until someone else verifies your hardware works.
233 245
 // If this is enabled, find your own PID constants below.
234
-//#define PIDTEMPBED
246
+#define PIDTEMPBED
235 247
 
236 248
 //#define BED_LIMIT_SWITCHING
237 249
 
@@ -247,13 +259,25 @@ Here are some standard links for getting your machine calibrated:
247 259
 
248 260
   #define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
249 261
 
250
-  //Vellemann K8200 PCB heatbed with standard PCU at 60 degreesC - calculated with PID Autotune and tested
262
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
263
+  //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
264
+  //#define  DEFAULT_bedKp 10.00
265
+  //#define  DEFAULT_bedKi .023
266
+  //#define  DEFAULT_bedKd 305.4
267
+
268
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
251 269
   //from pidautotune
270
+  //#define  DEFAULT_bedKp 97.1
271
+  //#define  DEFAULT_bedKi 1.41
272
+  //#define  DEFAULT_bedKd 1675.16
273
+
274
+  // FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
275
+
276
+  // Vellemann K8200 PCB heatbed with standard PCU at 60 degreesC - calculated with PID Autotune and tested
277
+  // from pidautotune
252 278
   #define  DEFAULT_bedKp 341.88
253 279
   #define  DEFAULT_bedKi 25.32
254 280
   #define  DEFAULT_bedKd 1153.89
255
-
256
-  // FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
257 281
 #endif // PIDTEMPBED
258 282
 
259 283
 // @section extruder
@@ -272,16 +296,15 @@ Here are some standard links for getting your machine calibrated:
272 296
 //===========================================================================
273 297
 
274 298
 /**
275
- * Thermal Runaway Protection protects your printer from damage and fire if a
299
+ * Thermal Protection protects your printer from damage and fire if a
276 300
  * thermistor falls out or temperature sensors fail in any way.
277 301
  *
278 302
  * The issue: If a thermistor falls out or a temperature sensor fails,
279 303
  * Marlin can no longer sense the actual temperature. Since a disconnected
280 304
  * thermistor reads as a low temperature, the firmware will keep the heater on.
281 305
  *
282
- * The solution: Once the temperature reaches the target, start observing.
283
- * If the temperature stays too far below the target (hysteresis) for too long,
284
- * the firmware will halt as a safety precaution.
306
+ * If you get "Thermal Runaway" or "Heating failed" errors the
307
+ * details can be tuned in Configuration_adv.h
285 308
  */
286 309
 
287 310
 #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
@@ -329,10 +352,52 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
329 352
 #define DISABLE_MAX_ENDSTOPS
330 353
 //#define DISABLE_MIN_ENDSTOPS
331 354
 
332
-// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
333
-// This only affects a Z probe endstop if you have separate Z min endstop as well and have
334
-// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
335
-// this has no effect.
355
+//===========================================================================
356
+//============================= Z Probe Options =============================
357
+//===========================================================================
358
+
359
+// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
360
+// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
361
+//
362
+// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
363
+//
364
+// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
365
+// Example: To park the head outside the bed area when homing with G28.
366
+//
367
+// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
368
+//
369
+// For a servo-based Z probe, you must set up servo support below, including
370
+// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
371
+//
372
+// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
373
+// - Use 5V for powered (usu. inductive) sensors.
374
+// - Otherwise connect:
375
+//   - normally-closed switches to GND and D32.
376
+//   - normally-open switches to 5V and D32.
377
+//
378
+// Normally-closed switches are advised and are the default.
379
+//
380
+// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
381
+// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
382
+// default pin for all RAMPS-based boards. Some other boards map differently.
383
+// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
384
+//
385
+// WARNING:
386
+// Setting the wrong pin may have unexpected and potentially disastrous consequences.
387
+// Use with caution and do your homework.
388
+//
389
+//#define Z_MIN_PROBE_ENDSTOP
390
+
391
+// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
392
+// The Z_MIN_PIN will then be used for both Z-homing and probing.
393
+#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
394
+
395
+// To use a probe you must enable one of the two options above!
396
+
397
+// This option disables the use of the Z_MIN_PROBE_PIN
398
+// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
399
+// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
400
+// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
336 401
 //#define DISABLE_Z_MIN_PROBE_ENDSTOP
337 402
 
338 403
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
@@ -342,11 +407,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
342 407
 #define Z_ENABLE_ON 0
343 408
 #define E_ENABLE_ON 0 // For all extruders
344 409
 
345
-// Disables axis when it's not being used.
410
+// Disables axis stepper immediately when it's not being used.
346 411
 // WARNING: When motors turn off there is a chance of losing position accuracy!
347 412
 #define DISABLE_X false
348 413
 #define DISABLE_Y false
349
-#define DISABLE_Z true
414
+#define DISABLE_Z false // not for K8200 -> looses Steps
415
+// Warn on display about possibly reduced accuracy
416
+//#define DISABLE_REDUCED_ACCURACY_WARNING
350 417
 
351 418
 // @section extruder
352 419
 
@@ -357,7 +424,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
357 424
 
358 425
 // Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way.
359 426
 #define INVERT_X_DIR false
360
-#define INVERT_Y_DIR false
427
+#define INVERT_Y_DIR false // was true -> why for K8200?
361 428
 #define INVERT_Z_DIR false
362 429
 
363 430
 // @section extruder
@@ -369,6 +436,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
369 436
 #define INVERT_E3_DIR true
370 437
 
371 438
 // @section homing
439
+//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
440
+                                    // Be sure you have this distance over your Z_MAX_POS in case.
372 441
 
373 442
 // ENDSTOP SETTINGS:
374 443
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
@@ -404,24 +473,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
404 473
 #endif
405 474
 
406 475
 //===========================================================================
407
-//=========================== Manual Bed Leveling ===========================
476
+//============================ Mesh Bed Leveling ============================
408 477
 //===========================================================================
409 478
 
410
-//#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
411 479
 //#define MESH_BED_LEVELING    // Enable mesh bed leveling.
412 480
 
413
-#if ENABLED(MANUAL_BED_LEVELING)
414
-  #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
415
-#endif  // MANUAL_BED_LEVELING
416
-
417 481
 #if ENABLED(MESH_BED_LEVELING)
418 482
   #define MESH_MIN_X 10
419
-  #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
483
+  #define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
420 484
   #define MESH_MIN_Y 10
421
-  #define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
485
+  #define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
422 486
   #define MESH_NUM_X_POINTS 3  // Don't use more than 7 points per axis, implementation limited.
423 487
   #define MESH_NUM_Y_POINTS 3
424 488
   #define MESH_HOME_SEARCH_Z 4  // Z after Home, bed somewhere below but above 0.0.
489
+
490
+  //#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
491
+
492
+  #if ENABLED(MANUAL_BED_LEVELING)
493
+    #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
494
+  #endif  // MANUAL_BED_LEVELING
495
+
425 496
 #endif  // MESH_BED_LEVELING
426 497
 
427 498
 //===========================================================================
@@ -432,7 +503,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
432 503
 
433 504
 //#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
434 505
 //#define DEBUG_LEVELING_FEATURE
435
-#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
506
+#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
436 507
 
437 508
 #if ENABLED(AUTO_BED_LEVELING_FEATURE)
438 509
 
@@ -444,7 +515,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
444 515
   //   This mode is preferred because there are more measurements.
445 516
   //
446 517
   // - "3-point" mode
447
-  //   Probe 3 arbitrary points on the bed (that aren't colinear)
518
+  //   Probe 3 arbitrary points on the bed (that aren't collinear)
448 519
   //   You specify the XY coordinates of all 3 points.
449 520
 
450 521
   // Enable this to sample the bed in a grid (least squares solution).
@@ -458,7 +529,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
458 529
     #define FRONT_PROBE_BED_POSITION 20
459 530
     #define BACK_PROBE_BED_POSITION 170
460 531
 
461
-    #define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
532
+    #define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
462 533
 
463 534
     // Set the number of grid points per dimension.
464 535
     // You probably don't need more than 3 (squared=9).
@@ -466,25 +537,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
466 537
 
467 538
   #else  // !AUTO_BED_LEVELING_GRID
468 539
 
469
-      // Arbitrary points to probe.
470
-      // A simple cross-product is used to estimate the plane of the bed.
471
-      #define ABL_PROBE_PT_1_X 15
472
-      #define ABL_PROBE_PT_1_Y 180
473
-      #define ABL_PROBE_PT_2_X 15
474
-      #define ABL_PROBE_PT_2_Y 20
475
-      #define ABL_PROBE_PT_3_X 170
476
-      #define ABL_PROBE_PT_3_Y 20
540
+    // Arbitrary points to probe.
541
+    // A simple cross-product is used to estimate the plane of the bed.
542
+    #define ABL_PROBE_PT_1_X 15
543
+    #define ABL_PROBE_PT_1_Y 180
544
+    #define ABL_PROBE_PT_2_X 15
545
+    #define ABL_PROBE_PT_2_Y 20
546
+    #define ABL_PROBE_PT_3_X 170
547
+    #define ABL_PROBE_PT_3_Y 20
477 548
 
478 549
   #endif // AUTO_BED_LEVELING_GRID
479 550
 
480
-  // Offsets to the Z probe relative to the nozzle tip.
551
+  // Z Probe to nozzle (X,Y) offset, relative to (0, 0).
481 552
   // X and Y offsets must be integers.
482
-  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // Z probe to nozzle X offset: -left  +right
483
-  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Z probe to nozzle Y offset: -front +behind
484
-  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z probe to nozzle Z offset: -below (always!)
485
-
486
-  #define Z_RAISE_BEFORE_HOMING 4       // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
487
-                                        // Be sure you have this distance over your Z_MAX_POS in case.
553
+  //
554
+  // In the following example the X and Y offsets are both positive:
555
+  // #define X_PROBE_OFFSET_FROM_EXTRUDER 10
556
+  // #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
557
+  //
558
+  //    +-- BACK ---+
559
+  //    |           |
560
+  //  L |    (+) P  | R <-- probe (20,20)
561
+  //  E |           | I
562
+  //  F | (-) N (+) | G <-- nozzle (10,10)
563
+  //  T |           | H
564
+  //    |    (-)    | T
565
+  //    |           |
566
+  //    O-- FRONT --+
567
+  //  (0,0)
568
+  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // X offset: -left  [of the nozzle] +right
569
+  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Y offset: -front [of the nozzle] +behind
570
+  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z offset: -below [the nozzle] (always negative!)
488 571
 
489 572
   #define XY_TRAVEL_SPEED 8000         // X and Y axis travel speed between probes, in mm/min.
490 573
 
@@ -492,16 +575,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
492 575
   #define Z_RAISE_BETWEEN_PROBINGS 5  // How much the Z axis will be raised when traveling from between next probing points.
493 576
   #define Z_RAISE_AFTER_PROBING 15    // How much the Z axis will be raised after the last probing point.
494 577
 
495
-//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
496
-                                                                            // Useful to retract a deployable Z probe.
578
+  //#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
579
+                                                                             // Useful to retract a deployable Z probe.
497 580
 
498
-  //#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
581
+  // Probes are sensors/switches that need to be activated before they can be used
582
+  // and deactivated after the use.
583
+  // Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
584
+
585
+  // A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
586
+  // when the hardware endstops are active.
587
+  //#define FIX_MOUNTED_PROBE
588
+
589
+  // A Servo Probe can be defined in the servo section below.
590
+
591
+  // An Allen Key Probe is currently predefined only in the delta example configurations.
592
+
593
+  //#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
499 594
   //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
500 595
 
501
-// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
502
-// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
596
+  // If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
597
+  // it is highly recommended you leave Z_SAFE_HOMING enabled!
503 598
 
504
-  #define Z_SAFE_HOMING   // This feature is meant to avoid Z homing with Z probe outside the bed area.
599
+  #define Z_SAFE_HOMING   // Use the z-min-probe for homing to z-min - not the z-min-endstop.
600
+                          // This feature is meant to avoid Z homing with Z probe outside the bed area.
505 601
                           // When defined, it will:
506 602
                           // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
507 603
                           // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
@@ -515,37 +611,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
515 611
 
516 612
   #endif
517 613
 
518
-  // Support for a dedicated Z probe endstop separate from the Z min endstop.
519
-  // If you would like to use both a Z probe and a Z min endstop together,
520
-  // uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
521
-  // If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
522
-  // Example: To park the head outside the bed area when homing with G28.
523
-  //
524
-  // WARNING:
525
-  // The Z min endstop will need to set properly as it would without a Z probe
526
-  // to prevent head crashes and premature stopping during a print.
527
-  //
528
-  // To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
529
-  // defined in the pins_XXXXX.h file for your control board.
530
-  // If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
531
-  // Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
532
-  // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
533
-  // in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
534
-  // otherwise connect to ground and D32 for normally closed configuration
535
-  // and 5V and D32 for normally open configurations.
536
-  // Normally closed configuration is advised and assumed.
537
-  // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
538
-  // Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
539
-  // Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
540
-  // D32 is currently selected in the RAMPS 1.3/1.4 pin file.
541
-  // All other boards will need changes to the respective pins_XXXXX.h file.
542
-  //
543
-  // WARNING:
544
-  // Setting the wrong pin may have unexpected and potentially disastrous outcomes.
545
-  // Use with caution and do your homework.
546
-  //
547
-  //#define Z_MIN_PROBE_ENDSTOP
548
-
549 614
 #endif // AUTO_BED_LEVELING_FEATURE
550 615
 
551 616
 
@@ -579,7 +644,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
579 644
 #define DEFAULT_MAX_ACCELERATION      {9000,9000,100,10000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
580 645
 
581 646
 #define DEFAULT_ACCELERATION          1000    // X, Y, Z and E acceleration in mm/s^2 for printing moves
582
-#define DEFAULT_RETRACT_ACCELERATION  1000    // E acceleration in mm/s^2 for retracts
647
+#define DEFAULT_RETRACT_ACCELERATION  1000   // E acceleration in mm/s^2 for retracts
583 648
 #define DEFAULT_TRAVEL_ACCELERATION   1000    // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
584 649
 
585 650
 // The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
@@ -620,6 +685,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
620 685
 #endif
621 686
 
622 687
 //
688
+// Host Keepalive
689
+//
690
+// By default Marlin will send a busy status message to the host
691
+// every 2 seconds when it can't accept commands.
692
+//
693
+//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
694
+
695
+//
623 696
 // M100 Free Memory Watcher
624 697
 //
625 698
 //#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
@@ -639,26 +712,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
639 712
 // @section lcd
640 713
 
641 714
 // Define your display language below. Replace (en) with your language code and uncomment.
642
-// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
715
+// en, pl, fr, de, es, ru, bg, it, pt, pt_utf8, pt-br, pt-br_utf8, fi, an, nl, ca, eu, kana, kana_utf8, cn, cz, test
643 716
 // See also language.h
644 717
 #define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
645 718
 
646 719
 // Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
647 720
 // To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
648
-// See also documentation/LCDLanguageFont.md
721
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
649 722
   #define DISPLAY_CHARSET_HD44780_JAPAN        // K8200: for Display VM8201 // this is the most common hardware
650 723
   //#define DISPLAY_CHARSET_HD44780_WESTERN
651 724
   //#define DISPLAY_CHARSET_HD44780_CYRILLIC
652 725
 
653 726
 //#define ULTRA_LCD  //general LCD support, also 16x2
654 727
 //#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
655
-//#define SDSUPPORT // Enable SD Card Support in Hardware Console
656
-// Changed behaviour! If you need SDSUPPORT uncomment it!
657
-//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
658
-//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
728
+#define SDSUPPORT // Enable SD Card Support in Hardware Console
729
+                    // Changed behaviour! If you need SDSUPPORT uncomment it!
730
+//#define SPI_SPEED SPI_HALF_SPEED // (also SPI_QUARTER_SPEED, SPI_EIGHTH_SPEED) Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
659 731
 //#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
660 732
 //#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
661 733
 //#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
734
+//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
662 735
 #define ULTIMAKERCONTROLLER // K8200: for Display VM8201 // as available from the Ultimaker online store.
663 736
 //#define ULTIPANEL  //the UltiPanel as on Thingiverse
664 737
 //#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
@@ -675,13 +748,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
675 748
 
676 749
 // The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
677 750
 // http://panucatt.com
678
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
751
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
679 752
 //#define VIKI2
680 753
 //#define miniVIKI
681 754
 
682 755
 // This is a new controller currently under development.  https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
683 756
 //
684
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
757
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
685 758
 //#define ELB_FULL_GRAPHIC_CONTROLLER
686 759
 //#define SD_DETECT_INVERTED
687 760
 
@@ -696,7 +769,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
696 769
 // The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
697 770
 // http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
698 771
 //
699
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
772
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
700 773
 //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
701 774
 
702 775
 // The RepRapWorld REPRAPWORLD_KEYPAD v1.1
@@ -719,6 +792,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
719 792
 
720 793
 //#define LCD_I2C_SAINSMART_YWROBOT
721 794
 
795
+//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
796
+
722 797
 // PANELOLU2 LCD with status LEDs, separate encoder and click inputs
723 798
 //
724 799
 // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
@@ -732,7 +807,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
732 807
 //#define LCD_I2C_VIKI
733 808
 
734 809
 // SSD1306 OLED generic display support
735
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
810
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
736 811
 //#define U8GLIB_SSD1306
737 812
 
738 813
 // Shift register panels
@@ -744,7 +819,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
744 819
 
745 820
 // @section extras
746 821
 
747
-// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
822
+// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
748 823
 //#define FAST_PWM_FAN
749 824
 
750 825
 // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
@@ -826,19 +901,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
826 901
 // Uncomment below to enable
827 902
 //#define FILAMENT_SENSOR
828 903
 
829
-#define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
830
-#define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
831
-
832 904
 #define DEFAULT_NOMINAL_FILAMENT_DIA 3.00  //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
833
-#define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
834
-#define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
835
-#define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
836 905
 
837
-//defines used in the code
838
-#define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
906
+#if ENABLED(FILAMENT_SENSOR)
907
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
908
+  #define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
839 909
 
840
-//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
841
-//#define FILAMENT_LCD_DISPLAY
910
+  #define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
911
+  #define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
912
+  #define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
913
+
914
+  #define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
915
+
916
+  //When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
917
+  //#define FILAMENT_LCD_DISPLAY
918
+#endif
842 919
 
843 920
 #include "Configuration_adv.h"
844 921
 #include "thermistortables.h"

+ 101
- 71
Marlin/example_configurations/K8200/Configuration_adv.h Näytä tiedosto

@@ -1,3 +1,8 @@
1
+// Sample configuration file for Vellemann K8200
2
+// tested on K8200 with VM8201 (Display)
3
+// and Arduino 1.6.8 (Mac) by @CONSULitAS, 2016-02-21
4
+// https://github.com/CONSULitAS/Marlin-K8200/archive/K8200_stable_2016-02-21.zip
5
+
1 6
 #ifndef CONFIGURATION_ADV_H
2 7
 #define CONFIGURATION_ADV_H
3 8
 
@@ -17,35 +22,47 @@
17 22
 /**
18 23
  * Thermal Protection parameters
19 24
  */
25
+  /**
26
+   * Thermal Protection protects your printer from damage and fire if a
27
+   * thermistor falls out or temperature sensors fail in any way.
28
+   *
29
+   * The issue: If a thermistor falls out or a temperature sensor fails,
30
+   * Marlin can no longer sense the actual temperature. Since a disconnected
31
+   * thermistor reads as a low temperature, the firmware will keep the heater on.
32
+   *
33
+   * The solution: Once the temperature reaches the target, start observing.
34
+   * If the temperature stays too far below the target (hysteresis) for too long (period),
35
+   * the firmware will halt the machine as a safety precaution.
36
+   *
37
+   * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
38
+   */
20 39
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
21
-  #define THERMAL_PROTECTION_PERIOD 40        // Seconds
22
-  #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
40
+  #define THERMAL_PROTECTION_PERIOD 60        // Seconds
41
+  #define THERMAL_PROTECTION_HYSTERESIS 8     // Degrees Celsius
23 42
 
24 43
   /**
25 44
    * Whenever an M104 or M109 increases the target temperature the firmware will wait for the
26 45
    * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
27 46
    * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
28 47
    * but only if the current temperature is far enough below the target for a reliable test.
48
+   *
49
+   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
50
+   * WATCH_TEMP_INCREASE should not be below 2.
29 51
    */
30
-  #define WATCH_TEMP_PERIOD 16                // Seconds
52
+  #define WATCH_TEMP_PERIOD 30                // Seconds
31 53
   #define WATCH_TEMP_INCREASE 4               // Degrees Celsius
32 54
 #endif
33 55
 
56
+  /**
57
+   * Thermal Protection parameters for the bed
58
+   * are like the above for the hotends.
59
+   * WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
60
+   */
34 61
 #if ENABLED(THERMAL_PROTECTION_BED)
35 62
   #define THERMAL_PROTECTION_BED_PERIOD 20    // Seconds
36 63
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
37 64
 #endif
38 65
 
39
-/**
40
- * Automatic Temperature:
41
- * The hotend target temperature is calculated by all the buffered lines of gcode.
42
- * The maximum buffered steps/sec of the extruder motor is called "se".
43
- * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
44
- * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
45
- * mintemp and maxtemp. Turn this off by excuting M109 without F*
46
- * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
47
- * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
48
- */
49 66
 #if ENABLED(PIDTEMP)
50 67
   // this adds an experimental additional term to the heating power, proportional to the extrusion speed.
51 68
   // if Kc is chosen well, the additional required power due to increased melting should be compensated.
@@ -56,14 +73,16 @@
56 73
   #endif
57 74
 #endif
58 75
 
59
-
60
-//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
61
-//The maximum buffered steps/sec of the extruder motor are called "se".
62
-//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
63
-// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
64
-// you exit the value by any M109 without F*
65
-// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
66
-// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
76
+/**
77
+ * Automatic Temperature:
78
+ * The hotend target temperature is calculated by all the buffered lines of gcode.
79
+ * The maximum buffered steps/sec of the extruder motor is called "se".
80
+ * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
81
+ * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
82
+ * mintemp and maxtemp. Turn this off by executing M109 without F*
83
+ * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
84
+ * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
85
+ */
67 86
 #define AUTOTEMP
68 87
 #if ENABLED(AUTOTEMP)
69 88
   #define AUTOTEMP_OLDWEIGHT 0.98
@@ -101,12 +120,12 @@
101 120
 // When first starting the main fan, run it at full speed for the
102 121
 // given number of milliseconds.  This gets the fan spinning reliably
103 122
 // before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
104
-//#define FAN_KICKSTART_TIME 100
123
+#define FAN_KICKSTART_TIME 500
105 124
 
106 125
 // This defines the minimal speed for the main fan, run in PWM mode
107 126
 // to enable uncomment and set minimal PWM speed for reliable running (1-255)
108 127
 // if fan speed is [1 - (FAN_MIN_PWM-1)] it is set to FAN_MIN_PWM
109
-#define FAN_MIN_PWM 50 // K8200: fan stops running at about 35 to 40 (of 255)
128
+#define FAN_MIN_PWM 50
110 129
 
111 130
 // @section extruder
112 131
 
@@ -220,9 +239,9 @@
220 239
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
221 240
 #define X_HOME_BUMP_MM 5
222 241
 #define Y_HOME_BUMP_MM 5
223
-#define Z_HOME_BUMP_MM 3
224
-#define HOMING_BUMP_DIVISOR {2, 2, 4}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
225
-//#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
242
+#define Z_HOME_BUMP_MM 2
243
+#define HOMING_BUMP_DIVISOR {4, 4, 8}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
244
+#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
226 245
 
227 246
 // When G28 is called, this option will make Y home before X
228 247
 //#define HOME_Y_BEFORE_X
@@ -240,7 +259,13 @@
240 259
 #define INVERT_E_STEP_PIN false
241 260
 
242 261
 // Default stepper release if idle. Set to 0 to deactivate.
262
+// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
263
+// Time can be set by M18 and M84.
243 264
 #define DEFAULT_STEPPER_DEACTIVE_TIME 60
265
+#define DISABLE_INACTIVE_X true
266
+#define DISABLE_INACTIVE_Y true
267
+#define DISABLE_INACTIVE_Z true  // set to false if the nozzle will fall down on your printed part when print has finished.
268
+#define DISABLE_INACTIVE_E true
244 269
 
245 270
 #define DEFAULT_MINIMUMFEEDRATE       0.0     // minimum feedrate
246 271
 #define DEFAULT_MINTRAVELFEEDRATE     0.0
@@ -276,6 +301,9 @@
276 301
 // Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
277 302
 #define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
278 303
 
304
+// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
305
+//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
306
+
279 307
 // uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
280 308
 //#define DIGIPOT_I2C
281 309
 // Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
@@ -311,10 +339,10 @@
311 339
   #define SDCARD_RATHERRECENTFIRST  //reverse file order of sd card menu display. Its sorted practically after the file system block order.
312 340
   // 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.
313 341
   // using:
314
-  //#define MENU_ADDAUTOSTART
342
+  #define MENU_ADDAUTOSTART
315 343
 
316 344
   // Show a progress bar on HD44780 LCDs for SD printing
317
-  //#define LCD_PROGRESS_BAR
345
+  #define LCD_PROGRESS_BAR
318 346
 
319 347
   #if ENABLED(LCD_PROGRESS_BAR)
320 348
     // Amount of time (ms) to show the bar
@@ -328,7 +356,7 @@
328 356
   #endif
329 357
 
330 358
   // This allows hosts to request long names for files and folders with M33
331
-  //#define LONG_FILENAME_HOST_SUPPORT
359
+  #define LONG_FILENAME_HOST_SUPPORT
332 360
 
333 361
   // This option allows you to abort SD printing when any endstop is triggered.
334 362
   // This feature must be enabled with "M540 S1" or from the LCD menu.
@@ -349,17 +377,16 @@
349 377
   //#define USE_SMALL_INFOFONT
350 378
 #endif // DOGLCD
351 379
 
352
-
353 380
 // @section more
354 381
 
355 382
 // The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
356
-//#define USE_WATCHDOG
383
+#define USE_WATCHDOG
357 384
 
358 385
 #if ENABLED(USE_WATCHDOG)
359
-// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
360
-// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
361
-//  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
362
-//#define WATCHDOG_RESET_MANUAL
386
+  // If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
387
+  // The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
388
+  //  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
389
+  //#define WATCHDOG_RESET_MANUAL
363 390
 #endif
364 391
 
365 392
 // @section lcd
@@ -367,9 +394,10 @@
367 394
 // Babystepping enables the user to control the axis in tiny amounts, independently from the normal printing process
368 395
 // it can e.g. be used to change z-positions in the print startup phase in real-time
369 396
 // does not respect endstops!
370
-//#define BABYSTEPPING
397
+#define BABYSTEPPING
371 398
 #if ENABLED(BABYSTEPPING)
372 399
   #define BABYSTEP_XY  //not only z, but also XY in the menu. more clutter, more functions
400
+                       //not implemented for deltabots!
373 401
   #define BABYSTEP_INVERT_Z false  //true for inverse movements in Z
374 402
   #define BABYSTEP_MULTIPLICATOR 1 //faster movements
375 403
 #endif
@@ -388,7 +416,6 @@
388 416
 #if ENABLED(ADVANCE)
389 417
   #define EXTRUDER_ADVANCE_K .0
390 418
   #define D_FILAMENT 2.85
391
-  #define STEPS_MM_E 836
392 419
 #endif
393 420
 
394 421
 // @section extras
@@ -397,7 +424,7 @@
397 424
 #define MM_PER_ARC_SEGMENT 1
398 425
 #define N_ARC_CORRECTION 25
399 426
 
400
-const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
427
+const unsigned int dropsegments = 2; //everything with less than this number of steps will be ignored as move and joined with the next movement
401 428
 
402 429
 // @section temperature
403 430
 
@@ -415,7 +442,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
415 442
 #if ENABLED(SDSUPPORT)
416 443
   #define BLOCK_BUFFER_SIZE 16   // SD,LCD,Buttons take more memory, block buffer needs to be smaller
417 444
 #else
418
-  #define BLOCK_BUFFER_SIZE 16 // maximize block buffer
445
+  #define BLOCK_BUFFER_SIZE 32 // maximize block buffer
419 446
 #endif
420 447
 
421 448
 // @section more
@@ -462,12 +489,15 @@ const unsigned int dropsegments=5; //everything with less than this number of st
462 489
     #define FILAMENTCHANGE_ZADD 10
463 490
     #define FILAMENTCHANGE_FIRSTRETRACT -2
464 491
     #define FILAMENTCHANGE_FINALRETRACT -100
492
+    #define AUTO_FILAMENT_CHANGE                //This extrude filament until you press the button on LCD
493
+    #define AUTO_FILAMENT_CHANGE_LENGTH 0.04    //Extrusion length on automatic extrusion loop
494
+    #define AUTO_FILAMENT_CHANGE_FEEDRATE 300   //Extrusion feedrate (mm/min) on automatic extrusion loop
465 495
   #endif
466 496
 #endif
467 497
 
468 498
 /******************************************************************************\
469 499
  * enable this section if you have TMC26X motor drivers.
470
- * you need to import the TMC26XStepper library into the arduino IDE for this
500
+ * you need to import the TMC26XStepper library into the Arduino IDE for this
471 501
  ******************************************************************************/
472 502
 
473 503
 // @section tmc
@@ -475,52 +505,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
475 505
 //#define HAVE_TMCDRIVER
476 506
 #if ENABLED(HAVE_TMCDRIVER)
477 507
 
478
-//#define X_IS_TMC
508
+  //#define X_IS_TMC
479 509
   #define X_MAX_CURRENT 1000  //in mA
480 510
   #define X_SENSE_RESISTOR 91 //in mOhms
481 511
   #define X_MICROSTEPS 16     //number of microsteps
482 512
 
483
-//#define X2_IS_TMC
513
+  //#define X2_IS_TMC
484 514
   #define X2_MAX_CURRENT 1000  //in mA
485 515
   #define X2_SENSE_RESISTOR 91 //in mOhms
486 516
   #define X2_MICROSTEPS 16     //number of microsteps
487 517
 
488
-//#define Y_IS_TMC
518
+  //#define Y_IS_TMC
489 519
   #define Y_MAX_CURRENT 1000  //in mA
490 520
   #define Y_SENSE_RESISTOR 91 //in mOhms
491 521
   #define Y_MICROSTEPS 16     //number of microsteps
492 522
 
493
-//#define Y2_IS_TMC
523
+  //#define Y2_IS_TMC
494 524
   #define Y2_MAX_CURRENT 1000  //in mA
495 525
   #define Y2_SENSE_RESISTOR 91 //in mOhms
496 526
   #define Y2_MICROSTEPS 16     //number of microsteps
497 527
 
498
-//#define Z_IS_TMC
528
+  //#define Z_IS_TMC
499 529
   #define Z_MAX_CURRENT 1000  //in mA
500 530
   #define Z_SENSE_RESISTOR 91 //in mOhms
501 531
   #define Z_MICROSTEPS 16     //number of microsteps
502 532
 
503
-//#define Z2_IS_TMC
533
+  //#define Z2_IS_TMC
504 534
   #define Z2_MAX_CURRENT 1000  //in mA
505 535
   #define Z2_SENSE_RESISTOR 91 //in mOhms
506 536
   #define Z2_MICROSTEPS 16     //number of microsteps
507 537
 
508
-//#define E0_IS_TMC
538
+  //#define E0_IS_TMC
509 539
   #define E0_MAX_CURRENT 1000  //in mA
510 540
   #define E0_SENSE_RESISTOR 91 //in mOhms
511 541
   #define E0_MICROSTEPS 16     //number of microsteps
512 542
 
513
-//#define E1_IS_TMC
543
+  //#define E1_IS_TMC
514 544
   #define E1_MAX_CURRENT 1000  //in mA
515 545
   #define E1_SENSE_RESISTOR 91 //in mOhms
516 546
   #define E1_MICROSTEPS 16     //number of microsteps
517 547
 
518
-//#define E2_IS_TMC
548
+  //#define E2_IS_TMC
519 549
   #define E2_MAX_CURRENT 1000  //in mA
520 550
   #define E2_SENSE_RESISTOR 91 //in mOhms
521 551
   #define E2_MICROSTEPS 16     //number of microsteps
522 552
 
523
-//#define E3_IS_TMC
553
+  //#define E3_IS_TMC
524 554
   #define E3_MAX_CURRENT 1000  //in mA
525 555
   #define E3_SENSE_RESISTOR 91 //in mOhms
526 556
   #define E3_MICROSTEPS 16     //number of microsteps
@@ -529,7 +559,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
529 559
 
530 560
 /******************************************************************************\
531 561
  * enable this section if you have L6470  motor drivers.
532
- * you need to import the L6470 library into the arduino IDE for this
562
+ * you need to import the L6470 library into the Arduino IDE for this
533 563
  ******************************************************************************/
534 564
 
535 565
 // @section l6470
@@ -537,63 +567,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
537 567
 //#define HAVE_L6470DRIVER
538 568
 #if ENABLED(HAVE_L6470DRIVER)
539 569
 
540
-//#define X_IS_L6470
570
+  //#define X_IS_L6470
541 571
   #define X_MICROSTEPS 16     //number of microsteps
542
-  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
572
+  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
543 573
   #define X_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
544 574
   #define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
545 575
 
546
-//#define X2_IS_L6470
576
+  //#define X2_IS_L6470
547 577
   #define X2_MICROSTEPS 16     //number of microsteps
548
-  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
578
+  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
549 579
   #define X2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
550 580
   #define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
551 581
 
552
-//#define Y_IS_L6470
582
+  //#define Y_IS_L6470
553 583
   #define Y_MICROSTEPS 16     //number of microsteps
554
-  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
584
+  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
555 585
   #define Y_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
556 586
   #define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
557 587
 
558
-//#define Y2_IS_L6470
588
+  //#define Y2_IS_L6470
559 589
   #define Y2_MICROSTEPS 16     //number of microsteps
560
-  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
590
+  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
561 591
   #define Y2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
562 592
   #define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
563 593
 
564
-//#define Z_IS_L6470
594
+  //#define Z_IS_L6470
565 595
   #define Z_MICROSTEPS 16     //number of microsteps
566
-  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
596
+  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
567 597
   #define Z_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
568 598
   #define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
569 599
 
570
-//#define Z2_IS_L6470
600
+  //#define Z2_IS_L6470
571 601
   #define Z2_MICROSTEPS 16     //number of microsteps
572
-  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
602
+  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
573 603
   #define Z2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
574 604
   #define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
575 605
 
576
-//#define E0_IS_L6470
606
+  //#define E0_IS_L6470
577 607
   #define E0_MICROSTEPS 16     //number of microsteps
578
-  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
608
+  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
579 609
   #define E0_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
580 610
   #define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
581 611
 
582
-//#define E1_IS_L6470
612
+  //#define E1_IS_L6470
583 613
   #define E1_MICROSTEPS 16     //number of microsteps
584
-  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
614
+  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
585 615
   #define E1_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
586 616
   #define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
587 617
 
588
-//#define E2_IS_L6470
618
+  //#define E2_IS_L6470
589 619
   #define E2_MICROSTEPS 16     //number of microsteps
590
-  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
620
+  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
591 621
   #define E2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
592 622
   #define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
593 623
 
594
-//#define E3_IS_L6470
624
+  //#define E3_IS_L6470
595 625
   #define E3_MICROSTEPS 16     //number of microsteps
596
-  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
626
+  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
597 627
   #define E3_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
598 628
   #define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
599 629
 

+ 152
- 102
Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h Näytä tiedosto

@@ -110,6 +110,7 @@ Here are some standard links for getting your machine calibrated:
110 110
 //--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
111 111
 //
112 112
 //// Temperature sensor settings:
113
+// -3 is thermocouple with MAX31855 (only for sensor 0)
113 114
 // -2 is thermocouple with MAX6675 (only for sensor 0)
114 115
 // -1 is thermocouple with AD595
115 116
 // 0 is not used
@@ -129,6 +130,7 @@ Here are some standard links for getting your machine calibrated:
129 130
 // 13 is 100k Hisens 3950  1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
130 131
 // 20 is the PT100 circuit found in the Ultimainboard V2.x
131 132
 // 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
133
+// 70 is the 100K thermistor found in the bq Hephestos 2
132 134
 //
133 135
 //    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
134 136
 //                          (but gives greater accuracy and more stable PID)
@@ -144,7 +146,7 @@ Here are some standard links for getting your machine calibrated:
144 146
 //     Use it for Testing or Development purposes. NEVER for production machine.
145 147
 //#define DUMMY_THERMISTOR_998_VALUE 25
146 148
 //#define DUMMY_THERMISTOR_999_VALUE 100
147
-// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
149
+// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-3': "Thermocouple + MAX31855 (only for sensor 0)", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
148 150
 #define TEMP_SENSOR_0 1
149 151
 #define TEMP_SENSOR_1 0
150 152
 #define TEMP_SENSOR_2 0
@@ -178,14 +180,9 @@ Here are some standard links for getting your machine calibrated:
178 180
 #define HEATER_3_MAXTEMP 275
179 181
 #define BED_MAXTEMP 150
180 182
 
181
-// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
182
-// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
183
-// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
184
-//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
185
-
186 183
 // If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
187
-//#define EXTRUDER_WATTS (12.0*12.0/6.7) //  P=I^2/R
188
-//#define BED_WATTS (12.0*12.0/1.1)      // P=I^2/R
184
+//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
185
+//#define BED_WATTS (12.0*12.0/1.1)      // P=U^2/R
189 186
 
190 187
 //===========================================================================
191 188
 //============================= PID Settings ================================
@@ -253,13 +250,13 @@ Here are some standard links for getting your machine calibrated:
253 250
 
254 251
   #define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
255 252
 
256
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
253
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
257 254
   //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
258 255
   #define  DEFAULT_bedKp 10.00
259 256
   #define  DEFAULT_bedKi .023
260 257
   #define  DEFAULT_bedKd 305.4
261 258
 
262
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
259
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
263 260
   //from pidautotune
264 261
   //#define  DEFAULT_bedKp 97.1
265 262
   //#define  DEFAULT_bedKi 1.41
@@ -284,16 +281,15 @@ Here are some standard links for getting your machine calibrated:
284 281
 //===========================================================================
285 282
 
286 283
 /**
287
- * Thermal Runaway Protection protects your printer from damage and fire if a
284
+ * Thermal Protection protects your printer from damage and fire if a
288 285
  * thermistor falls out or temperature sensors fail in any way.
289 286
  *
290 287
  * The issue: If a thermistor falls out or a temperature sensor fails,
291 288
  * Marlin can no longer sense the actual temperature. Since a disconnected
292 289
  * thermistor reads as a low temperature, the firmware will keep the heater on.
293 290
  *
294
- * The solution: Once the temperature reaches the target, start observing.
295
- * If the temperature stays too far below the target (hysteresis) for too long,
296
- * the firmware will halt as a safety precaution.
291
+ * If you get "Thermal Runaway" or "Heating failed" errors the
292
+ * details can be tuned in Configuration_adv.h
297 293
  */
298 294
 
299 295
 #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
@@ -341,10 +337,52 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
341 337
 //#define DISABLE_MAX_ENDSTOPS
342 338
 //#define DISABLE_MIN_ENDSTOPS
343 339
 
344
-// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
345
-// This only affects a Z probe endstop if you have separate Z min endstop as well and have
346
-// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
347
-// this has no effect.
340
+//===========================================================================
341
+//============================= Z Probe Options =============================
342
+//===========================================================================
343
+
344
+// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
345
+// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
346
+//
347
+// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
348
+//
349
+// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
350
+// Example: To park the head outside the bed area when homing with G28.
351
+//
352
+// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
353
+//
354
+// For a servo-based Z probe, you must set up servo support below, including
355
+// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
356
+//
357
+// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
358
+// - Use 5V for powered (usu. inductive) sensors.
359
+// - Otherwise connect:
360
+//   - normally-closed switches to GND and D32.
361
+//   - normally-open switches to 5V and D32.
362
+//
363
+// Normally-closed switches are advised and are the default.
364
+//
365
+// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
366
+// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
367
+// default pin for all RAMPS-based boards. Some other boards map differently.
368
+// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
369
+//
370
+// WARNING:
371
+// Setting the wrong pin may have unexpected and potentially disastrous consequences.
372
+// Use with caution and do your homework.
373
+//
374
+//#define Z_MIN_PROBE_ENDSTOP
375
+
376
+// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
377
+// The Z_MIN_PIN will then be used for both Z-homing and probing.
378
+#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
379
+
380
+// To use a probe you must enable one of the two options above!
381
+
382
+// This option disables the use of the Z_MIN_PROBE_PIN
383
+// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
384
+// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
385
+// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
348 386
 //#define DISABLE_Z_MIN_PROBE_ENDSTOP
349 387
 
350 388
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
@@ -354,11 +392,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
354 392
 #define Z_ENABLE_ON 0
355 393
 #define E_ENABLE_ON 0 // For all extruders
356 394
 
357
-// Disables axis when it's not being used.
395
+// Disables axis stepper immediately when it's not being used.
358 396
 // WARNING: When motors turn off there is a chance of losing position accuracy!
359 397
 #define DISABLE_X false
360 398
 #define DISABLE_Y false
361 399
 #define DISABLE_Z false
400
+// Warn on display about possibly reduced accuracy
401
+//#define DISABLE_REDUCED_ACCURACY_WARNING
362 402
 
363 403
 // @section extruder
364 404
 
@@ -381,6 +421,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
381 421
 #define INVERT_E3_DIR false
382 422
 
383 423
 // @section homing
424
+//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
425
+                                    // Be sure you have this distance over your Z_MAX_POS in case.
384 426
 
385 427
 // ENDSTOP SETTINGS:
386 428
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
@@ -416,24 +458,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
416 458
 #endif
417 459
 
418 460
 //===========================================================================
419
-//=========================== Manual Bed Leveling ===========================
461
+//============================ Mesh Bed Leveling ============================
420 462
 //===========================================================================
421 463
 
422
-//#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
423 464
 //#define MESH_BED_LEVELING    // Enable mesh bed leveling.
424 465
 
425
-#if ENABLED(MANUAL_BED_LEVELING)
426
-  #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
427
-#endif  // MANUAL_BED_LEVELING
428
-
429 466
 #if ENABLED(MESH_BED_LEVELING)
430 467
   #define MESH_MIN_X 10
431
-  #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
468
+  #define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
432 469
   #define MESH_MIN_Y 10
433
-  #define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
470
+  #define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
434 471
   #define MESH_NUM_X_POINTS 3  // Don't use more than 7 points per axis, implementation limited.
435 472
   #define MESH_NUM_Y_POINTS 3
436 473
   #define MESH_HOME_SEARCH_Z 4  // Z after Home, bed somewhere below but above 0.0.
474
+
475
+  //#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
476
+
477
+  #if ENABLED(MANUAL_BED_LEVELING)
478
+    #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
479
+  #endif  // MANUAL_BED_LEVELING
480
+
437 481
 #endif  // MESH_BED_LEVELING
438 482
 
439 483
 //===========================================================================
@@ -442,10 +486,9 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
442 486
 
443 487
 // @section bedlevel
444 488
 
445
-
446 489
 //#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
447 490
 //#define DEBUG_LEVELING_FEATURE
448
-#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
491
+#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
449 492
 
450 493
 #if ENABLED(AUTO_BED_LEVELING_FEATURE)
451 494
 
@@ -457,7 +500,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
457 500
   //   This mode is preferred because there are more measurements.
458 501
   //
459 502
   // - "3-point" mode
460
-  //   Probe 3 arbitrary points on the bed (that aren't colinear)
503
+  //   Probe 3 arbitrary points on the bed (that aren't collinear)
461 504
   //   You specify the XY coordinates of all 3 points.
462 505
 
463 506
   // Enable this to sample the bed in a grid (least squares solution).
@@ -471,7 +514,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
471 514
     #define FRONT_PROBE_BED_POSITION 20
472 515
     #define BACK_PROBE_BED_POSITION 170
473 516
 
474
-    #define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
517
+    #define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
475 518
 
476 519
     // Set the number of grid points per dimension.
477 520
     // You probably don't need more than 3 (squared=9).
@@ -479,25 +522,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
479 522
 
480 523
   #else  // !AUTO_BED_LEVELING_GRID
481 524
 
482
-      // Arbitrary points to probe.
483
-      // A simple cross-product is used to estimate the plane of the bed.
484
-      #define ABL_PROBE_PT_1_X 15
485
-      #define ABL_PROBE_PT_1_Y 180
486
-      #define ABL_PROBE_PT_2_X 15
487
-      #define ABL_PROBE_PT_2_Y 20
488
-      #define ABL_PROBE_PT_3_X 170
489
-      #define ABL_PROBE_PT_3_Y 20
525
+    // Arbitrary points to probe.
526
+    // A simple cross-product is used to estimate the plane of the bed.
527
+    #define ABL_PROBE_PT_1_X 15
528
+    #define ABL_PROBE_PT_1_Y 180
529
+    #define ABL_PROBE_PT_2_X 15
530
+    #define ABL_PROBE_PT_2_Y 20
531
+    #define ABL_PROBE_PT_3_X 170
532
+    #define ABL_PROBE_PT_3_Y 20
490 533
 
491 534
   #endif // AUTO_BED_LEVELING_GRID
492 535
 
493
-  // Offsets to the Z probe relative to the nozzle tip.
536
+  // Z Probe to nozzle (X,Y) offset, relative to (0, 0).
494 537
   // X and Y offsets must be integers.
495
-  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // Z probe to nozzle X offset: -left  +right
496
-  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Z probe to nozzle Y offset: -front +behind
497
-  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z probe to nozzle Z offset: -below (always!)
498
-
499
-  #define Z_RAISE_BEFORE_HOMING 4       // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
500
-                                        // Be sure you have this distance over your Z_MAX_POS in case.
538
+  //
539
+  // In the following example the X and Y offsets are both positive:
540
+  // #define X_PROBE_OFFSET_FROM_EXTRUDER 10
541
+  // #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
542
+  //
543
+  //    +-- BACK ---+
544
+  //    |           |
545
+  //  L |    (+) P  | R <-- probe (20,20)
546
+  //  E |           | I
547
+  //  F | (-) N (+) | G <-- nozzle (10,10)
548
+  //  T |           | H
549
+  //    |    (-)    | T
550
+  //    |           |
551
+  //    O-- FRONT --+
552
+  //  (0,0)
553
+  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // X offset: -left  [of the nozzle] +right
554
+  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Y offset: -front [of the nozzle] +behind
555
+  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z offset: -below [the nozzle] (always negative!)
501 556
 
502 557
   #define XY_TRAVEL_SPEED 8000         // X and Y axis travel speed between probes, in mm/min.
503 558
 
@@ -505,16 +560,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
505 560
   #define Z_RAISE_BETWEEN_PROBINGS 5  // How much the Z axis will be raised when traveling from between next probing points.
506 561
   #define Z_RAISE_AFTER_PROBING 15    // How much the Z axis will be raised after the last probing point.
507 562
 
508
-//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
509
-                                                                            // Useful to retract a deployable Z probe.
563
+  //#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
564
+                                                                             // Useful to retract a deployable Z probe.
565
+
566
+  // Probes are sensors/switches that need to be activated before they can be used
567
+  // and deactivated after the use.
568
+  // Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
569
+
570
+  // A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
571
+  // when the hardware endstops are active.
572
+  //#define FIX_MOUNTED_PROBE
573
+
574
+  // A Servo Probe can be defined in the servo section below.
510 575
 
511
-  //#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
576
+  // An Allen Key Probe is currently predefined only in the delta example configurations.
577
+
578
+  //#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
512 579
   //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
513 580
 
514
-// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
515
-// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
581
+  // If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
582
+  // it is highly recommended you leave Z_SAFE_HOMING enabled!
516 583
 
517
-  #define Z_SAFE_HOMING   // This feature is meant to avoid Z homing with Z probe outside the bed area.
584
+  #define Z_SAFE_HOMING   // Use the z-min-probe for homing to z-min - not the z-min-endstop.
585
+                          // This feature is meant to avoid Z homing with Z probe outside the bed area.
518 586
                           // When defined, it will:
519 587
                           // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
520 588
                           // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
@@ -528,37 +596,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
528 596
 
529 597
   #endif
530 598
 
531
-  // Support for a dedicated Z probe endstop separate from the Z min endstop.
532
-  // If you would like to use both a Z probe and a Z min endstop together,
533
-  // uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
534
-  // If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
535
-  // Example: To park the head outside the bed area when homing with G28.
536
-  //
537
-  // WARNING:
538
-  // The Z min endstop will need to set properly as it would without a Z probe
539
-  // to prevent head crashes and premature stopping during a print.
540
-  //
541
-  // To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
542
-  // defined in the pins_XXXXX.h file for your control board.
543
-  // If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
544
-  // Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
545
-  // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
546
-  // in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
547
-  // otherwise connect to ground and D32 for normally closed configuration
548
-  // and 5V and D32 for normally open configurations.
549
-  // Normally closed configuration is advised and assumed.
550
-  // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
551
-  // Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
552
-  // Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
553
-  // D32 is currently selected in the RAMPS 1.3/1.4 pin file.
554
-  // All other boards will need changes to the respective pins_XXXXX.h file.
555
-  //
556
-  // WARNING:
557
-  // Setting the wrong pin may have unexpected and potentially disastrous outcomes.
558
-  // Use with caution and do your homework.
559
-  //
560
-  //#define Z_MIN_PROBE_ENDSTOP
561
-
562 599
 #endif // AUTO_BED_LEVELING_FEATURE
563 600
 
564 601
 
@@ -633,6 +670,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
633 670
 #endif
634 671
 
635 672
 //
673
+// Host Keepalive
674
+//
675
+// By default Marlin will send a busy status message to the host
676
+// every 2 seconds when it can't accept commands.
677
+//
678
+//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
679
+
680
+//
636 681
 // M100 Free Memory Watcher
637 682
 //
638 683
 //#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
@@ -652,13 +697,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
652 697
 // @section lcd
653 698
 
654 699
 // Define your display language below. Replace (en) with your language code and uncomment.
655
-// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
700
+// en, pl, fr, de, es, ru, bg, it, pt, pt_utf8, pt-br, pt-br_utf8, fi, an, nl, ca, eu, kana, kana_utf8, cn, cz, test
656 701
 // See also language.h
657 702
 #define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
658 703
 
659 704
 // Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
660 705
 // To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
661
-// See also documentation/LCDLanguageFont.md
706
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
662 707
   #define DISPLAY_CHARSET_HD44780_JAPAN        // this is the most common hardware
663 708
   //#define DISPLAY_CHARSET_HD44780_WESTERN
664 709
   //#define DISPLAY_CHARSET_HD44780_CYRILLIC
@@ -666,11 +711,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
666 711
 #define ULTRA_LCD  //general LCD support, also 16x2
667 712
 //#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
668 713
 #define SDSUPPORT // Enable SD Card Support in Hardware Console
669
-//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
670
-//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
714
+                  // Changed behaviour! If you need SDSUPPORT uncomment it!
715
+//#define SPI_SPEED SPI_HALF_SPEED // (also SPI_QUARTER_SPEED, SPI_EIGHTH_SPEED) Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
671 716
 #define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
672 717
 //#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
673 718
 //#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
719
+//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
674 720
 //#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
675 721
 //#define ULTIPANEL  //the UltiPanel as on Thingiverse
676 722
 //#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
@@ -687,13 +733,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
687 733
 
688 734
 // The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
689 735
 // http://panucatt.com
690
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
736
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
691 737
 //#define VIKI2
692 738
 //#define miniVIKI
693 739
 
694 740
 // This is a new controller currently under development.  https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
695 741
 //
696
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
742
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
697 743
 //#define ELB_FULL_GRAPHIC_CONTROLLER
698 744
 //#define SD_DETECT_INVERTED
699 745
 
@@ -708,7 +754,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
708 754
 // The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
709 755
 // http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
710 756
 //
711
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
757
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
712 758
 //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
713 759
 
714 760
 // The RepRapWorld REPRAPWORLD_KEYPAD v1.1
@@ -731,6 +777,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
731 777
 
732 778
 //#define LCD_I2C_SAINSMART_YWROBOT
733 779
 
780
+//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
781
+
734 782
 // PANELOLU2 LCD with status LEDs, separate encoder and click inputs
735 783
 //
736 784
 // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
@@ -744,7 +792,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
744 792
 //#define LCD_I2C_VIKI
745 793
 
746 794
 // SSD1306 OLED generic display support
747
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
795
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
748 796
 //#define U8GLIB_SSD1306
749 797
 
750 798
 // Shift register panels
@@ -756,7 +804,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
756 804
 
757 805
 // @section extras
758 806
 
759
-// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
807
+// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
760 808
 //#define FAST_PWM_FAN
761 809
 
762 810
 // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
@@ -838,19 +886,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
838 886
 // Uncomment below to enable
839 887
 //#define FILAMENT_SENSOR
840 888
 
841
-#define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
842
-#define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
843
-
844 889
 #define DEFAULT_NOMINAL_FILAMENT_DIA 3.00  //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
845
-#define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
846
-#define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
847
-#define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
848 890
 
849
-//defines used in the code
850
-#define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
891
+#if ENABLED(FILAMENT_SENSOR)
892
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
893
+  #define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
894
+
895
+  #define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
896
+  #define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
897
+  #define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
851 898
 
852
-//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
853
-//#define FILAMENT_LCD_DISPLAY
899
+  #define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
900
+
901
+  //When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
902
+  //#define FILAMENT_LCD_DISPLAY
903
+#endif
854 904
 
855 905
 #include "Configuration_adv.h"
856 906
 #include "thermistortables.h"

+ 164
- 102
Marlin/example_configurations/RigidBot/Configuration.h Näytä tiedosto

@@ -110,6 +110,7 @@ Here are some standard links for getting your machine calibrated:
110 110
 //--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
111 111
 //
112 112
 //// Temperature sensor settings:
113
+// -3 is thermocouple with MAX31855 (only for sensor 0)
113 114
 // -2 is thermocouple with MAX6675 (only for sensor 0)
114 115
 // -1 is thermocouple with AD595
115 116
 // 0 is not used
@@ -129,6 +130,7 @@ Here are some standard links for getting your machine calibrated:
129 130
 // 13 is 100k Hisens 3950  1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
130 131
 // 20 is the PT100 circuit found in the Ultimainboard V2.x
131 132
 // 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
133
+// 70 is the 100K thermistor found in the bq Hephestos 2
132 134
 //
133 135
 //    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
134 136
 //                          (but gives greater accuracy and more stable PID)
@@ -144,7 +146,7 @@ Here are some standard links for getting your machine calibrated:
144 146
 //     Use it for Testing or Development purposes. NEVER for production machine.
145 147
 //#define DUMMY_THERMISTOR_998_VALUE 25
146 148
 //#define DUMMY_THERMISTOR_999_VALUE 100
147
-// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
149
+// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-3': "Thermocouple + MAX31855 (only for sensor 0)", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
148 150
 #define TEMP_SENSOR_0 1 // DGlass3D = 5; RigidBot = 1; 3DSv6 = 5
149 151
 #define TEMP_SENSOR_1 0
150 152
 #define TEMP_SENSOR_2 0
@@ -178,14 +180,9 @@ Here are some standard links for getting your machine calibrated:
178 180
 #define HEATER_3_MAXTEMP 275
179 181
 #define BED_MAXTEMP 150
180 182
 
181
-// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
182
-// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
183
-// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
184
-//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
185
-
186 183
 // If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
187
-//#define EXTRUDER_WATTS (12.0*12.0/6.7) //  P=I^2/R
188
-//#define BED_WATTS (12.0*12.0/1.1)      // P=I^2/R
184
+//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
185
+//#define BED_WATTS (12.0*12.0/1.1)      // P=U^2/R
189 186
 
190 187
 //===========================================================================
191 188
 //============================= PID Settings ================================
@@ -219,6 +216,11 @@ Here are some standard links for getting your machine calibrated:
219 216
   //#define  DEFAULT_Ki 0.85
220 217
   //#define  DEFAULT_Kd 245
221 218
 
219
+  // E3D w/ rigidbot cartridge
220
+  //#define  DEFAULT_Kp 16.30
221
+  //#define  DEFAULT_Ki 0.95
222
+  //#define  DEFAULT_Kd 69.69
223
+
222 224
 #endif // PIDTEMP
223 225
 
224 226
 //===========================================================================
@@ -273,16 +275,15 @@ Here are some standard links for getting your machine calibrated:
273 275
 //===========================================================================
274 276
 
275 277
 /**
276
- * Thermal Runaway Protection protects your printer from damage and fire if a
278
+ * Thermal Protection protects your printer from damage and fire if a
277 279
  * thermistor falls out or temperature sensors fail in any way.
278 280
  *
279 281
  * The issue: If a thermistor falls out or a temperature sensor fails,
280 282
  * Marlin can no longer sense the actual temperature. Since a disconnected
281 283
  * thermistor reads as a low temperature, the firmware will keep the heater on.
282 284
  *
283
- * The solution: Once the temperature reaches the target, start observing.
284
- * If the temperature stays too far below the target (hysteresis) for too long,
285
- * the firmware will halt as a safety precaution.
285
+ * If you get "Thermal Runaway" or "Heating failed" errors the
286
+ * details can be tuned in Configuration_adv.h
286 287
  */
287 288
 
288 289
 #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
@@ -297,6 +298,9 @@ Here are some standard links for getting your machine calibrated:
297 298
 // Uncomment this option to enable CoreXY kinematics
298 299
 //#define COREXY
299 300
 
301
+// Uncomment this option to enable CoreXZ kinematics
302
+//#define COREXZ
303
+
300 304
 // Enable this option for Toshiba steppers
301 305
 //#define CONFIG_STEPPERS_TOSHIBA
302 306
 
@@ -327,10 +331,52 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
327 331
 //#define DISABLE_MAX_ENDSTOPS
328 332
 //#define DISABLE_MIN_ENDSTOPS
329 333
 
330
-// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
331
-// This only affects a Z probe endstop if you have separate Z min endstop as well and have
332
-// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
333
-// this has no effect.
334
+//===========================================================================
335
+//============================= Z Probe Options =============================
336
+//===========================================================================
337
+
338
+// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
339
+// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
340
+//
341
+// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
342
+//
343
+// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
344
+// Example: To park the head outside the bed area when homing with G28.
345
+//
346
+// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
347
+//
348
+// For a servo-based Z probe, you must set up servo support below, including
349
+// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
350
+//
351
+// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
352
+// - Use 5V for powered (usu. inductive) sensors.
353
+// - Otherwise connect:
354
+//   - normally-closed switches to GND and D32.
355
+//   - normally-open switches to 5V and D32.
356
+//
357
+// Normally-closed switches are advised and are the default.
358
+//
359
+// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
360
+// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
361
+// default pin for all RAMPS-based boards. Some other boards map differently.
362
+// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
363
+//
364
+// WARNING:
365
+// Setting the wrong pin may have unexpected and potentially disastrous consequences.
366
+// Use with caution and do your homework.
367
+//
368
+//#define Z_MIN_PROBE_ENDSTOP
369
+
370
+// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
371
+// The Z_MIN_PIN will then be used for both Z-homing and probing.
372
+#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
373
+
374
+// To use a probe you must enable one of the two options above!
375
+
376
+// This option disables the use of the Z_MIN_PROBE_PIN
377
+// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
378
+// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
379
+// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
334 380
 //#define DISABLE_Z_MIN_PROBE_ENDSTOP
335 381
 
336 382
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
@@ -340,11 +386,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
340 386
 #define Z_ENABLE_ON 0
341 387
 #define E_ENABLE_ON 0 // For all extruders
342 388
 
343
-// Disables axis when it's not being used.
389
+// Disables axis stepper immediately when it's not being used.
344 390
 // WARNING: When motors turn off there is a chance of losing position accuracy!
345 391
 #define DISABLE_X false
346 392
 #define DISABLE_Y false
347 393
 #define DISABLE_Z false
394
+// Warn on display about possibly reduced accuracy
395
+//#define DISABLE_REDUCED_ACCURACY_WARNING
348 396
 
349 397
 // @section extruder
350 398
 
@@ -367,6 +415,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
367 415
 #define INVERT_E3_DIR false
368 416
 
369 417
 // @section homing
418
+//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
419
+                                    // Be sure you have this distance over your Z_MAX_POS in case.
370 420
 
371 421
 // ENDSTOP SETTINGS:
372 422
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
@@ -402,24 +452,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
402 452
 #endif
403 453
 
404 454
 //===========================================================================
405
-//=========================== Manual Bed Leveling ===========================
455
+//============================ Mesh Bed Leveling ============================
406 456
 //===========================================================================
407 457
 
408
-//#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
409 458
 //#define MESH_BED_LEVELING    // Enable mesh bed leveling.
410 459
 
411
-#if ENABLED(MANUAL_BED_LEVELING)
412
-  #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
413
-#endif  // MANUAL_BED_LEVELING
414
-
415 460
 #if ENABLED(MESH_BED_LEVELING)
416 461
   #define MESH_MIN_X 10
417
-  #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
462
+  #define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
418 463
   #define MESH_MIN_Y 10
419
-  #define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
464
+  #define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
420 465
   #define MESH_NUM_X_POINTS 3  // Don't use more than 7 points per axis, implementation limited.
421 466
   #define MESH_NUM_Y_POINTS 3
422 467
   #define MESH_HOME_SEARCH_Z 4  // Z after Home, bed somewhere below but above 0.0.
468
+
469
+  //#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
470
+
471
+  #if ENABLED(MANUAL_BED_LEVELING)
472
+    #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
473
+  #endif  // MANUAL_BED_LEVELING
474
+
423 475
 #endif  // MESH_BED_LEVELING
424 476
 
425 477
 //===========================================================================
@@ -430,7 +482,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
430 482
 
431 483
 //#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
432 484
 //#define DEBUG_LEVELING_FEATURE
433
-//#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
485
+//#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
434 486
 
435 487
 #if ENABLED(AUTO_BED_LEVELING_FEATURE)
436 488
 
@@ -442,7 +494,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
442 494
   //   This mode is preferred because there are more measurements.
443 495
   //
444 496
   // - "3-point" mode
445
-  //   Probe 3 arbitrary points on the bed (that aren't colinear)
497
+  //   Probe 3 arbitrary points on the bed (that aren't collinear)
446 498
   //   You specify the XY coordinates of all 3 points.
447 499
 
448 500
   // Enable this to sample the bed in a grid (least squares solution).
@@ -456,7 +508,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
456 508
     #define FRONT_PROBE_BED_POSITION 20
457 509
     #define BACK_PROBE_BED_POSITION 170
458 510
 
459
-    #define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
511
+    #define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
460 512
 
461 513
     // Set the number of grid points per dimension.
462 514
     // You probably don't need more than 3 (squared=9).
@@ -464,25 +516,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
464 516
 
465 517
   #else  // !AUTO_BED_LEVELING_GRID
466 518
 
467
-      // Arbitrary points to probe.
468
-      // A simple cross-product is used to estimate the plane of the bed.
469
-      #define ABL_PROBE_PT_1_X 15
470
-      #define ABL_PROBE_PT_1_Y 180
471
-      #define ABL_PROBE_PT_2_X 15
472
-      #define ABL_PROBE_PT_2_Y 20
473
-      #define ABL_PROBE_PT_3_X 170
474
-      #define ABL_PROBE_PT_3_Y 20
519
+    // Arbitrary points to probe.
520
+    // A simple cross-product is used to estimate the plane of the bed.
521
+    #define ABL_PROBE_PT_1_X 15
522
+    #define ABL_PROBE_PT_1_Y 180
523
+    #define ABL_PROBE_PT_2_X 15
524
+    #define ABL_PROBE_PT_2_Y 20
525
+    #define ABL_PROBE_PT_3_X 170
526
+    #define ABL_PROBE_PT_3_Y 20
475 527
 
476 528
   #endif // AUTO_BED_LEVELING_GRID
477 529
 
478
-  // Offsets to the Z probe relative to the nozzle tip.
530
+  // Z Probe to nozzle (X,Y) offset, relative to (0, 0).
479 531
   // X and Y offsets must be integers.
480
-  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // Z probe to nozzle X offset: -left  +right
481
-  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Z probe to nozzle Y offset: -front +behind
482
-  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z probe to nozzle Z offset: -below (always!)
483
-
484
-  #define Z_RAISE_BEFORE_HOMING 4       // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
485
-                                        // Be sure you have this distance over your Z_MAX_POS in case.
532
+  //
533
+  // In the following example the X and Y offsets are both positive:
534
+  // #define X_PROBE_OFFSET_FROM_EXTRUDER 10
535
+  // #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
536
+  //
537
+  //    +-- BACK ---+
538
+  //    |           |
539
+  //  L |    (+) P  | R <-- probe (20,20)
540
+  //  E |           | I
541
+  //  F | (-) N (+) | G <-- nozzle (10,10)
542
+  //  T |           | H
543
+  //    |    (-)    | T
544
+  //    |           |
545
+  //    O-- FRONT --+
546
+  //  (0,0)
547
+  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // X offset: -left  [of the nozzle] +right
548
+  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Y offset: -front [of the nozzle] +behind
549
+  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z offset: -below [the nozzle] (always negative!)
486 550
 
487 551
   #define XY_TRAVEL_SPEED 8000         // X and Y axis travel speed between probes, in mm/min.
488 552
 
@@ -490,16 +554,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
490 554
   #define Z_RAISE_BETWEEN_PROBINGS 5  // How much the Z axis will be raised when traveling from between next probing points.
491 555
   #define Z_RAISE_AFTER_PROBING 15    // How much the Z axis will be raised after the last probing point.
492 556
 
493
-//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
494
-                                                                            // Useful to retract a deployable Z probe.
557
+  //#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
558
+                                                                             // Useful to retract a deployable Z probe.
559
+
560
+  // Probes are sensors/switches that need to be activated before they can be used
561
+  // and deactivated after the use.
562
+  // Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
563
+
564
+  // A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
565
+  // when the hardware endstops are active.
566
+  //#define FIX_MOUNTED_PROBE
567
+
568
+  // A Servo Probe can be defined in the servo section below.
495 569
 
496
-  //#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
570
+  // An Allen Key Probe is currently predefined only in the delta example configurations.
571
+
572
+  //#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
497 573
   //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
498 574
 
499
-// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
500
-// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
575
+  // If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
576
+  // it is highly recommended you leave Z_SAFE_HOMING enabled!
501 577
 
502
-  #define Z_SAFE_HOMING   // This feature is meant to avoid Z homing with Z probe outside the bed area.
578
+  #define Z_SAFE_HOMING   // Use the z-min-probe for homing to z-min - not the z-min-endstop.
579
+                          // This feature is meant to avoid Z homing with Z probe outside the bed area.
503 580
                           // When defined, it will:
504 581
                           // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
505 582
                           // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
@@ -513,37 +590,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
513 590
 
514 591
   #endif
515 592
 
516
-  // Support for a dedicated Z probe endstop separate from the Z min endstop.
517
-  // If you would like to use both a Z probe and a Z min endstop together,
518
-  // uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
519
-  // If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
520
-  // Example: To park the head outside the bed area when homing with G28.
521
-  //
522
-  // WARNING:
523
-  // The Z min endstop will need to set properly as it would without a Z probe
524
-  // to prevent head crashes and premature stopping during a print.
525
-  //
526
-  // To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
527
-  // defined in the pins_XXXXX.h file for your control board.
528
-  // If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
529
-  // Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
530
-  // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
531
-  // in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
532
-  // otherwise connect to ground and D32 for normally closed configuration
533
-  // and 5V and D32 for normally open configurations.
534
-  // Normally closed configuration is advised and assumed.
535
-  // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
536
-  // Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
537
-  // Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
538
-  // D32 is currently selected in the RAMPS 1.3/1.4 pin file.
539
-  // All other boards will need changes to the respective pins_XXXXX.h file.
540
-  //
541
-  // WARNING:
542
-  // Setting the wrong pin may have unexpected and potentially disastrous outcomes.
543
-  // Use with caution and do your homework.
544
-  //
545
-  //#define Z_MIN_PROBE_ENDSTOP
546
-
547 593
 #endif // AUTO_BED_LEVELING_FEATURE
548 594
 
549 595
 
@@ -611,7 +657,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
611 657
 // M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
612 658
 // M502 - reverts to the default "factory settings".  You still need to store them in EEPROM afterwards if you want to.
613 659
 //define this to enable EEPROM support
614
-//#define EEPROM_SETTINGS
660
+#define EEPROM_SETTINGS
615 661
 
616 662
 #if ENABLED(EEPROM_SETTINGS)
617 663
   // To disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
@@ -619,6 +665,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
619 665
 #endif
620 666
 
621 667
 //
668
+// Host Keepalive
669
+//
670
+// By default Marlin will send a busy status message to the host
671
+// every 2 seconds when it can't accept commands.
672
+//
673
+//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
674
+
675
+//
622 676
 // M100 Free Memory Watcher
623 677
 //
624 678
 //#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
@@ -638,26 +692,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
638 692
 // @section lcd
639 693
 
640 694
 // Define your display language below. Replace (en) with your language code and uncomment.
641
-// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
695
+// en, pl, fr, de, es, ru, bg, it, pt, pt_utf8, pt-br, pt-br_utf8, fi, an, nl, ca, eu, kana, kana_utf8, cn, cz, test
642 696
 // See also language.h
643 697
 #define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
644 698
 
645 699
 // Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
646 700
 // To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
647
-// See also documentation/LCDLanguageFont.md
701
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
648 702
   #define DISPLAY_CHARSET_HD44780_JAPAN        // this is the most common hardware
649 703
   //#define DISPLAY_CHARSET_HD44780_WESTERN
650 704
   //#define DISPLAY_CHARSET_HD44780_CYRILLIC
651 705
 
652 706
 //#define ULTRA_LCD  //general LCD support, also 16x2
653 707
 //#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
654
-//#define SDSUPPORT // Enable SD Card Support in Hardware Console
655
-// Changed behaviour! If you need SDSUPPORT uncomment it!
656
-//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
657
-//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
708
+#define SDSUPPORT // Enable SD Card Support in Hardware Console
709
+                  // Changed behaviour! If you need SDSUPPORT uncomment it!
710
+#define SPI_SPEED SPI_EIGHTH_SPEED // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
658 711
 //#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
659 712
 //#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
660 713
 //#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
714
+//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
661 715
 //#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
662 716
 //#define ULTIPANEL  //the UltiPanel as on Thingiverse
663 717
 //#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
@@ -674,13 +728,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
674 728
 
675 729
 // The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
676 730
 // http://panucatt.com
677
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
731
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
678 732
 //#define VIKI2
679 733
 //#define miniVIKI
680 734
 
681 735
 // This is a new controller currently under development.  https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
682 736
 //
683
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
737
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
684 738
 //#define ELB_FULL_GRAPHIC_CONTROLLER
685 739
 //#define SD_DETECT_INVERTED
686 740
 
@@ -695,7 +749,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
695 749
 // The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
696 750
 // http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
697 751
 //
698
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
752
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
699 753
 //
700 754
 // RigidBoard: To rewire this for a RigidBot see http://rigidtalk.com/wiki/index.php?title=LCD_Smart_Controller
701 755
 //
@@ -711,6 +765,10 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
711 765
 // REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
712 766
 //#define RA_CONTROL_PANEL
713 767
 
768
+// The MakerLab Mini Panel with graphic controller and SD support
769
+// http://reprap.org/wiki/Mini_panel
770
+//#define MINIPANEL
771
+
714 772
 // RigidBot Panel V1.0
715 773
 // http://www.inventapart.com/
716 774
 #define RIGIDBOT_PANEL
@@ -721,6 +779,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
721 779
 
722 780
 //#define LCD_I2C_SAINSMART_YWROBOT
723 781
 
782
+//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
783
+
724 784
 // PANELOLU2 LCD with status LEDs, separate encoder and click inputs
725 785
 //
726 786
 // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
@@ -734,7 +794,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
734 794
 //#define LCD_I2C_VIKI
735 795
 
736 796
 // SSD1306 OLED generic display support
737
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
797
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
738 798
 //#define U8GLIB_SSD1306
739 799
 
740 800
 // Shift register panels
@@ -746,7 +806,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
746 806
 
747 807
 // @section extras
748 808
 
749
-// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
809
+// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
750 810
 //#define FAST_PWM_FAN
751 811
 
752 812
 // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
@@ -828,19 +888,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
828 888
 // Uncomment below to enable
829 889
 //#define FILAMENT_SENSOR
830 890
 
831
-#define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
832
-#define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
833
-
834 891
 #define DEFAULT_NOMINAL_FILAMENT_DIA 3.00  //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
835
-#define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
836
-#define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
837
-#define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
838 892
 
839
-//defines used in the code
840
-#define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
893
+#if ENABLED(FILAMENT_SENSOR)
894
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
895
+  #define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
896
+
897
+  #define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
898
+  #define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
899
+  #define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
841 900
 
842
-//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
843
-//#define FILAMENT_LCD_DISPLAY
901
+  #define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
902
+
903
+  //When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
904
+  //#define FILAMENT_LCD_DISPLAY
905
+#endif
844 906
 
845 907
 #include "Configuration_adv.h"
846 908
 #include "thermistortables.h"

+ 81
- 51
Marlin/example_configurations/RigidBot/Configuration_adv.h Näytä tiedosto

@@ -17,6 +17,20 @@
17 17
 /**
18 18
  * Thermal Protection parameters
19 19
  */
20
+  /**
21
+   * Thermal Protection protects your printer from damage and fire if a
22
+   * thermistor falls out or temperature sensors fail in any way.
23
+   *
24
+   * The issue: If a thermistor falls out or a temperature sensor fails,
25
+   * Marlin can no longer sense the actual temperature. Since a disconnected
26
+   * thermistor reads as a low temperature, the firmware will keep the heater on.
27
+   *
28
+   * The solution: Once the temperature reaches the target, start observing.
29
+   * If the temperature stays too far below the target (hysteresis) for too long (period),
30
+   * the firmware will halt the machine as a safety precaution.
31
+   *
32
+   * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
33
+   */
20 34
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
21 35
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
22 36
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
@@ -26,11 +40,19 @@
26 40
    * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
27 41
    * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
28 42
    * but only if the current temperature is far enough below the target for a reliable test.
43
+   *
44
+   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
45
+   * WATCH_TEMP_INCREASE should not be below 2.
29 46
    */
30 47
   #define WATCH_TEMP_PERIOD 16                // Seconds
31 48
   #define WATCH_TEMP_INCREASE 4               // Degrees Celsius
32 49
 #endif
33 50
 
51
+  /**
52
+   * Thermal Protection parameters for the bed
53
+   * are like the above for the hotends.
54
+   * WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
55
+   */
34 56
 #if ENABLED(THERMAL_PROTECTION_BED)
35 57
   #define THERMAL_PROTECTION_BED_PERIOD 20    // Seconds
36 58
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
@@ -52,7 +74,7 @@
52 74
  * The maximum buffered steps/sec of the extruder motor is called "se".
53 75
  * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
54 76
  * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
55
- * mintemp and maxtemp. Turn this off by excuting M109 without F*
77
+ * mintemp and maxtemp. Turn this off by executing M109 without F*
56 78
  * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
57 79
  * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
58 80
  */
@@ -232,7 +254,13 @@
232 254
 #define INVERT_E_STEP_PIN false
233 255
 
234 256
 // Default stepper release if idle. Set to 0 to deactivate.
257
+// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
258
+// Time can be set by M18 and M84.
235 259
 #define DEFAULT_STEPPER_DEACTIVE_TIME 60
260
+#define DISABLE_INACTIVE_X true
261
+#define DISABLE_INACTIVE_Y true
262
+#define DISABLE_INACTIVE_Z true  // set to false if the nozzle will fall down on your printed part when print has finished.
263
+#define DISABLE_INACTIVE_E true
236 264
 
237 265
 #define DEFAULT_MINIMUMFEEDRATE       0.0     // minimum feedrate
238 266
 #define DEFAULT_MINTRAVELFEEDRATE     0.0
@@ -268,6 +296,9 @@
268 296
 // Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
269 297
 #define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
270 298
 
299
+// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
300
+//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
301
+
271 302
 // uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
272 303
 //#define DIGIPOT_I2C
273 304
 // Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
@@ -279,9 +310,9 @@
279 310
 //=============================Additional Features===========================
280 311
 //===========================================================================
281 312
 
282
-#define ENCODER_RATE_MULTIPLIER         // If defined, certain menu edit operations automatically multiply the steps when the encoder is moved quickly
283
-#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
284
-#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
313
+//#define ENCODER_RATE_MULTIPLIER         // If defined, certain menu edit operations automatically multiply the steps when the encoder is moved quickly
314
+//#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
315
+//#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
285 316
 
286 317
 //#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/
287 318
 #define CHDK_DELAY 50 //How long in ms the pin should stay HIGH before going LOW again
@@ -290,13 +321,12 @@
290 321
 
291 322
 #if ENABLED(SDSUPPORT)
292 323
 
293
-  // If you are using a RAMPS board or cheap E-bay purchased boards that do not detect when an SD card is inserted
294
-  // You can get round this by connecting a push button or single throw switch to the pin defined as SD_DETECT_PIN
295
-  // in the pins.h file.  When using a push button pulling the pin to ground this will need inverted.  This setting should
296
-  // be commented out otherwise
297
-  #ifndef ELB_FULL_GRAPHIC_CONTROLLER
298
-    #define SD_DETECT_INVERTED
299
-  #endif
324
+  // Some RAMPS and other boards don't detect when an SD card is inserted. You can work
325
+  // around this by connecting a push button or single throw switch to the pin defined
326
+  // as SD_DETECT_PIN in your board's pins definitions.
327
+  // This setting should be disabled unless you are using a push button, pulling the pin to ground.
328
+  // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
329
+  #define SD_DETECT_INVERTED
300 330
 
301 331
   #define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
302 332
   #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
@@ -345,13 +375,13 @@
345 375
 // @section more
346 376
 
347 377
 // The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
348
-//#define USE_WATCHDOG
378
+#define USE_WATCHDOG
349 379
 
350 380
 #if ENABLED(USE_WATCHDOG)
351
-// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
352
-// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
353
-//  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
354
-//#define WATCHDOG_RESET_MANUAL
381
+  // If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
382
+  // The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
383
+  //  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
384
+  //#define WATCHDOG_RESET_MANUAL
355 385
 #endif
356 386
 
357 387
 // @section lcd
@@ -362,6 +392,7 @@
362 392
 //#define BABYSTEPPING
363 393
 #if ENABLED(BABYSTEPPING)
364 394
   #define BABYSTEP_XY  //not only z, but also XY in the menu. more clutter, more functions
395
+                       //not implemented for deltabots!
365 396
   #define BABYSTEP_INVERT_Z false  //true for inverse movements in Z
366 397
   #define BABYSTEP_MULTIPLICATOR 1 //faster movements
367 398
 #endif
@@ -380,7 +411,6 @@
380 411
 #if ENABLED(ADVANCE)
381 412
   #define EXTRUDER_ADVANCE_K .0
382 413
   #define D_FILAMENT 1.75
383
-  #define STEPS_MM_E 836
384 414
 #endif
385 415
 
386 416
 // @section extras
@@ -389,7 +419,7 @@
389 419
 #define MM_PER_ARC_SEGMENT 1
390 420
 #define N_ARC_CORRECTION 25
391 421
 
392
-const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
422
+const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
393 423
 
394 424
 // @section temperature
395 425
 
@@ -414,7 +444,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
414 444
 
415 445
 //The ASCII buffer for receiving from the serial:
416 446
 #define MAX_CMD_SIZE 96
417
-#define BUFSIZE 4
447
+#define BUFSIZE 8
418 448
 
419 449
 // Bad Serial-connections can miss a received command by sending an 'ok'
420 450
 // Therefore some clients abort after 30 seconds in a timeout.
@@ -462,7 +492,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
462 492
 
463 493
 /******************************************************************************\
464 494
  * enable this section if you have TMC26X motor drivers.
465
- * you need to import the TMC26XStepper library into the arduino IDE for this
495
+ * you need to import the TMC26XStepper library into the Arduino IDE for this
466 496
  ******************************************************************************/
467 497
 
468 498
 // @section tmc
@@ -470,52 +500,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
470 500
 //#define HAVE_TMCDRIVER
471 501
 #if ENABLED(HAVE_TMCDRIVER)
472 502
 
473
-//#define X_IS_TMC
503
+  //#define X_IS_TMC
474 504
   #define X_MAX_CURRENT 1000  //in mA
475 505
   #define X_SENSE_RESISTOR 91 //in mOhms
476 506
   #define X_MICROSTEPS 16     //number of microsteps
477 507
 
478
-//#define X2_IS_TMC
508
+  //#define X2_IS_TMC
479 509
   #define X2_MAX_CURRENT 1000  //in mA
480 510
   #define X2_SENSE_RESISTOR 91 //in mOhms
481 511
   #define X2_MICROSTEPS 16     //number of microsteps
482 512
 
483
-//#define Y_IS_TMC
513
+  //#define Y_IS_TMC
484 514
   #define Y_MAX_CURRENT 1000  //in mA
485 515
   #define Y_SENSE_RESISTOR 91 //in mOhms
486 516
   #define Y_MICROSTEPS 16     //number of microsteps
487 517
 
488
-//#define Y2_IS_TMC
518
+  //#define Y2_IS_TMC
489 519
   #define Y2_MAX_CURRENT 1000  //in mA
490 520
   #define Y2_SENSE_RESISTOR 91 //in mOhms
491 521
   #define Y2_MICROSTEPS 16     //number of microsteps
492 522
 
493
-//#define Z_IS_TMC
523
+  //#define Z_IS_TMC
494 524
   #define Z_MAX_CURRENT 1000  //in mA
495 525
   #define Z_SENSE_RESISTOR 91 //in mOhms
496 526
   #define Z_MICROSTEPS 16     //number of microsteps
497 527
 
498
-//#define Z2_IS_TMC
528
+  //#define Z2_IS_TMC
499 529
   #define Z2_MAX_CURRENT 1000  //in mA
500 530
   #define Z2_SENSE_RESISTOR 91 //in mOhms
501 531
   #define Z2_MICROSTEPS 16     //number of microsteps
502 532
 
503
-//#define E0_IS_TMC
533
+  //#define E0_IS_TMC
504 534
   #define E0_MAX_CURRENT 1000  //in mA
505 535
   #define E0_SENSE_RESISTOR 91 //in mOhms
506 536
   #define E0_MICROSTEPS 16     //number of microsteps
507 537
 
508
-//#define E1_IS_TMC
538
+  //#define E1_IS_TMC
509 539
   #define E1_MAX_CURRENT 1000  //in mA
510 540
   #define E1_SENSE_RESISTOR 91 //in mOhms
511 541
   #define E1_MICROSTEPS 16     //number of microsteps
512 542
 
513
-//#define E2_IS_TMC
543
+  //#define E2_IS_TMC
514 544
   #define E2_MAX_CURRENT 1000  //in mA
515 545
   #define E2_SENSE_RESISTOR 91 //in mOhms
516 546
   #define E2_MICROSTEPS 16     //number of microsteps
517 547
 
518
-//#define E3_IS_TMC
548
+  //#define E3_IS_TMC
519 549
   #define E3_MAX_CURRENT 1000  //in mA
520 550
   #define E3_SENSE_RESISTOR 91 //in mOhms
521 551
   #define E3_MICROSTEPS 16     //number of microsteps
@@ -524,7 +554,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
524 554
 
525 555
 /******************************************************************************\
526 556
  * enable this section if you have L6470  motor drivers.
527
- * you need to import the L6470 library into the arduino IDE for this
557
+ * you need to import the L6470 library into the Arduino IDE for this
528 558
  ******************************************************************************/
529 559
 
530 560
 // @section l6470
@@ -532,63 +562,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
532 562
 //#define HAVE_L6470DRIVER
533 563
 #if ENABLED(HAVE_L6470DRIVER)
534 564
 
535
-//#define X_IS_L6470
565
+  //#define X_IS_L6470
536 566
   #define X_MICROSTEPS 16     //number of microsteps
537
-  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
567
+  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
538 568
   #define X_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
539 569
   #define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
540 570
 
541
-//#define X2_IS_L6470
571
+  //#define X2_IS_L6470
542 572
   #define X2_MICROSTEPS 16     //number of microsteps
543
-  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
573
+  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
544 574
   #define X2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
545 575
   #define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
546 576
 
547
-//#define Y_IS_L6470
577
+  //#define Y_IS_L6470
548 578
   #define Y_MICROSTEPS 16     //number of microsteps
549
-  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
579
+  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
550 580
   #define Y_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
551 581
   #define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
552 582
 
553
-//#define Y2_IS_L6470
583
+  //#define Y2_IS_L6470
554 584
   #define Y2_MICROSTEPS 16     //number of microsteps
555
-  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
585
+  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
556 586
   #define Y2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
557 587
   #define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
558 588
 
559
-//#define Z_IS_L6470
589
+  //#define Z_IS_L6470
560 590
   #define Z_MICROSTEPS 16     //number of microsteps
561
-  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
591
+  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
562 592
   #define Z_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
563 593
   #define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
564 594
 
565
-//#define Z2_IS_L6470
595
+  //#define Z2_IS_L6470
566 596
   #define Z2_MICROSTEPS 16     //number of microsteps
567
-  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
597
+  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
568 598
   #define Z2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
569 599
   #define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
570 600
 
571
-//#define E0_IS_L6470
601
+  //#define E0_IS_L6470
572 602
   #define E0_MICROSTEPS 16     //number of microsteps
573
-  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
603
+  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
574 604
   #define E0_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
575 605
   #define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
576 606
 
577
-//#define E1_IS_L6470
607
+  //#define E1_IS_L6470
578 608
   #define E1_MICROSTEPS 16     //number of microsteps
579
-  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
609
+  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
580 610
   #define E1_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
581 611
   #define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
582 612
 
583
-//#define E2_IS_L6470
613
+  //#define E2_IS_L6470
584 614
   #define E2_MICROSTEPS 16     //number of microsteps
585
-  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
615
+  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
586 616
   #define E2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
587 617
   #define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
588 618
 
589
-//#define E3_IS_L6470
619
+  //#define E3_IS_L6470
590 620
   #define E3_MICROSTEPS 16     //number of microsteps
591
-  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
621
+  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
592 622
   #define E3_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
593 623
   #define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
594 624
 

+ 159
- 109
Marlin/example_configurations/SCARA/Configuration.h Näytä tiedosto

@@ -95,7 +95,7 @@ Here are some standard links for getting your machine calibrated:
95 95
 // The following define selects which electronics board you have.
96 96
 // Please choose the name from boards.h that matches your setup
97 97
 #ifndef MOTHERBOARD
98
-  #define MOTHERBOARD BOARD_RAMPS_13_EFB
98
+  #define MOTHERBOARD BOARD_RAMPS_14_EFB
99 99
 #endif
100 100
 
101 101
 // Optional custom name for your RepStrap or other custom machine
@@ -135,6 +135,7 @@ Here are some standard links for getting your machine calibrated:
135 135
 //--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
136 136
 //
137 137
 //// Temperature sensor settings:
138
+// -3 is thermocouple with MAX31855 (only for sensor 0)
138 139
 // -2 is thermocouple with MAX6675 (only for sensor 0)
139 140
 // -1 is thermocouple with AD595
140 141
 // 0 is not used
@@ -154,6 +155,7 @@ Here are some standard links for getting your machine calibrated:
154 155
 // 13 is 100k Hisens 3950  1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
155 156
 // 20 is the PT100 circuit found in the Ultimainboard V2.x
156 157
 // 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
158
+// 70 is the 100K thermistor found in the bq Hephestos 2
157 159
 //
158 160
 //    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
159 161
 //                          (but gives greater accuracy and more stable PID)
@@ -169,7 +171,7 @@ Here are some standard links for getting your machine calibrated:
169 171
 //     Use it for Testing or Development purposes. NEVER for production machine.
170 172
 //#define DUMMY_THERMISTOR_998_VALUE 25
171 173
 //#define DUMMY_THERMISTOR_999_VALUE 100
172
-// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
174
+// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-3': "Thermocouple + MAX31855 (only for sensor 0)", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
173 175
 #define TEMP_SENSOR_0 1
174 176
 #define TEMP_SENSOR_1 0
175 177
 #define TEMP_SENSOR_2 0
@@ -203,14 +205,9 @@ Here are some standard links for getting your machine calibrated:
203 205
 #define HEATER_3_MAXTEMP 275
204 206
 #define BED_MAXTEMP 150
205 207
 
206
-// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
207
-// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
208
-// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
209
-//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
210
-
211 208
 // If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
212
-#define EXTRUDER_WATTS (2*2/5.9) //  P=I^2/R
213
-#define BED_WATTS (5.45*5.45/2.2)      // P=I^2/R
209
+#define EXTRUDER_WATTS (2*2/5.9)       // P=U^2/R
210
+#define BED_WATTS (5.45*5.45/2.2)      // P=U^2/R
214 211
 
215 212
 //===========================================================================
216 213
 //============================= PID Settings ================================
@@ -292,16 +289,15 @@ Here are some standard links for getting your machine calibrated:
292 289
 //===========================================================================
293 290
 
294 291
 /**
295
- * Thermal Runaway Protection protects your printer from damage and fire if a
292
+ * Thermal Protection protects your printer from damage and fire if a
296 293
  * thermistor falls out or temperature sensors fail in any way.
297 294
  *
298 295
  * The issue: If a thermistor falls out or a temperature sensor fails,
299 296
  * Marlin can no longer sense the actual temperature. Since a disconnected
300 297
  * thermistor reads as a low temperature, the firmware will keep the heater on.
301 298
  *
302
- * The solution: Once the temperature reaches the target, start observing.
303
- * If the temperature stays too far below the target (hysteresis) for too long,
304
- * the firmware will halt as a safety precaution.
299
+ * If you get "Thermal Runaway" or "Heating failed" errors the
300
+ * details can be tuned in Configuration_adv.h
305 301
  */
306 302
 
307 303
 #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
@@ -331,9 +327,9 @@ Here are some standard links for getting your machine calibrated:
331 327
   // fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined
332 328
   //#define ENDSTOPPULLUP_XMAX
333 329
   //#define ENDSTOPPULLUP_YMAX
334
-   #define ENDSTOPPULLUP_ZMAX  // open pin, inverted
335
-   #define ENDSTOPPULLUP_XMIN  // open pin, inverted
336
-   #define ENDSTOPPULLUP_YMIN  // open pin, inverted
330
+  #define ENDSTOPPULLUP_ZMAX  // open pin, inverted
331
+  #define ENDSTOPPULLUP_XMIN  // open pin, inverted
332
+  #define ENDSTOPPULLUP_YMIN  // open pin, inverted
337 333
   //#define ENDSTOPPULLUP_ZMIN
338 334
   //#define ENDSTOPPULLUP_ZMIN_PROBE
339 335
 #endif
@@ -349,10 +345,52 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
349 345
 //#define DISABLE_MAX_ENDSTOPS
350 346
 //#define DISABLE_MIN_ENDSTOPS
351 347
 
352
-// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
353
-// This only affects a Z probe endstop if you have separate Z min endstop as well and have
354
-// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
355
-// this has no effect.
348
+//===========================================================================
349
+//============================= Z Probe Options =============================
350
+//===========================================================================
351
+
352
+// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
353
+// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
354
+//
355
+// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
356
+//
357
+// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
358
+// Example: To park the head outside the bed area when homing with G28.
359
+//
360
+// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
361
+//
362
+// For a servo-based Z probe, you must set up servo support below, including
363
+// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
364
+//
365
+// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
366
+// - Use 5V for powered (usu. inductive) sensors.
367
+// - Otherwise connect:
368
+//   - normally-closed switches to GND and D32.
369
+//   - normally-open switches to 5V and D32.
370
+//
371
+// Normally-closed switches are advised and are the default.
372
+//
373
+// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
374
+// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
375
+// default pin for all RAMPS-based boards. Some other boards map differently.
376
+// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
377
+//
378
+// WARNING:
379
+// Setting the wrong pin may have unexpected and potentially disastrous consequences.
380
+// Use with caution and do your homework.
381
+//
382
+//#define Z_MIN_PROBE_ENDSTOP
383
+
384
+// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
385
+// The Z_MIN_PIN will then be used for both Z-homing and probing.
386
+#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
387
+
388
+// To use a probe you must enable one of the two options above!
389
+
390
+// This option disables the use of the Z_MIN_PROBE_PIN
391
+// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
392
+// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
393
+// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
356 394
 //#define DISABLE_Z_MIN_PROBE_ENDSTOP
357 395
 
358 396
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
@@ -362,11 +400,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
362 400
 #define Z_ENABLE_ON 0
363 401
 #define E_ENABLE_ON 0 // For all extruders
364 402
 
365
-// Disables axis when it's not being used.
403
+// Disables axis stepper immediately when it's not being used.
366 404
 // WARNING: When motors turn off there is a chance of losing position accuracy!
367 405
 #define DISABLE_X false
368 406
 #define DISABLE_Y false
369 407
 #define DISABLE_Z false
408
+// Warn on display about possibly reduced accuracy
409
+//#define DISABLE_REDUCED_ACCURACY_WARNING
370 410
 
371 411
 // @section extruder
372 412
 
@@ -389,6 +429,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
389 429
 #define INVERT_E3_DIR false
390 430
 
391 431
 // @section homing
432
+//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
433
+                                    // Be sure you have this distance over your Z_MAX_POS in case.
392 434
 
393 435
 // ENDSTOP SETTINGS:
394 436
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
@@ -424,24 +466,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
424 466
 #endif
425 467
 
426 468
 //===========================================================================
427
-//=========================== Manual Bed Leveling ===========================
469
+//============================ Mesh Bed Leveling ============================
428 470
 //===========================================================================
429 471
 
430
-//#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
431 472
 //#define MESH_BED_LEVELING    // Enable mesh bed leveling.
432 473
 
433
-#if ENABLED(MANUAL_BED_LEVELING)
434
-  #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
435
-#endif  // MANUAL_BED_LEVELING
436
-
437 474
 #if ENABLED(MESH_BED_LEVELING)
438 475
   #define MESH_MIN_X 10
439
-  #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
476
+  #define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
440 477
   #define MESH_MIN_Y 10
441
-  #define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
478
+  #define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
442 479
   #define MESH_NUM_X_POINTS 3  // Don't use more than 7 points per axis, implementation limited.
443 480
   #define MESH_NUM_Y_POINTS 3
444 481
   #define MESH_HOME_SEARCH_Z 4  // Z after Home, bed somewhere below but above 0.0.
482
+
483
+  //#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
484
+
485
+  #if ENABLED(MANUAL_BED_LEVELING)
486
+    #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
487
+  #endif  // MANUAL_BED_LEVELING
488
+
445 489
 #endif  // MESH_BED_LEVELING
446 490
 
447 491
 //===========================================================================
@@ -452,7 +496,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
452 496
 
453 497
 //#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
454 498
 //#define DEBUG_LEVELING_FEATURE
455
-//#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
499
+//#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
456 500
 
457 501
 #if ENABLED(AUTO_BED_LEVELING_FEATURE)
458 502
 
@@ -464,7 +508,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
464 508
   //   This mode is preferred because there are more measurements.
465 509
   //
466 510
   // - "3-point" mode
467
-  //   Probe 3 arbitrary points on the bed (that aren't colinear)
511
+  //   Probe 3 arbitrary points on the bed (that aren't collinear)
468 512
   //   You specify the XY coordinates of all 3 points.
469 513
 
470 514
   // Enable this to sample the bed in a grid (least squares solution).
@@ -478,7 +522,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
478 522
     #define FRONT_PROBE_BED_POSITION 20
479 523
     #define BACK_PROBE_BED_POSITION 170
480 524
 
481
-    #define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
525
+    #define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
482 526
 
483 527
     // Set the number of grid points per dimension.
484 528
     // You probably don't need more than 3 (squared=9).
@@ -486,25 +530,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
486 530
 
487 531
   #else  // !AUTO_BED_LEVELING_GRID
488 532
 
489
-      // Arbitrary points to probe.
490
-      // A simple cross-product is used to estimate the plane of the bed.
491
-      #define ABL_PROBE_PT_1_X 15
492
-      #define ABL_PROBE_PT_1_Y 180
493
-      #define ABL_PROBE_PT_2_X 15
494
-      #define ABL_PROBE_PT_2_Y 20
495
-      #define ABL_PROBE_PT_3_X 170
496
-      #define ABL_PROBE_PT_3_Y 20
533
+    // Arbitrary points to probe.
534
+    // A simple cross-product is used to estimate the plane of the bed.
535
+    #define ABL_PROBE_PT_1_X 15
536
+    #define ABL_PROBE_PT_1_Y 180
537
+    #define ABL_PROBE_PT_2_X 15
538
+    #define ABL_PROBE_PT_2_Y 20
539
+    #define ABL_PROBE_PT_3_X 170
540
+    #define ABL_PROBE_PT_3_Y 20
497 541
 
498 542
   #endif // AUTO_BED_LEVELING_GRID
499 543
 
500
-  // Offsets to the Z probe relative to the nozzle tip.
544
+  // Z Probe to nozzle (X,Y) offset, relative to (0, 0).
501 545
   // X and Y offsets must be integers.
502
-  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // Z probe to nozzle X offset: -left  +right
503
-  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Z probe to nozzle Y offset: -front +behind
504
-  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z probe to nozzle Z offset: -below (always!)
505
-
506
-  //#define Z_RAISE_BEFORE_HOMING 4       // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
507
-                                        // Be sure you have this distance over your Z_MAX_POS in case.
546
+  //
547
+  // In the following example the X and Y offsets are both positive:
548
+  // #define X_PROBE_OFFSET_FROM_EXTRUDER 10
549
+  // #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
550
+  //
551
+  //    +-- BACK ---+
552
+  //    |           |
553
+  //  L |    (+) P  | R <-- probe (20,20)
554
+  //  E |           | I
555
+  //  F | (-) N (+) | G <-- nozzle (10,10)
556
+  //  T |           | H
557
+  //    |    (-)    | T
558
+  //    |           |
559
+  //    O-- FRONT --+
560
+  //  (0,0)
561
+  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // X offset: -left  [of the nozzle] +right
562
+  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Y offset: -front [of the nozzle] +behind
563
+  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z offset: -below [the nozzle] (always negative!)
508 564
 
509 565
   #define XY_TRAVEL_SPEED 8000         // X and Y axis travel speed between probes, in mm/min.
510 566
 
@@ -512,21 +568,34 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
512 568
   #define Z_RAISE_BETWEEN_PROBINGS 5  // How much the Z axis will be raised when traveling from between next probing points.
513 569
   #define Z_RAISE_AFTER_PROBING 15    // How much the Z axis will be raised after the last probing point.
514 570
 
515
-//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
516
-                                                                            // Useful to retract a deployable Z probe.
571
+  //#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
572
+                                                                             // Useful to retract a deployable Z probe.
573
+
574
+  // Probes are sensors/switches that need to be activated before they can be used
575
+  // and deactivated after the use.
576
+  // Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
577
+
578
+  // A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
579
+  // when the hardware endstops are active.
580
+  //#define FIX_MOUNTED_PROBE
581
+
582
+  // A Servo Probe can be defined in the servo section below.
517 583
 
518
-  //#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
584
+  // An Allen Key Probe is currently predefined only in the delta example configurations.
585
+
586
+  //#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
519 587
   //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
520 588
 
521
-// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
522
-// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
589
+  // If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
590
+  // it is highly recommended you leave Z_SAFE_HOMING enabled!
523 591
 
524
- //#define Z_SAFE_HOMING   // This feature is meant to avoid Z homing with Z probe outside the bed area.
525
-                          // When defined, it will:
526
-                          // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
527
-                          // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
528
-                          // - Position the Z probe in a defined XY point before Z Homing when homing all axis (G28).
529
-                          // - Block Z homing only when the Z probe is outside bed area.
592
+  //#define Z_SAFE_HOMING   // Use the z-min-probe for homing to z-min - not the z-min-endstop.
593
+                            // This feature is meant to avoid Z homing with Z probe outside the bed area.
594
+                            // When defined, it will:
595
+                            // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
596
+                            // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
597
+                            // - Position the Z probe in a defined XY point before Z Homing when homing all axis (G28).
598
+                            // - Block Z homing only when the Z probe is outside bed area.
530 599
 
531 600
   #if ENABLED(Z_SAFE_HOMING)
532 601
 
@@ -535,37 +604,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
535 604
 
536 605
   #endif
537 606
 
538
-  // Support for a dedicated Z probe endstop separate from the Z min endstop.
539
-  // If you would like to use both a Z probe and a Z min endstop together,
540
-  // uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
541
-  // If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
542
-  // Example: To park the head outside the bed area when homing with G28.
543
-  //
544
-  // WARNING:
545
-  // The Z min endstop will need to set properly as it would without a Z probe
546
-  // to prevent head crashes and premature stopping during a print.
547
-  //
548
-  // To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
549
-  // defined in the pins_XXXXX.h file for your control board.
550
-  // If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
551
-  // Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
552
-  // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
553
-  // in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
554
-  // otherwise connect to ground and D32 for normally closed configuration
555
-  // and 5V and D32 for normally open configurations.
556
-  // Normally closed configuration is advised and assumed.
557
-  // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
558
-  // Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
559
-  // Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
560
-  // D32 is currently selected in the RAMPS 1.3/1.4 pin file.
561
-  // All other boards will need changes to the respective pins_XXXXX.h file.
562
-  //
563
-  // WARNING:
564
-  // Setting the wrong pin may have unexpected and potentially disastrous outcomes.
565
-  // Use with caution and do your homework.
566
-  //
567
-  //#define Z_MIN_PROBE_ENDSTOP
568
-
569 607
 #endif // AUTO_BED_LEVELING_FEATURE
570 608
 
571 609
 
@@ -640,6 +678,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
640 678
 #endif
641 679
 
642 680
 //
681
+// Host Keepalive
682
+//
683
+// By default Marlin will send a busy status message to the host
684
+// every 2 seconds when it can't accept commands.
685
+//
686
+//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
687
+
688
+//
643 689
 // M100 Free Memory Watcher
644 690
 //
645 691
 //#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
@@ -659,13 +705,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
659 705
 // @section lcd
660 706
 
661 707
 // Define your display language below. Replace (en) with your language code and uncomment.
662
-// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
708
+// en, pl, fr, de, es, ru, bg, it, pt, pt_utf8, pt-br, pt-br_utf8, fi, an, nl, ca, eu, kana, kana_utf8, cn, cz, test
663 709
 // See also language.h
664 710
 //#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
665 711
 
666 712
 // Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
667 713
 // To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
668
-// See also documentation/LCDLanguageFont.md
714
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
669 715
   #define DISPLAY_CHARSET_HD44780_JAPAN        // this is the most common hardware
670 716
   //#define DISPLAY_CHARSET_HD44780_WESTERN
671 717
   //#define DISPLAY_CHARSET_HD44780_CYRILLIC
@@ -673,12 +719,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
673 719
 //#define ULTRA_LCD  //general LCD support, also 16x2
674 720
 //#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
675 721
 //#define SDSUPPORT // Enable SD Card Support in Hardware Console
676
-// Changed behaviour! If you need SDSUPPORT uncomment it!
677
-//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
678
-//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
722
+                    // Changed behaviour! If you need SDSUPPORT uncomment it!
723
+//#define SPI_SPEED SPI_HALF_SPEED // (also SPI_QUARTER_SPEED, SPI_EIGHTH_SPEED) Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
679 724
 //#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
680 725
 //#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
681 726
 //#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
727
+//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
682 728
 //#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
683 729
 //#define ULTIPANEL  //the UltiPanel as on Thingiverse
684 730
 //#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
@@ -695,13 +741,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
695 741
 
696 742
 // The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
697 743
 // http://panucatt.com
698
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
744
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
699 745
 //#define VIKI2
700 746
 //#define miniVIKI
701 747
 
702 748
 // This is a new controller currently under development.  https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
703 749
 //
704
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
750
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
705 751
 //#define ELB_FULL_GRAPHIC_CONTROLLER
706 752
 //#define SD_DETECT_INVERTED
707 753
 
@@ -716,7 +762,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
716 762
 // The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
717 763
 // http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
718 764
 //
719
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
765
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
720 766
 //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
721 767
 
722 768
 // The RepRapWorld REPRAPWORLD_KEYPAD v1.1
@@ -739,6 +785,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
739 785
 
740 786
 //#define LCD_I2C_SAINSMART_YWROBOT
741 787
 
788
+//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
789
+
742 790
 // PANELOLU2 LCD with status LEDs, separate encoder and click inputs
743 791
 //
744 792
 // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
@@ -752,7 +800,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
752 800
 //#define LCD_I2C_VIKI
753 801
 
754 802
 // SSD1306 OLED generic display support
755
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
803
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
756 804
 //#define U8GLIB_SSD1306
757 805
 
758 806
 // Shift register panels
@@ -764,7 +812,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
764 812
 
765 813
 // @section extras
766 814
 
767
-// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
815
+// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
768 816
 //#define FAST_PWM_FAN
769 817
 
770 818
 // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
@@ -846,19 +894,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
846 894
 // Uncomment below to enable
847 895
 //#define FILAMENT_SENSOR
848 896
 
849
-#define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
850
-#define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
851
-
852 897
 #define DEFAULT_NOMINAL_FILAMENT_DIA 3.00  //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
853
-#define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
854
-#define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
855
-#define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
856 898
 
857
-//defines used in the code
858
-#define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
899
+#if ENABLED(FILAMENT_SENSOR)
900
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
901
+  #define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
902
+
903
+  #define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
904
+  #define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
905
+  #define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
859 906
 
860
-//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
861
-//#define FILAMENT_LCD_DISPLAY
907
+  #define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
908
+
909
+  //When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
910
+  //#define FILAMENT_LCD_DISPLAY
911
+#endif
862 912
 
863 913
 #include "Configuration_adv.h"
864 914
 #include "thermistortables.h"

+ 83
- 58
Marlin/example_configurations/SCARA/Configuration_adv.h Näytä tiedosto

@@ -17,6 +17,20 @@
17 17
 /**
18 18
  * Thermal Protection parameters
19 19
  */
20
+  /**
21
+   * Thermal Protection protects your printer from damage and fire if a
22
+   * thermistor falls out or temperature sensors fail in any way.
23
+   *
24
+   * The issue: If a thermistor falls out or a temperature sensor fails,
25
+   * Marlin can no longer sense the actual temperature. Since a disconnected
26
+   * thermistor reads as a low temperature, the firmware will keep the heater on.
27
+   *
28
+   * The solution: Once the temperature reaches the target, start observing.
29
+   * If the temperature stays too far below the target (hysteresis) for too long (period),
30
+   * the firmware will halt the machine as a safety precaution.
31
+   *
32
+   * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
33
+   */
20 34
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
21 35
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
22 36
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
@@ -26,26 +40,24 @@
26 40
    * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
27 41
    * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
28 42
    * but only if the current temperature is far enough below the target for a reliable test.
43
+   *
44
+   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
45
+   * WATCH_TEMP_INCREASE should not be below 2.
29 46
    */
30 47
   #define WATCH_TEMP_PERIOD 16                // Seconds
31 48
   #define WATCH_TEMP_INCREASE 4               // Degrees Celsius
32 49
 #endif
33 50
 
51
+  /**
52
+   * Thermal Protection parameters for the bed
53
+   * are like the above for the hotends.
54
+   * WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
55
+   */
34 56
 #if ENABLED(THERMAL_PROTECTION_BED)
35 57
   #define THERMAL_PROTECTION_BED_PERIOD 20    // Seconds
36 58
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
37 59
 #endif
38 60
 
39
-/**
40
- * Automatic Temperature:
41
- * The hotend target temperature is calculated by all the buffered lines of gcode.
42
- * The maximum buffered steps/sec of the extruder motor is called "se".
43
- * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
44
- * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
45
- * mintemp and maxtemp. Turn this off by excuting M109 without F*
46
- * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
47
- * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
48
- */
49 61
 #if ENABLED(PIDTEMP)
50 62
   // this adds an experimental additional term to the heating power, proportional to the extrusion speed.
51 63
   // if Kc is chosen well, the additional required power due to increased melting should be compensated.
@@ -56,14 +68,16 @@
56 68
   #endif
57 69
 #endif
58 70
 
59
-
60
-//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
61
-//The maximum buffered steps/sec of the extruder motor are called "se".
62
-//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
63
-// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
64
-// you exit the value by any M109 without F*
65
-// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
66
-// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
71
+/**
72
+ * Automatic Temperature:
73
+ * The hotend target temperature is calculated by all the buffered lines of gcode.
74
+ * The maximum buffered steps/sec of the extruder motor is called "se".
75
+ * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
76
+ * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
77
+ * mintemp and maxtemp. Turn this off by executing M109 without F*
78
+ * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
79
+ * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
80
+ */
67 81
 #define AUTOTEMP
68 82
 #if ENABLED(AUTOTEMP)
69 83
   #define AUTOTEMP_OLDWEIGHT 0.98
@@ -240,7 +254,13 @@
240 254
 #define INVERT_E_STEP_PIN false
241 255
 
242 256
 // Default stepper release if idle. Set to 0 to deactivate.
257
+// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
258
+// Time can be set by M18 and M84.
243 259
 #define DEFAULT_STEPPER_DEACTIVE_TIME 240
260
+#define DISABLE_INACTIVE_X true
261
+#define DISABLE_INACTIVE_Y true
262
+#define DISABLE_INACTIVE_Z true  // set to false if the nozzle will fall down on your printed part when print has finished.
263
+#define DISABLE_INACTIVE_E true
244 264
 
245 265
 #define DEFAULT_MINIMUMFEEDRATE       0.0     // minimum feedrate
246 266
 #define DEFAULT_MINTRAVELFEEDRATE     0.0
@@ -276,6 +296,9 @@
276 296
 // Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
277 297
 #define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
278 298
 
299
+// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
300
+//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
301
+
279 302
 // uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
280 303
 //#define DIGIPOT_I2C
281 304
 // Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
@@ -349,17 +372,16 @@
349 372
   //#define USE_SMALL_INFOFONT
350 373
 #endif // DOGLCD
351 374
 
352
-
353 375
 // @section more
354 376
 
355 377
 // The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
356
-//#define USE_WATCHDOG
378
+#define USE_WATCHDOG
357 379
 
358 380
 #if ENABLED(USE_WATCHDOG)
359
-// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
360
-// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
361
-//  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
362
-//#define WATCHDOG_RESET_MANUAL
381
+  // If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
382
+  // The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
383
+  //  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
384
+  //#define WATCHDOG_RESET_MANUAL
363 385
 #endif
364 386
 
365 387
 // @section lcd
@@ -370,6 +392,7 @@
370 392
 //#define BABYSTEPPING
371 393
 #if ENABLED(BABYSTEPPING)
372 394
   #define BABYSTEP_XY  //not only z, but also XY in the menu. more clutter, more functions
395
+                       //not implemented for deltabots!
373 396
   #define BABYSTEP_INVERT_Z false  //true for inverse movements in Z
374 397
   #define BABYSTEP_MULTIPLICATOR 1 //faster movements
375 398
 #endif
@@ -388,7 +411,6 @@
388 411
 #if ENABLED(ADVANCE)
389 412
   #define EXTRUDER_ADVANCE_K .0
390 413
   #define D_FILAMENT 1.75
391
-  #define STEPS_MM_E 1000
392 414
 #endif
393 415
 
394 416
 // @section extras
@@ -397,7 +419,7 @@
397 419
 #define MM_PER_ARC_SEGMENT 1
398 420
 #define N_ARC_CORRECTION 25
399 421
 
400
-const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
422
+const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
401 423
 
402 424
 // @section temperature
403 425
 
@@ -462,12 +484,15 @@ const unsigned int dropsegments=5; //everything with less than this number of st
462 484
     #define FILAMENTCHANGE_ZADD 10
463 485
     #define FILAMENTCHANGE_FIRSTRETRACT -2
464 486
     #define FILAMENTCHANGE_FINALRETRACT -100
487
+    #define AUTO_FILAMENT_CHANGE                //This extrude filament until you press the button on LCD
488
+    #define AUTO_FILAMENT_CHANGE_LENGTH 0.04    //Extrusion length on automatic extrusion loop
489
+    #define AUTO_FILAMENT_CHANGE_FEEDRATE 300   //Extrusion feedrate (mm/min) on automatic extrusion loop
465 490
   #endif
466 491
 #endif
467 492
 
468 493
 /******************************************************************************\
469 494
  * enable this section if you have TMC26X motor drivers.
470
- * you need to import the TMC26XStepper library into the arduino IDE for this
495
+ * you need to import the TMC26XStepper library into the Arduino IDE for this
471 496
  ******************************************************************************/
472 497
 
473 498
 // @section tmc
@@ -475,52 +500,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
475 500
 //#define HAVE_TMCDRIVER
476 501
 #if ENABLED(HAVE_TMCDRIVER)
477 502
 
478
-//#define X_IS_TMC
503
+  //#define X_IS_TMC
479 504
   #define X_MAX_CURRENT 1000  //in mA
480 505
   #define X_SENSE_RESISTOR 91 //in mOhms
481 506
   #define X_MICROSTEPS 16     //number of microsteps
482 507
 
483
-//#define X2_IS_TMC
508
+  //#define X2_IS_TMC
484 509
   #define X2_MAX_CURRENT 1000  //in mA
485 510
   #define X2_SENSE_RESISTOR 91 //in mOhms
486 511
   #define X2_MICROSTEPS 16     //number of microsteps
487 512
 
488
-//#define Y_IS_TMC
513
+  //#define Y_IS_TMC
489 514
   #define Y_MAX_CURRENT 1000  //in mA
490 515
   #define Y_SENSE_RESISTOR 91 //in mOhms
491 516
   #define Y_MICROSTEPS 16     //number of microsteps
492 517
 
493
-//#define Y2_IS_TMC
518
+  //#define Y2_IS_TMC
494 519
   #define Y2_MAX_CURRENT 1000  //in mA
495 520
   #define Y2_SENSE_RESISTOR 91 //in mOhms
496 521
   #define Y2_MICROSTEPS 16     //number of microsteps
497 522
 
498
-//#define Z_IS_TMC
523
+  //#define Z_IS_TMC
499 524
   #define Z_MAX_CURRENT 1000  //in mA
500 525
   #define Z_SENSE_RESISTOR 91 //in mOhms
501 526
   #define Z_MICROSTEPS 16     //number of microsteps
502 527
 
503
-//#define Z2_IS_TMC
528
+  //#define Z2_IS_TMC
504 529
   #define Z2_MAX_CURRENT 1000  //in mA
505 530
   #define Z2_SENSE_RESISTOR 91 //in mOhms
506 531
   #define Z2_MICROSTEPS 16     //number of microsteps
507 532
 
508
-//#define E0_IS_TMC
533
+  //#define E0_IS_TMC
509 534
   #define E0_MAX_CURRENT 1000  //in mA
510 535
   #define E0_SENSE_RESISTOR 91 //in mOhms
511 536
   #define E0_MICROSTEPS 16     //number of microsteps
512 537
 
513
-//#define E1_IS_TMC
538
+  //#define E1_IS_TMC
514 539
   #define E1_MAX_CURRENT 1000  //in mA
515 540
   #define E1_SENSE_RESISTOR 91 //in mOhms
516 541
   #define E1_MICROSTEPS 16     //number of microsteps
517 542
 
518
-//#define E2_IS_TMC
543
+  //#define E2_IS_TMC
519 544
   #define E2_MAX_CURRENT 1000  //in mA
520 545
   #define E2_SENSE_RESISTOR 91 //in mOhms
521 546
   #define E2_MICROSTEPS 16     //number of microsteps
522 547
 
523
-//#define E3_IS_TMC
548
+  //#define E3_IS_TMC
524 549
   #define E3_MAX_CURRENT 1000  //in mA
525 550
   #define E3_SENSE_RESISTOR 91 //in mOhms
526 551
   #define E3_MICROSTEPS 16     //number of microsteps
@@ -529,7 +554,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
529 554
 
530 555
 /******************************************************************************\
531 556
  * enable this section if you have L6470  motor drivers.
532
- * you need to import the L6470 library into the arduino IDE for this
557
+ * you need to import the L6470 library into the Arduino IDE for this
533 558
  ******************************************************************************/
534 559
 
535 560
 // @section l6470
@@ -537,63 +562,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
537 562
 //#define HAVE_L6470DRIVER
538 563
 #if ENABLED(HAVE_L6470DRIVER)
539 564
 
540
-//#define X_IS_L6470
565
+  //#define X_IS_L6470
541 566
   #define X_MICROSTEPS 16     //number of microsteps
542
-  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
567
+  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
543 568
   #define X_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
544 569
   #define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
545 570
 
546
-//#define X2_IS_L6470
571
+  //#define X2_IS_L6470
547 572
   #define X2_MICROSTEPS 16     //number of microsteps
548
-  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
573
+  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
549 574
   #define X2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
550 575
   #define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
551 576
 
552
-//#define Y_IS_L6470
577
+  //#define Y_IS_L6470
553 578
   #define Y_MICROSTEPS 16     //number of microsteps
554
-  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
579
+  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
555 580
   #define Y_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
556 581
   #define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
557 582
 
558
-//#define Y2_IS_L6470
583
+  //#define Y2_IS_L6470
559 584
   #define Y2_MICROSTEPS 16     //number of microsteps
560
-  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
585
+  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
561 586
   #define Y2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
562 587
   #define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
563 588
 
564
-//#define Z_IS_L6470
589
+  //#define Z_IS_L6470
565 590
   #define Z_MICROSTEPS 16     //number of microsteps
566
-  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
591
+  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
567 592
   #define Z_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
568 593
   #define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
569 594
 
570
-//#define Z2_IS_L6470
595
+  //#define Z2_IS_L6470
571 596
   #define Z2_MICROSTEPS 16     //number of microsteps
572
-  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
597
+  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
573 598
   #define Z2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
574 599
   #define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
575 600
 
576
-//#define E0_IS_L6470
601
+  //#define E0_IS_L6470
577 602
   #define E0_MICROSTEPS 16     //number of microsteps
578
-  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
603
+  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
579 604
   #define E0_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
580 605
   #define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
581 606
 
582
-//#define E1_IS_L6470
607
+  //#define E1_IS_L6470
583 608
   #define E1_MICROSTEPS 16     //number of microsteps
584
-  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
609
+  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
585 610
   #define E1_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
586 611
   #define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
587 612
 
588
-//#define E2_IS_L6470
613
+  //#define E2_IS_L6470
589 614
   #define E2_MICROSTEPS 16     //number of microsteps
590
-  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
615
+  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
591 616
   #define E2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
592 617
   #define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
593 618
 
594
-//#define E3_IS_L6470
619
+  //#define E3_IS_L6470
595 620
   #define E3_MICROSTEPS 16     //number of microsteps
596
-  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
621
+  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
597 622
   #define E3_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
598 623
   #define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
599 624
 

+ 158
- 106
Marlin/example_configurations/TAZ4/Configuration.h Näytä tiedosto

@@ -110,6 +110,7 @@ Here are some standard links for getting your machine calibrated:
110 110
 //--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
111 111
 //
112 112
 //// Temperature sensor settings:
113
+// -3 is thermocouple with MAX31855 (only for sensor 0)
113 114
 // -2 is thermocouple with MAX6675 (only for sensor 0)
114 115
 // -1 is thermocouple with AD595
115 116
 // 0 is not used
@@ -129,6 +130,7 @@ Here are some standard links for getting your machine calibrated:
129 130
 // 13 is 100k Hisens 3950  1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
130 131
 // 20 is the PT100 circuit found in the Ultimainboard V2.x
131 132
 // 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
133
+// 70 is the 100K thermistor found in the bq Hephestos 2
132 134
 //
133 135
 //    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
134 136
 //                          (but gives greater accuracy and more stable PID)
@@ -144,7 +146,7 @@ Here are some standard links for getting your machine calibrated:
144 146
 //     Use it for Testing or Development purposes. NEVER for production machine.
145 147
 //#define DUMMY_THERMISTOR_998_VALUE 25
146 148
 //#define DUMMY_THERMISTOR_999_VALUE 100
147
-// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
149
+// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-3': "Thermocouple + MAX31855 (only for sensor 0)", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
148 150
 #define TEMP_SENSOR_0 7
149 151
 #define TEMP_SENSOR_1 7
150 152
 #define TEMP_SENSOR_2 0
@@ -178,14 +180,9 @@ Here are some standard links for getting your machine calibrated:
178 180
 #define HEATER_3_MAXTEMP 250
179 181
 #define BED_MAXTEMP 150
180 182
 
181
-// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
182
-// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
183
-// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
184
-//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
185
-
186 183
 // If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
187
-//#define EXTRUDER_WATTS (12.0*12.0/6.7) //  P=I^2/R
188
-//#define BED_WATTS (12.0*12.0/1.1)      // P=I^2/R
184
+//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
185
+//#define BED_WATTS (12.0*12.0/1.1)      // P=U^2/R
189 186
 
190 187
 //===========================================================================
191 188
 //============================= PID Settings ================================
@@ -207,7 +204,7 @@ Here are some standard links for getting your machine calibrated:
207 204
   #define PID_INTEGRAL_DRIVE_MAX PID_MAX  //limit for the integral term
208 205
   #define K1 0.95 //smoothing factor within the PID
209 206
 
210
-  // If you are using a preconfigured hotend then you can use one of the value sets by uncommenting it
207
+  // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
211 208
   // Buda 2.0 on 24V
212 209
   #define  DEFAULT_Kp 6
213 210
   #define  DEFAULT_Ki .3
@@ -260,6 +257,7 @@ Here are some standard links for getting your machine calibrated:
260 257
 //#define PID_BED_DEBUG // Sends debug data to the serial port.
261 258
 
262 259
 #if ENABLED(PIDTEMPBED)
260
+
263 261
   #define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
264 262
 
265 263
   //24V 360W silicone heater from NPH on 3mm borosilicate (TAZ 2.2+)
@@ -273,13 +271,13 @@ Here are some standard links for getting your machine calibrated:
273 271
   //#define  DEFAULT_bedKi 60
274 272
   //#define  DEFAULT_bedKd 1800
275 273
 
276
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
274
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
277 275
   //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
278 276
   //#define  DEFAULT_bedKp 10.00
279 277
   //#define  DEFAULT_bedKi .023
280 278
   //#define  DEFAULT_bedKd 305.4
281 279
 
282
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
280
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
283 281
   //from pidautotune
284 282
   //#define  DEFAULT_bedKp 97.1
285 283
   //#define  DEFAULT_bedKi 1.41
@@ -304,16 +302,15 @@ Here are some standard links for getting your machine calibrated:
304 302
 //===========================================================================
305 303
 
306 304
 /**
307
- * Thermal Runaway Protection protects your printer from damage and fire if a
305
+ * Thermal Protection protects your printer from damage and fire if a
308 306
  * thermistor falls out or temperature sensors fail in any way.
309 307
  *
310 308
  * The issue: If a thermistor falls out or a temperature sensor fails,
311 309
  * Marlin can no longer sense the actual temperature. Since a disconnected
312 310
  * thermistor reads as a low temperature, the firmware will keep the heater on.
313 311
  *
314
- * The solution: Once the temperature reaches the target, start observing.
315
- * If the temperature stays too far below the target (hysteresis) for too long,
316
- * the firmware will halt as a safety precaution.
312
+ * If you get "Thermal Runaway" or "Heating failed" errors the
313
+ * details can be tuned in Configuration_adv.h
317 314
  */
318 315
 
319 316
 #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
@@ -361,10 +358,52 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
361 358
 #define DISABLE_MAX_ENDSTOPS
362 359
 //#define DISABLE_MIN_ENDSTOPS
363 360
 
364
-// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
365
-// This only affects a Z probe endstop if you have separate Z min endstop as well and have
366
-// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
367
-// this has no effect.
361
+//===========================================================================
362
+//============================= Z Probe Options =============================
363
+//===========================================================================
364
+
365
+// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
366
+// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
367
+//
368
+// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
369
+//
370
+// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
371
+// Example: To park the head outside the bed area when homing with G28.
372
+//
373
+// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
374
+//
375
+// For a servo-based Z probe, you must set up servo support below, including
376
+// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
377
+//
378
+// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
379
+// - Use 5V for powered (usu. inductive) sensors.
380
+// - Otherwise connect:
381
+//   - normally-closed switches to GND and D32.
382
+//   - normally-open switches to 5V and D32.
383
+//
384
+// Normally-closed switches are advised and are the default.
385
+//
386
+// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
387
+// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
388
+// default pin for all RAMPS-based boards. Some other boards map differently.
389
+// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
390
+//
391
+// WARNING:
392
+// Setting the wrong pin may have unexpected and potentially disastrous consequences.
393
+// Use with caution and do your homework.
394
+//
395
+//#define Z_MIN_PROBE_ENDSTOP
396
+
397
+// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
398
+// The Z_MIN_PIN will then be used for both Z-homing and probing.
399
+#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
400
+
401
+// To use a probe you must enable one of the two options above!
402
+
403
+// This option disables the use of the Z_MIN_PROBE_PIN
404
+// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
405
+// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
406
+// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
368 407
 //#define DISABLE_Z_MIN_PROBE_ENDSTOP
369 408
 
370 409
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
@@ -374,11 +413,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
374 413
 #define Z_ENABLE_ON 0
375 414
 #define E_ENABLE_ON 0 // For all extruders
376 415
 
377
-// Disables axis when it's not being used.
416
+// Disables axis stepper immediately when it's not being used.
378 417
 // WARNING: When motors turn off there is a chance of losing position accuracy!
379 418
 #define DISABLE_X false
380 419
 #define DISABLE_Y false
381 420
 #define DISABLE_Z false
421
+// Warn on display about possibly reduced accuracy
422
+//#define DISABLE_REDUCED_ACCURACY_WARNING
382 423
 
383 424
 // @section extruder
384 425
 
@@ -401,6 +442,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
401 442
 #define INVERT_E3_DIR true
402 443
 
403 444
 // @section homing
445
+//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
446
+                                    // Be sure you have this distance over your Z_MAX_POS in case.
404 447
 
405 448
 // ENDSTOP SETTINGS:
406 449
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
@@ -436,24 +479,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
436 479
 #endif
437 480
 
438 481
 //===========================================================================
439
-//=========================== Manual Bed Leveling ===========================
482
+//============================ Mesh Bed Leveling ============================
440 483
 //===========================================================================
441 484
 
442
-//#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
443 485
 //#define MESH_BED_LEVELING    // Enable mesh bed leveling.
444 486
 
445
-#if ENABLED(MANUAL_BED_LEVELING)
446
-  #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
447
-#endif  // MANUAL_BED_LEVELING
448
-
449 487
 #if ENABLED(MESH_BED_LEVELING)
450 488
   #define MESH_MIN_X 10
451
-  #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
489
+  #define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
452 490
   #define MESH_MIN_Y 10
453
-  #define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
491
+  #define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
454 492
   #define MESH_NUM_X_POINTS 3  // Don't use more than 7 points per axis, implementation limited.
455 493
   #define MESH_NUM_Y_POINTS 3
456 494
   #define MESH_HOME_SEARCH_Z 4  // Z after Home, bed somewhere below but above 0.0.
495
+
496
+  //#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
497
+
498
+  #if ENABLED(MANUAL_BED_LEVELING)
499
+    #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
500
+  #endif  // MANUAL_BED_LEVELING
501
+
457 502
 #endif  // MESH_BED_LEVELING
458 503
 
459 504
 //===========================================================================
@@ -462,10 +507,11 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
462 507
 
463 508
 // @section bedlevel
464 509
 
465
-//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line).
466
-#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z probe repeatability test will be included if auto bed leveling is enabled.
510
+//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
511
+//#define DEBUG_LEVELING_FEATURE
512
+#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
467 513
 
468
-#if ENABLED(ENABLE_AUTO_BED_LEVELING)
514
+#if ENABLED(AUTO_BED_LEVELING_FEATURE)
469 515
 
470 516
   // There are 2 different ways to specify probing locations:
471 517
   //
@@ -475,7 +521,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
475 521
   //   This mode is preferred because there are more measurements.
476 522
   //
477 523
   // - "3-point" mode
478
-  //   Probe 3 arbitrary points on the bed (that aren't colinear)
524
+  //   Probe 3 arbitrary points on the bed (that aren't collinear)
479 525
   //   You specify the XY coordinates of all 3 points.
480 526
 
481 527
   // Enable this to sample the bed in a grid (least squares solution).
@@ -497,25 +543,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
497 543
 
498 544
   #else  // !AUTO_BED_LEVELING_GRID
499 545
 
500
-      // Arbitrary points to probe.
501
-      // A simple cross-product is used to estimate the plane of the bed.
502
-      #define ABL_PROBE_PT_1_X 15
503
-      #define ABL_PROBE_PT_1_Y 180
504
-      #define ABL_PROBE_PT_2_X 15
505
-      #define ABL_PROBE_PT_2_Y 20
506
-      #define ABL_PROBE_PT_3_X 170
507
-      #define ABL_PROBE_PT_3_Y 20
546
+    // Arbitrary points to probe.
547
+    // A simple cross-product is used to estimate the plane of the bed.
548
+    #define ABL_PROBE_PT_1_X 15
549
+    #define ABL_PROBE_PT_1_Y 180
550
+    #define ABL_PROBE_PT_2_X 15
551
+    #define ABL_PROBE_PT_2_Y 20
552
+    #define ABL_PROBE_PT_3_X 170
553
+    #define ABL_PROBE_PT_3_Y 20
508 554
 
509 555
   #endif // AUTO_BED_LEVELING_GRID
510 556
 
511
-  // Offsets to the Z probe relative to the nozzle tip.
557
+  // Z Probe to nozzle (X,Y) offset, relative to (0, 0).
512 558
   // X and Y offsets must be integers.
513
-  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // Z probe to nozzle X offset: -left  +right
514
-  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Z probe to nozzle Y offset: -front +behind
515
-  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z probe to nozzle Z offset: -below (always!)
516
-
517
-  #define Z_RAISE_BEFORE_HOMING 4       // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
518
-                                        // Be sure you have this distance over your Z_MAX_POS in case.
559
+  //
560
+  // In the following example the X and Y offsets are both positive:
561
+  // #define X_PROBE_OFFSET_FROM_EXTRUDER 10
562
+  // #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
563
+  //
564
+  //    +-- BACK ---+
565
+  //    |           |
566
+  //  L |    (+) P  | R <-- probe (20,20)
567
+  //  E |           | I
568
+  //  F | (-) N (+) | G <-- nozzle (10,10)
569
+  //  T |           | H
570
+  //    |    (-)    | T
571
+  //    |           |
572
+  //    O-- FRONT --+
573
+  //  (0,0)
574
+  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // X offset: -left  [of the nozzle] +right
575
+  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Y offset: -front [of the nozzle] +behind
576
+  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z offset: -below [the nozzle] (always negative!)
519 577
 
520 578
   #define XY_TRAVEL_SPEED 8000         // X and Y axis travel speed between probes, in mm/min.
521 579
 
@@ -523,16 +581,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
523 581
   #define Z_RAISE_BETWEEN_PROBINGS 5  // How much the Z axis will be raised when traveling from between next probing points.
524 582
   #define Z_RAISE_AFTER_PROBING 15    // How much the Z axis will be raised after the last probing point.
525 583
 
526
-//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
527
-                                                                            // Useful to retract a deployable Z probe.
584
+  //#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
585
+                                                                             // Useful to retract a deployable Z probe.
586
+
587
+  // Probes are sensors/switches that need to be activated before they can be used
588
+  // and deactivated after the use.
589
+  // Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
590
+
591
+  // A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
592
+  // when the hardware endstops are active.
593
+  //#define FIX_MOUNTED_PROBE
594
+
595
+  // A Servo Probe can be defined in the servo section below.
528 596
 
529
-  //#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
597
+  // An Allen Key Probe is currently predefined only in the delta example configurations.
598
+
599
+  //#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
530 600
   //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
531 601
 
532
-// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
533
-// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
602
+  // If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
603
+  // it is highly recommended you leave Z_SAFE_HOMING enabled!
534 604
 
535
-  #define Z_SAFE_HOMING   // This feature is meant to avoid Z homing with Z probe outside the bed area.
605
+  #define Z_SAFE_HOMING   // Use the z-min-probe for homing to z-min - not the z-min-endstop.
606
+                          // This feature is meant to avoid Z homing with Z probe outside the bed area.
536 607
                           // When defined, it will:
537 608
                           // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
538 609
                           // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
@@ -546,38 +617,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
546 617
 
547 618
   #endif
548 619
 
549
-  // Support for a dedicated Z probe endstop separate from the Z min endstop.
550
-  // If you would like to use both a Z probe and a Z min endstop together,
551
-  // uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
552
-  // If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
553
-  // Example: To park the head outside the bed area when homing with G28.
554
-  //
555
-  // WARNING:
556
-  // The Z min endstop will need to set properly as it would without a Z probe
557
-  // to prevent head crashes and premature stopping during a print.
558
-  //
559
-  // To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
560
-  // defined in the pins_XXXXX.h file for your control board.
561
-  // If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
562
-  // Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
563
-  // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
564
-  // in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
565
-  // otherwise connect to ground and D32 for normally closed configuration
566
-  // and 5V and D32 for normally open configurations.
567
-  // Normally closed configuration is advised and assumed.
568
-  // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
569
-  // Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
570
-  // Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
571
-  // D32 is currently selected in the RAMPS 1.3/1.4 pin file.
572
-  // All other boards will need changes to the respective pins_XXXXX.h file.
573
-  //
574
-  // WARNING:
575
-  // Setting the wrong pin may have unexpected and potentially disastrous outcomes.
576
-  // Use with caution and do your homework.
577
-  //
578
-  //#define Z_MIN_PROBE_ENDSTOP
579
-
580
-#endif // ENABLE_AUTO_BED_LEVELING
620
+#endif // AUTO_BED_LEVELING_FEATURE
581 621
 
582 622
 
583 623
 // @section homing
@@ -628,7 +668,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
628 668
 // Custom M code points
629 669
 #define CUSTOM_M_CODES
630 670
 #if ENABLED(CUSTOM_M_CODES)
631
-  #if ENABLED(ENABLE_AUTO_BED_LEVELING)
671
+  #if ENABLED(AUTO_BED_LEVELING_FEATURE)
632 672
     #define CUSTOM_M_CODE_SET_Z_PROBE_OFFSET 851
633 673
     #define Z_PROBE_OFFSET_RANGE_MIN -20
634 674
     #define Z_PROBE_OFFSET_RANGE_MAX 20
@@ -651,6 +691,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
651 691
 #endif
652 692
 
653 693
 //
694
+// Host Keepalive
695
+//
696
+// By default Marlin will send a busy status message to the host
697
+// every 2 seconds when it can't accept commands.
698
+//
699
+//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
700
+
701
+//
654 702
 // M100 Free Memory Watcher
655 703
 //
656 704
 //#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
@@ -670,13 +718,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
670 718
 // @section lcd
671 719
 
672 720
 // Define your display language below. Replace (en) with your language code and uncomment.
673
-// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
721
+// en, pl, fr, de, es, ru, bg, it, pt, pt_utf8, pt-br, pt-br_utf8, fi, an, nl, ca, eu, kana, kana_utf8, cn, cz, test
674 722
 // See also language.h
675 723
 #define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
676 724
 
677 725
 // Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
678 726
 // To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
679
-// See also documentation/LCDLanguageFont.md
727
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
680 728
   #define DISPLAY_CHARSET_HD44780_JAPAN        // this is the most common hardware
681 729
   //#define DISPLAY_CHARSET_HD44780_WESTERN
682 730
   //#define DISPLAY_CHARSET_HD44780_CYRILLIC
@@ -684,12 +732,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
684 732
 //#define ULTRA_LCD  //general LCD support, also 16x2
685 733
 //#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
686 734
 //#define SDSUPPORT // Enable SD Card Support in Hardware Console
687
-// Changed behaviour! If you need SDSUPPORT uncomment it!
688
-//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
689
-//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
735
+                    // Changed behaviour! If you need SDSUPPORT uncomment it!
736
+//#define SPI_SPEED SPI_HALF_SPEED // (also SPI_QUARTER_SPEED, SPI_EIGHTH_SPEED) Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
690 737
 //#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
691 738
 #define ENCODER_PULSES_PER_STEP 2 // Increase if you have a high resolution encoder
692 739
 #define ENCODER_STEPS_PER_MENU_ITEM 1 // Set according to ENCODER_PULSES_PER_STEP or your liking
740
+//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
693 741
 //#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
694 742
 //#define ULTIPANEL  //the UltiPanel as on Thingiverse
695 743
 //#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
@@ -706,13 +754,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
706 754
 
707 755
 // The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
708 756
 // http://panucatt.com
709
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
757
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
710 758
 //#define VIKI2
711 759
 //#define miniVIKI
712 760
 
713 761
 // This is a new controller currently under development.  https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
714 762
 //
715
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
763
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
716 764
 //#define ELB_FULL_GRAPHIC_CONTROLLER
717 765
 //#define SD_DETECT_INVERTED
718 766
 
@@ -727,7 +775,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
727 775
 // The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
728 776
 // http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
729 777
 //
730
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
778
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
731 779
 #define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
732 780
 
733 781
 // The RepRapWorld REPRAPWORLD_KEYPAD v1.1
@@ -750,6 +798,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
750 798
 
751 799
 //#define LCD_I2C_SAINSMART_YWROBOT
752 800
 
801
+//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
802
+
753 803
 // PANELOLU2 LCD with status LEDs, separate encoder and click inputs
754 804
 //
755 805
 // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
@@ -763,7 +813,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
763 813
 //#define LCD_I2C_VIKI
764 814
 
765 815
 // SSD1306 OLED generic display support
766
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
816
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
767 817
 //#define U8GLIB_SSD1306
768 818
 
769 819
 // Shift register panels
@@ -775,7 +825,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
775 825
 
776 826
 // @section extras
777 827
 
778
-// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
828
+// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
779 829
 #define FAST_PWM_FAN
780 830
 
781 831
 // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
@@ -857,19 +907,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
857 907
 // Uncomment below to enable
858 908
 //#define FILAMENT_SENSOR
859 909
 
860
-#define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
861
-#define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
862
-
863 910
 #define DEFAULT_NOMINAL_FILAMENT_DIA 3.00  //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
864
-#define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
865
-#define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
866
-#define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
867 911
 
868
-//defines used in the code
869
-#define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
912
+#if ENABLED(FILAMENT_SENSOR)
913
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
914
+  #define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
915
+
916
+  #define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
917
+  #define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
918
+  #define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
870 919
 
871
-//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
872
-//#define FILAMENT_LCD_DISPLAY
920
+  #define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
921
+
922
+  //When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
923
+  //#define FILAMENT_LCD_DISPLAY
924
+#endif
873 925
 
874 926
 #include "Configuration_adv.h"
875 927
 #include "thermistortables.h"

+ 71
- 41
Marlin/example_configurations/TAZ4/Configuration_adv.h Näytä tiedosto

@@ -17,6 +17,20 @@
17 17
 /**
18 18
  * Thermal Protection parameters
19 19
  */
20
+  /**
21
+   * Thermal Protection protects your printer from damage and fire if a
22
+   * thermistor falls out or temperature sensors fail in any way.
23
+   *
24
+   * The issue: If a thermistor falls out or a temperature sensor fails,
25
+   * Marlin can no longer sense the actual temperature. Since a disconnected
26
+   * thermistor reads as a low temperature, the firmware will keep the heater on.
27
+   *
28
+   * The solution: Once the temperature reaches the target, start observing.
29
+   * If the temperature stays too far below the target (hysteresis) for too long (period),
30
+   * the firmware will halt the machine as a safety precaution.
31
+   *
32
+   * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
33
+   */
20 34
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
21 35
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
22 36
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
@@ -26,11 +40,19 @@
26 40
    * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
27 41
    * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
28 42
    * but only if the current temperature is far enough below the target for a reliable test.
43
+   *
44
+   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
45
+   * WATCH_TEMP_INCREASE should not be below 2.
29 46
    */
30 47
   #define WATCH_TEMP_PERIOD 16                // Seconds
31 48
   #define WATCH_TEMP_INCREASE 4               // Degrees Celsius
32 49
 #endif
33 50
 
51
+  /**
52
+   * Thermal Protection parameters for the bed
53
+   * are like the above for the hotends.
54
+   * WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
55
+   */
34 56
 #if ENABLED(THERMAL_PROTECTION_BED)
35 57
   #define THERMAL_PROTECTION_BED_PERIOD 20    // Seconds
36 58
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
@@ -52,7 +74,7 @@
52 74
  * The maximum buffered steps/sec of the extruder motor is called "se".
53 75
  * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
54 76
  * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
55
- * mintemp and maxtemp. Turn this off by excuting M109 without F*
77
+ * mintemp and maxtemp. Turn this off by executing M109 without F*
56 78
  * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
57 79
  * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
58 80
  */
@@ -240,7 +262,13 @@
240 262
 #define INVERT_E_STEP_PIN false
241 263
 
242 264
 // Default stepper release if idle. Set to 0 to deactivate.
265
+// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
266
+// Time can be set by M18 and M84.
243 267
 #define DEFAULT_STEPPER_DEACTIVE_TIME 60
268
+#define DISABLE_INACTIVE_X true
269
+#define DISABLE_INACTIVE_Y true
270
+#define DISABLE_INACTIVE_Z true  // set to false if the nozzle will fall down on your printed part when print has finished.
271
+#define DISABLE_INACTIVE_E true
244 272
 
245 273
 #define DEFAULT_MINIMUMFEEDRATE       0.0     // minimum feedrate
246 274
 #define DEFAULT_MINTRAVELFEEDRATE     0.0
@@ -276,6 +304,9 @@
276 304
 // Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
277 305
 #define DIGIPOT_MOTOR_CURRENT {175,175,240,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
278 306
 
307
+// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
308
+//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
309
+
279 310
 // uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
280 311
 //#define DIGIPOT_I2C
281 312
 // Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
@@ -352,13 +383,13 @@
352 383
 // @section more
353 384
 
354 385
 // The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
355
-//#define USE_WATCHDOG
386
+#define USE_WATCHDOG
356 387
 
357 388
 #if ENABLED(USE_WATCHDOG)
358
-// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
359
-// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
360
-//  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
361
-//#define WATCHDOG_RESET_MANUAL
389
+  // If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
390
+  // The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
391
+  //  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
392
+  //#define WATCHDOG_RESET_MANUAL
362 393
 #endif
363 394
 
364 395
 // @section lcd
@@ -369,7 +400,7 @@
369 400
 //#define BABYSTEPPING
370 401
 #if ENABLED(BABYSTEPPING)
371 402
   #define BABYSTEP_XY  //not only z, but also XY in the menu. more clutter, more functions
372
-                       //not implemented for CoreXY and deltabots!
403
+                       //not implemented for deltabots!
373 404
   #define BABYSTEP_INVERT_Z false  //true for inverse movements in Z
374 405
   #define BABYSTEP_MULTIPLICATOR 1 //faster movements
375 406
 #endif
@@ -388,7 +419,6 @@
388 419
 #if ENABLED(ADVANCE)
389 420
   #define EXTRUDER_ADVANCE_K .0
390 421
   #define D_FILAMENT 2.85
391
-  #define STEPS_MM_E 836
392 422
 #endif
393 423
 
394 424
 // @section extras
@@ -397,7 +427,7 @@
397 427
 #define MM_PER_ARC_SEGMENT 1
398 428
 #define N_ARC_CORRECTION 25
399 429
 
400
-const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
430
+const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
401 431
 
402 432
 // @section temperature
403 433
 
@@ -470,7 +500,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
470 500
 
471 501
 /******************************************************************************\
472 502
  * enable this section if you have TMC26X motor drivers.
473
- * you need to import the TMC26XStepper library into the arduino IDE for this
503
+ * you need to import the TMC26XStepper library into the Arduino IDE for this
474 504
  ******************************************************************************/
475 505
 
476 506
 // @section tmc
@@ -478,52 +508,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
478 508
 //#define HAVE_TMCDRIVER
479 509
 #if ENABLED(HAVE_TMCDRIVER)
480 510
 
481
-//#define X_IS_TMC
511
+  //#define X_IS_TMC
482 512
   #define X_MAX_CURRENT 1000  //in mA
483 513
   #define X_SENSE_RESISTOR 91 //in mOhms
484 514
   #define X_MICROSTEPS 16     //number of microsteps
485 515
 
486
-//#define X2_IS_TMC
516
+  //#define X2_IS_TMC
487 517
   #define X2_MAX_CURRENT 1000  //in mA
488 518
   #define X2_SENSE_RESISTOR 91 //in mOhms
489 519
   #define X2_MICROSTEPS 16     //number of microsteps
490 520
 
491
-//#define Y_IS_TMC
521
+  //#define Y_IS_TMC
492 522
   #define Y_MAX_CURRENT 1000  //in mA
493 523
   #define Y_SENSE_RESISTOR 91 //in mOhms
494 524
   #define Y_MICROSTEPS 16     //number of microsteps
495 525
 
496
-//#define Y2_IS_TMC
526
+  //#define Y2_IS_TMC
497 527
   #define Y2_MAX_CURRENT 1000  //in mA
498 528
   #define Y2_SENSE_RESISTOR 91 //in mOhms
499 529
   #define Y2_MICROSTEPS 16     //number of microsteps
500 530
 
501
-//#define Z_IS_TMC
531
+  //#define Z_IS_TMC
502 532
   #define Z_MAX_CURRENT 1000  //in mA
503 533
   #define Z_SENSE_RESISTOR 91 //in mOhms
504 534
   #define Z_MICROSTEPS 16     //number of microsteps
505 535
 
506
-//#define Z2_IS_TMC
536
+  //#define Z2_IS_TMC
507 537
   #define Z2_MAX_CURRENT 1000  //in mA
508 538
   #define Z2_SENSE_RESISTOR 91 //in mOhms
509 539
   #define Z2_MICROSTEPS 16     //number of microsteps
510 540
 
511
-//#define E0_IS_TMC
541
+  //#define E0_IS_TMC
512 542
   #define E0_MAX_CURRENT 1000  //in mA
513 543
   #define E0_SENSE_RESISTOR 91 //in mOhms
514 544
   #define E0_MICROSTEPS 16     //number of microsteps
515 545
 
516
-//#define E1_IS_TMC
546
+  //#define E1_IS_TMC
517 547
   #define E1_MAX_CURRENT 1000  //in mA
518 548
   #define E1_SENSE_RESISTOR 91 //in mOhms
519 549
   #define E1_MICROSTEPS 16     //number of microsteps
520 550
 
521
-//#define E2_IS_TMC
551
+  //#define E2_IS_TMC
522 552
   #define E2_MAX_CURRENT 1000  //in mA
523 553
   #define E2_SENSE_RESISTOR 91 //in mOhms
524 554
   #define E2_MICROSTEPS 16     //number of microsteps
525 555
 
526
-//#define E3_IS_TMC
556
+  //#define E3_IS_TMC
527 557
   #define E3_MAX_CURRENT 1000  //in mA
528 558
   #define E3_SENSE_RESISTOR 91 //in mOhms
529 559
   #define E3_MICROSTEPS 16     //number of microsteps
@@ -532,7 +562,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
532 562
 
533 563
 /******************************************************************************\
534 564
  * enable this section if you have L6470  motor drivers.
535
- * you need to import the L6470 library into the arduino IDE for this
565
+ * you need to import the L6470 library into the Arduino IDE for this
536 566
  ******************************************************************************/
537 567
 
538 568
 // @section l6470
@@ -540,63 +570,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
540 570
 //#define HAVE_L6470DRIVER
541 571
 #if ENABLED(HAVE_L6470DRIVER)
542 572
 
543
-//#define X_IS_L6470
573
+  //#define X_IS_L6470
544 574
   #define X_MICROSTEPS 16     //number of microsteps
545
-  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
575
+  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
546 576
   #define X_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
547 577
   #define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
548 578
 
549
-//#define X2_IS_L6470
579
+  //#define X2_IS_L6470
550 580
   #define X2_MICROSTEPS 16     //number of microsteps
551
-  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
581
+  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
552 582
   #define X2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
553 583
   #define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
554 584
 
555
-//#define Y_IS_L6470
585
+  //#define Y_IS_L6470
556 586
   #define Y_MICROSTEPS 16     //number of microsteps
557
-  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
587
+  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
558 588
   #define Y_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
559 589
   #define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
560 590
 
561
-//#define Y2_IS_L6470
591
+  //#define Y2_IS_L6470
562 592
   #define Y2_MICROSTEPS 16     //number of microsteps
563
-  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
593
+  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
564 594
   #define Y2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
565 595
   #define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
566 596
 
567
-//#define Z_IS_L6470
597
+  //#define Z_IS_L6470
568 598
   #define Z_MICROSTEPS 16     //number of microsteps
569
-  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
599
+  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
570 600
   #define Z_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
571 601
   #define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
572 602
 
573
-//#define Z2_IS_L6470
603
+  //#define Z2_IS_L6470
574 604
   #define Z2_MICROSTEPS 16     //number of microsteps
575
-  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
605
+  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
576 606
   #define Z2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
577 607
   #define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
578 608
 
579
-//#define E0_IS_L6470
609
+  //#define E0_IS_L6470
580 610
   #define E0_MICROSTEPS 16     //number of microsteps
581
-  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
611
+  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
582 612
   #define E0_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
583 613
   #define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
584 614
 
585
-//#define E1_IS_L6470
615
+  //#define E1_IS_L6470
586 616
   #define E1_MICROSTEPS 16     //number of microsteps
587
-  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
617
+  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
588 618
   #define E1_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
589 619
   #define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
590 620
 
591
-//#define E2_IS_L6470
621
+  //#define E2_IS_L6470
592 622
   #define E2_MICROSTEPS 16     //number of microsteps
593
-  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
623
+  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
594 624
   #define E2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
595 625
   #define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
596 626
 
597
-//#define E3_IS_L6470
627
+  //#define E3_IS_L6470
598 628
   #define E3_MICROSTEPS 16     //number of microsteps
599
-  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
629
+  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
600 630
   #define E3_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
601 631
   #define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
602 632
 

+ 153
- 102
Marlin/example_configurations/WITBOX/Configuration.h Näytä tiedosto

@@ -70,7 +70,7 @@ Here are some standard links for getting your machine calibrated:
70 70
 // The following define selects which electronics board you have.
71 71
 // Please choose the name from boards.h that matches your setup
72 72
 #ifndef MOTHERBOARD
73
-  #define MOTHERBOARD BOARD_RAMPS_13_EFB
73
+  #define MOTHERBOARD BOARD_RAMPS_14_EFB
74 74
 #endif
75 75
 
76 76
 // Optional custom name for your RepStrap or other custom machine
@@ -113,6 +113,7 @@ Here are some standard links for getting your machine calibrated:
113 113
 //--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
114 114
 //
115 115
 //// Temperature sensor settings:
116
+// -3 is thermocouple with MAX31855 (only for sensor 0)
116 117
 // -2 is thermocouple with MAX6675 (only for sensor 0)
117 118
 // -1 is thermocouple with AD595
118 119
 // 0 is not used
@@ -132,6 +133,7 @@ Here are some standard links for getting your machine calibrated:
132 133
 // 13 is 100k Hisens 3950  1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
133 134
 // 20 is the PT100 circuit found in the Ultimainboard V2.x
134 135
 // 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
136
+// 70 is the 100K thermistor found in the bq Hephestos 2
135 137
 //
136 138
 //    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
137 139
 //                          (but gives greater accuracy and more stable PID)
@@ -147,7 +149,7 @@ Here are some standard links for getting your machine calibrated:
147 149
 //     Use it for Testing or Development purposes. NEVER for production machine.
148 150
 //#define DUMMY_THERMISTOR_998_VALUE 25
149 151
 //#define DUMMY_THERMISTOR_999_VALUE 100
150
-// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
152
+// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-3': "Thermocouple + MAX31855 (only for sensor 0)", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
151 153
 #define TEMP_SENSOR_0 1
152 154
 #define TEMP_SENSOR_1 0
153 155
 #define TEMP_SENSOR_2 0
@@ -181,14 +183,9 @@ Here are some standard links for getting your machine calibrated:
181 183
 #define HEATER_3_MAXTEMP 260
182 184
 #define BED_MAXTEMP 150
183 185
 
184
-// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
185
-// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
186
-// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
187
-//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
188
-
189 186
 // If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
190
-//#define EXTRUDER_WATTS (12.0*12.0/6.7) //  P=I^2/R
191
-//#define BED_WATTS (12.0*12.0/1.1)      // P=I^2/R
187
+//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
188
+//#define BED_WATTS (12.0*12.0/1.1)      // P=U^2/R
192 189
 
193 190
 //===========================================================================
194 191
 //============================= PID Settings ================================
@@ -245,13 +242,13 @@ Here are some standard links for getting your machine calibrated:
245 242
 
246 243
   #define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
247 244
 
248
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
245
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
249 246
   //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
250 247
   #define  DEFAULT_bedKp 10.00
251 248
   #define  DEFAULT_bedKi .023
252 249
   #define  DEFAULT_bedKd 305.4
253 250
 
254
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
251
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
255 252
   //from pidautotune
256 253
   //#define  DEFAULT_bedKp 97.1
257 254
   //#define  DEFAULT_bedKi 1.41
@@ -276,16 +273,15 @@ Here are some standard links for getting your machine calibrated:
276 273
 //===========================================================================
277 274
 
278 275
 /**
279
- * Thermal Runaway Protection protects your printer from damage and fire if a
276
+ * Thermal Protection protects your printer from damage and fire if a
280 277
  * thermistor falls out or temperature sensors fail in any way.
281 278
  *
282 279
  * The issue: If a thermistor falls out or a temperature sensor fails,
283 280
  * Marlin can no longer sense the actual temperature. Since a disconnected
284 281
  * thermistor reads as a low temperature, the firmware will keep the heater on.
285 282
  *
286
- * The solution: Once the temperature reaches the target, start observing.
287
- * If the temperature stays too far below the target (hysteresis) for too long,
288
- * the firmware will halt as a safety precaution.
283
+ * If you get "Thermal Runaway" or "Heating failed" errors the
284
+ * details can be tuned in Configuration_adv.h
289 285
  */
290 286
 
291 287
 #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
@@ -333,10 +329,52 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
333 329
 //#define DISABLE_MAX_ENDSTOPS
334 330
 //#define DISABLE_MIN_ENDSTOPS
335 331
 
336
-// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
337
-// This only affects a Z probe endstop if you have separate Z min endstop as well and have
338
-// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
339
-// this has no effect.
332
+//===========================================================================
333
+//============================= Z Probe Options =============================
334
+//===========================================================================
335
+
336
+// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
337
+// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
338
+//
339
+// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
340
+//
341
+// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
342
+// Example: To park the head outside the bed area when homing with G28.
343
+//
344
+// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
345
+//
346
+// For a servo-based Z probe, you must set up servo support below, including
347
+// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
348
+//
349
+// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
350
+// - Use 5V for powered (usu. inductive) sensors.
351
+// - Otherwise connect:
352
+//   - normally-closed switches to GND and D32.
353
+//   - normally-open switches to 5V and D32.
354
+//
355
+// Normally-closed switches are advised and are the default.
356
+//
357
+// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
358
+// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
359
+// default pin for all RAMPS-based boards. Some other boards map differently.
360
+// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
361
+//
362
+// WARNING:
363
+// Setting the wrong pin may have unexpected and potentially disastrous consequences.
364
+// Use with caution and do your homework.
365
+//
366
+//#define Z_MIN_PROBE_ENDSTOP
367
+
368
+// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
369
+// The Z_MIN_PIN will then be used for both Z-homing and probing.
370
+#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
371
+
372
+// To use a probe you must enable one of the two options above!
373
+
374
+// This option disables the use of the Z_MIN_PROBE_PIN
375
+// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
376
+// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
377
+// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
340 378
 //#define DISABLE_Z_MIN_PROBE_ENDSTOP
341 379
 
342 380
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
@@ -346,11 +384,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
346 384
 #define Z_ENABLE_ON 0
347 385
 #define E_ENABLE_ON 0 // For all extruders
348 386
 
349
-// Disables axis when it's not being used.
387
+// Disables axis stepper immediately when it's not being used.
350 388
 // WARNING: When motors turn off there is a chance of losing position accuracy!
351 389
 #define DISABLE_X false
352 390
 #define DISABLE_Y false
353 391
 #define DISABLE_Z true
392
+// Warn on display about possibly reduced accuracy
393
+//#define DISABLE_REDUCED_ACCURACY_WARNING
354 394
 
355 395
 // @section extruder
356 396
 
@@ -373,6 +413,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
373 413
 #define INVERT_E3_DIR false
374 414
 
375 415
 // @section homing
416
+//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
417
+                                    // Be sure you have this distance over your Z_MAX_POS in case.
376 418
 
377 419
 // ENDSTOP SETTINGS:
378 420
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
@@ -408,24 +450,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
408 450
 #endif
409 451
 
410 452
 //===========================================================================
411
-//=========================== Manual Bed Leveling ===========================
453
+//============================ Mesh Bed Leveling ============================
412 454
 //===========================================================================
413 455
 
414
-//#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
415 456
 //#define MESH_BED_LEVELING    // Enable mesh bed leveling.
416 457
 
417
-#if ENABLED(MANUAL_BED_LEVELING)
418
-  #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
419
-#endif  // MANUAL_BED_LEVELING
420
-
421 458
 #if ENABLED(MESH_BED_LEVELING)
422 459
   #define MESH_MIN_X 10
423
-  #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
460
+  #define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
424 461
   #define MESH_MIN_Y 10
425
-  #define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
462
+  #define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
426 463
   #define MESH_NUM_X_POINTS 3  // Don't use more than 7 points per axis, implementation limited.
427 464
   #define MESH_NUM_Y_POINTS 3
428 465
   #define MESH_HOME_SEARCH_Z 4  // Z after Home, bed somewhere below but above 0.0.
466
+
467
+  //#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
468
+
469
+  #if ENABLED(MANUAL_BED_LEVELING)
470
+    #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
471
+  #endif  // MANUAL_BED_LEVELING
472
+
429 473
 #endif  // MESH_BED_LEVELING
430 474
 
431 475
 //===========================================================================
@@ -436,7 +480,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
436 480
 
437 481
 //#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
438 482
 //#define DEBUG_LEVELING_FEATURE
439
-#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
483
+#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
440 484
 
441 485
 #if ENABLED(AUTO_BED_LEVELING_FEATURE)
442 486
 
@@ -448,7 +492,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
448 492
   //   This mode is preferred because there are more measurements.
449 493
   //
450 494
   // - "3-point" mode
451
-  //   Probe 3 arbitrary points on the bed (that aren't colinear)
495
+  //   Probe 3 arbitrary points on the bed (that aren't collinear)
452 496
   //   You specify the XY coordinates of all 3 points.
453 497
 
454 498
   // Enable this to sample the bed in a grid (least squares solution).
@@ -462,7 +506,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
462 506
     #define FRONT_PROBE_BED_POSITION 20
463 507
     #define BACK_PROBE_BED_POSITION 170
464 508
 
465
-    #define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
509
+    #define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
466 510
 
467 511
     // Set the number of grid points per dimension.
468 512
     // You probably don't need more than 3 (squared=9).
@@ -470,25 +514,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
470 514
 
471 515
   #else  // !AUTO_BED_LEVELING_GRID
472 516
 
473
-      // Arbitrary points to probe.
474
-      // A simple cross-product is used to estimate the plane of the bed.
475
-      #define ABL_PROBE_PT_1_X 15
476
-      #define ABL_PROBE_PT_1_Y 180
477
-      #define ABL_PROBE_PT_2_X 15
478
-      #define ABL_PROBE_PT_2_Y 20
479
-      #define ABL_PROBE_PT_3_X 170
480
-      #define ABL_PROBE_PT_3_Y 20
517
+    // Arbitrary points to probe.
518
+    // A simple cross-product is used to estimate the plane of the bed.
519
+    #define ABL_PROBE_PT_1_X 15
520
+    #define ABL_PROBE_PT_1_Y 180
521
+    #define ABL_PROBE_PT_2_X 15
522
+    #define ABL_PROBE_PT_2_Y 20
523
+    #define ABL_PROBE_PT_3_X 170
524
+    #define ABL_PROBE_PT_3_Y 20
481 525
 
482 526
   #endif // AUTO_BED_LEVELING_GRID
483 527
 
484
-  // Offsets to the Z probe relative to the nozzle tip.
528
+  // Z Probe to nozzle (X,Y) offset, relative to (0, 0).
485 529
   // X and Y offsets must be integers.
486
-  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // Z probe to nozzle X offset: -left  +right
487
-  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Z probe to nozzle Y offset: -front +behind
488
-  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z probe to nozzle Z offset: -below (always!)
489
-
490
-  #define Z_RAISE_BEFORE_HOMING 4       // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
491
-                                        // Be sure you have this distance over your Z_MAX_POS in case.
530
+  //
531
+  // In the following example the X and Y offsets are both positive:
532
+  // #define X_PROBE_OFFSET_FROM_EXTRUDER 10
533
+  // #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
534
+  //
535
+  //    +-- BACK ---+
536
+  //    |           |
537
+  //  L |    (+) P  | R <-- probe (20,20)
538
+  //  E |           | I
539
+  //  F | (-) N (+) | G <-- nozzle (10,10)
540
+  //  T |           | H
541
+  //    |    (-)    | T
542
+  //    |           |
543
+  //    O-- FRONT --+
544
+  //  (0,0)
545
+  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // X offset: -left  [of the nozzle] +right
546
+  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Y offset: -front [of the nozzle] +behind
547
+  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z offset: -below [the nozzle] (always negative!)
492 548
 
493 549
   #define XY_TRAVEL_SPEED 8000         // X and Y axis travel speed between probes, in mm/min.
494 550
 
@@ -496,16 +552,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
496 552
   #define Z_RAISE_BETWEEN_PROBINGS 5  // How much the Z axis will be raised when traveling from between next probing points.
497 553
   #define Z_RAISE_AFTER_PROBING 15    // How much the Z axis will be raised after the last probing point.
498 554
 
499
-//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
500
-                                                                            // Useful to retract a deployable Z probe.
555
+  //#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
556
+                                                                             // Useful to retract a deployable Z probe.
557
+
558
+  // Probes are sensors/switches that need to be activated before they can be used
559
+  // and deactivated after the use.
560
+  // Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
561
+
562
+  // A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
563
+  // when the hardware endstops are active.
564
+  //#define FIX_MOUNTED_PROBE
565
+
566
+  // A Servo Probe can be defined in the servo section below.
501 567
 
502
-  //#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
568
+  // An Allen Key Probe is currently predefined only in the delta example configurations.
569
+
570
+  //#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
503 571
   //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
504 572
 
505
-// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
506
-// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
573
+  // If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
574
+  // it is highly recommended you leave Z_SAFE_HOMING enabled!
507 575
 
508
-  #define Z_SAFE_HOMING   // This feature is meant to avoid Z homing with Z probe outside the bed area.
576
+  #define Z_SAFE_HOMING   // Use the z-min-probe for homing to z-min - not the z-min-endstop.
577
+                          // This feature is meant to avoid Z homing with Z probe outside the bed area.
509 578
                           // When defined, it will:
510 579
                           // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
511 580
                           // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
@@ -519,37 +588,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
519 588
 
520 589
   #endif
521 590
 
522
-  // Support for a dedicated Z probe endstop separate from the Z min endstop.
523
-  // If you would like to use both a Z probe and a Z min endstop together,
524
-  // uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
525
-  // If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
526
-  // Example: To park the head outside the bed area when homing with G28.
527
-  //
528
-  // WARNING:
529
-  // The Z min endstop will need to set properly as it would without a Z probe
530
-  // to prevent head crashes and premature stopping during a print.
531
-  //
532
-  // To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
533
-  // defined in the pins_XXXXX.h file for your control board.
534
-  // If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
535
-  // Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
536
-  // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
537
-  // in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
538
-  // otherwise connect to ground and D32 for normally closed configuration
539
-  // and 5V and D32 for normally open configurations.
540
-  // Normally closed configuration is advised and assumed.
541
-  // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
542
-  // Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
543
-  // Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
544
-  // D32 is currently selected in the RAMPS 1.3/1.4 pin file.
545
-  // All other boards will need changes to the respective pins_XXXXX.h file.
546
-  //
547
-  // WARNING:
548
-  // Setting the wrong pin may have unexpected and potentially disastrous outcomes.
549
-  // Use with caution and do your homework.
550
-  //
551
-  //#define Z_MIN_PROBE_ENDSTOP
552
-
553 591
 #endif // AUTO_BED_LEVELING_FEATURE
554 592
 
555 593
 
@@ -624,6 +662,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
624 662
 #endif
625 663
 
626 664
 //
665
+// Host Keepalive
666
+//
667
+// By default Marlin will send a busy status message to the host
668
+// every 2 seconds when it can't accept commands.
669
+//
670
+//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
671
+
672
+//
627 673
 // M100 Free Memory Watcher
628 674
 //
629 675
 //#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
@@ -643,13 +689,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
643 689
 // @section lcd
644 690
 
645 691
 // Define your display language below. Replace (en) with your language code and uncomment.
646
-// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
692
+// en, pl, fr, de, es, ru, bg, it, pt, pt_utf8, pt-br, pt-br_utf8, fi, an, nl, ca, eu, kana, kana_utf8, cn, cz, test
647 693
 // See also language.h
648 694
 //#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
649 695
 
650 696
 // Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
651 697
 // To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
652
-// See also documentation/LCDLanguageFont.md
698
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
653 699
   #define DISPLAY_CHARSET_HD44780_JAPAN        // this is the most common hardware
654 700
   //#define DISPLAY_CHARSET_HD44780_WESTERN
655 701
   //#define DISPLAY_CHARSET_HD44780_CYRILLIC
@@ -657,11 +703,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
657 703
 #define ULTRA_LCD  //general LCD support, also 16x2
658 704
 //#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
659 705
 #define SDSUPPORT // Enable SD Card Support in Hardware Console
660
-//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
661
-//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
706
+                  // Changed behaviour! If you need SDSUPPORT uncomment it!
707
+//#define SPI_SPEED SPI_HALF_SPEED // (also SPI_QUARTER_SPEED, SPI_EIGHTH_SPEED) Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
662 708
 //#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
663 709
 //#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
664 710
 //#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
711
+//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
665 712
 //#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
666 713
 //#define ULTIPANEL  //the UltiPanel as on Thingiverse
667 714
 //#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
@@ -678,13 +725,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
678 725
 
679 726
 // The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
680 727
 // http://panucatt.com
681
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
728
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
682 729
 //#define VIKI2
683 730
 //#define miniVIKI
684 731
 
685 732
 // This is a new controller currently under development.  https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
686 733
 //
687
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
734
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
688 735
 //#define ELB_FULL_GRAPHIC_CONTROLLER
689 736
 //#define SD_DETECT_INVERTED
690 737
 
@@ -699,7 +746,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
699 746
 // The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
700 747
 // http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
701 748
 //
702
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
749
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
703 750
 //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
704 751
 
705 752
 // The RepRapWorld REPRAPWORLD_KEYPAD v1.1
@@ -722,6 +769,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
722 769
 
723 770
 //#define LCD_I2C_SAINSMART_YWROBOT
724 771
 
772
+//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
773
+
725 774
 // PANELOLU2 LCD with status LEDs, separate encoder and click inputs
726 775
 //
727 776
 // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
@@ -735,7 +784,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
735 784
 //#define LCD_I2C_VIKI
736 785
 
737 786
 // SSD1306 OLED generic display support
738
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
787
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
739 788
 //#define U8GLIB_SSD1306
740 789
 
741 790
 // Shift register panels
@@ -747,7 +796,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
747 796
 
748 797
 // @section extras
749 798
 
750
-// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
799
+// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
751 800
 //#define FAST_PWM_FAN
752 801
 
753 802
 // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
@@ -829,19 +878,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
829 878
 // Uncomment below to enable
830 879
 //#define FILAMENT_SENSOR
831 880
 
832
-#define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
833
-#define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
834
-
835 881
 #define DEFAULT_NOMINAL_FILAMENT_DIA 3.00  //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
836
-#define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
837
-#define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
838
-#define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
839 882
 
840
-//defines used in the code
841
-#define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
883
+#if ENABLED(FILAMENT_SENSOR)
884
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
885
+  #define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
886
+
887
+  #define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
888
+  #define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
889
+  #define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
842 890
 
843
-//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
844
-//#define FILAMENT_LCD_DISPLAY
891
+  #define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
892
+
893
+  //When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
894
+  //#define FILAMENT_LCD_DISPLAY
895
+#endif
845 896
 
846 897
 #include "Configuration_adv.h"
847 898
 #include "thermistortables.h"

+ 85
- 60
Marlin/example_configurations/WITBOX/Configuration_adv.h Näytä tiedosto

@@ -17,6 +17,20 @@
17 17
 /**
18 18
  * Thermal Protection parameters
19 19
  */
20
+  /**
21
+   * Thermal Protection protects your printer from damage and fire if a
22
+   * thermistor falls out or temperature sensors fail in any way.
23
+   *
24
+   * The issue: If a thermistor falls out or a temperature sensor fails,
25
+   * Marlin can no longer sense the actual temperature. Since a disconnected
26
+   * thermistor reads as a low temperature, the firmware will keep the heater on.
27
+   *
28
+   * The solution: Once the temperature reaches the target, start observing.
29
+   * If the temperature stays too far below the target (hysteresis) for too long (period),
30
+   * the firmware will halt the machine as a safety precaution.
31
+   *
32
+   * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
33
+   */
20 34
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
21 35
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
22 36
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
@@ -26,26 +40,24 @@
26 40
    * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
27 41
    * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
28 42
    * but only if the current temperature is far enough below the target for a reliable test.
43
+   *
44
+   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
45
+   * WATCH_TEMP_INCREASE should not be below 2.
29 46
    */
30 47
   #define WATCH_TEMP_PERIOD 16                // Seconds
31 48
   #define WATCH_TEMP_INCREASE 4               // Degrees Celsius
32 49
 #endif
33 50
 
51
+  /**
52
+   * Thermal Protection parameters for the bed
53
+   * are like the above for the hotends.
54
+   * WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
55
+   */
34 56
 #if ENABLED(THERMAL_PROTECTION_BED)
35 57
   #define THERMAL_PROTECTION_BED_PERIOD 20    // Seconds
36 58
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
37 59
 #endif
38 60
 
39
-/**
40
- * Automatic Temperature:
41
- * The hotend target temperature is calculated by all the buffered lines of gcode.
42
- * The maximum buffered steps/sec of the extruder motor is called "se".
43
- * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
44
- * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
45
- * mintemp and maxtemp. Turn this off by excuting M109 without F*
46
- * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
47
- * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
48
- */
49 61
 #if ENABLED(PIDTEMP)
50 62
   // this adds an experimental additional term to the heating power, proportional to the extrusion speed.
51 63
   // if Kc is chosen well, the additional required power due to increased melting should be compensated.
@@ -56,14 +68,16 @@
56 68
   #endif
57 69
 #endif
58 70
 
59
-
60
-//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
61
-//The maximum buffered steps/sec of the extruder motor are called "se".
62
-//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
63
-// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
64
-// you exit the value by any M109 without F*
65
-// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
66
-// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
71
+/**
72
+ * Automatic Temperature:
73
+ * The hotend target temperature is calculated by all the buffered lines of gcode.
74
+ * The maximum buffered steps/sec of the extruder motor is called "se".
75
+ * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
76
+ * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
77
+ * mintemp and maxtemp. Turn this off by executing M109 without F*
78
+ * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
79
+ * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
80
+ */
67 81
 #define AUTOTEMP
68 82
 #if ENABLED(AUTOTEMP)
69 83
   #define AUTOTEMP_OLDWEIGHT 0.98
@@ -240,7 +254,13 @@
240 254
 #define INVERT_E_STEP_PIN false
241 255
 
242 256
 // Default stepper release if idle. Set to 0 to deactivate.
257
+// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
258
+// Time can be set by M18 and M84.
243 259
 #define DEFAULT_STEPPER_DEACTIVE_TIME 60
260
+#define DISABLE_INACTIVE_X true
261
+#define DISABLE_INACTIVE_Y true
262
+#define DISABLE_INACTIVE_Z true  // set to false if the nozzle will fall down on your printed part when print has finished.
263
+#define DISABLE_INACTIVE_E true
244 264
 
245 265
 #define DEFAULT_MINIMUMFEEDRATE       0.0     // minimum feedrate
246 266
 #define DEFAULT_MINTRAVELFEEDRATE     0.0
@@ -276,6 +296,9 @@
276 296
 // Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
277 297
 #define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
278 298
 
299
+// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
300
+//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
301
+
279 302
 // uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
280 303
 //#define DIGIPOT_I2C
281 304
 // Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
@@ -349,17 +372,16 @@
349 372
   //#define USE_SMALL_INFOFONT
350 373
 #endif // DOGLCD
351 374
 
352
-
353 375
 // @section more
354 376
 
355 377
 // The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
356
-//#define USE_WATCHDOG
378
+#define USE_WATCHDOG
357 379
 
358 380
 #if ENABLED(USE_WATCHDOG)
359
-// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
360
-// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
361
-//  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
362
-//#define WATCHDOG_RESET_MANUAL
381
+  // If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
382
+  // The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
383
+  //  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
384
+  //#define WATCHDOG_RESET_MANUAL
363 385
 #endif
364 386
 
365 387
 // @section lcd
@@ -370,6 +392,7 @@
370 392
 //#define BABYSTEPPING
371 393
 #if ENABLED(BABYSTEPPING)
372 394
   #define BABYSTEP_XY  //not only z, but also XY in the menu. more clutter, more functions
395
+                       //not implemented for deltabots!
373 396
   #define BABYSTEP_INVERT_Z false  //true for inverse movements in Z
374 397
   #define BABYSTEP_MULTIPLICATOR 1 //faster movements
375 398
 #endif
@@ -388,7 +411,6 @@
388 411
 #if ENABLED(ADVANCE)
389 412
   #define EXTRUDER_ADVANCE_K .0
390 413
   #define D_FILAMENT 1.75
391
-  #define STEPS_MM_E 100.47095761381482
392 414
 #endif
393 415
 
394 416
 // @section extras
@@ -397,7 +419,7 @@
397 419
 #define MM_PER_ARC_SEGMENT 1
398 420
 #define N_ARC_CORRECTION 25
399 421
 
400
-const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
422
+const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
401 423
 
402 424
 // @section temperature
403 425
 
@@ -446,11 +468,11 @@ const unsigned int dropsegments=5; //everything with less than this number of st
446 468
   #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
447 469
   #define RETRACT_LENGTH 3               //default retract length (positive mm)
448 470
   #define RETRACT_LENGTH_SWAP 13         //default swap retract length (positive mm), for extruder change
449
-  #define RETRACT_FEEDRATE 80*60            //default feedrate for retracting (mm/s)
471
+  #define RETRACT_FEEDRATE 80            //default feedrate for retracting (mm/s)
450 472
   #define RETRACT_ZLIFT 0                //default retract Z-lift
451 473
   #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
452 474
   //#define RETRACT_RECOVER_LENGTH_SWAP 0  //default additional swap recover length (mm, added to retract length when recovering from extruder change)
453
-  #define RETRACT_RECOVER_FEEDRATE 8*60     //default feedrate for recovering from retraction (mm/s)
475
+  #define RETRACT_RECOVER_FEEDRATE 8     //default feedrate for recovering from retraction (mm/s)
454 476
 #endif
455 477
 
456 478
 // Add support for experimental filament exchange support M600; requires display
@@ -462,12 +484,15 @@ const unsigned int dropsegments=5; //everything with less than this number of st
462 484
     #define FILAMENTCHANGE_ZADD 10
463 485
     #define FILAMENTCHANGE_FIRSTRETRACT -2
464 486
     #define FILAMENTCHANGE_FINALRETRACT -100
487
+    #define AUTO_FILAMENT_CHANGE                //This extrude filament until you press the button on LCD
488
+    #define AUTO_FILAMENT_CHANGE_LENGTH 0.04    //Extrusion length on automatic extrusion loop
489
+    #define AUTO_FILAMENT_CHANGE_FEEDRATE 300   //Extrusion feedrate (mm/min) on automatic extrusion loop
465 490
   #endif
466 491
 #endif
467 492
 
468 493
 /******************************************************************************\
469 494
  * enable this section if you have TMC26X motor drivers.
470
- * you need to import the TMC26XStepper library into the arduino IDE for this
495
+ * you need to import the TMC26XStepper library into the Arduino IDE for this
471 496
  ******************************************************************************/
472 497
 
473 498
 // @section tmc
@@ -475,52 +500,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
475 500
 //#define HAVE_TMCDRIVER
476 501
 #if ENABLED(HAVE_TMCDRIVER)
477 502
 
478
-//#define X_IS_TMC
503
+  //#define X_IS_TMC
479 504
   #define X_MAX_CURRENT 1000  //in mA
480 505
   #define X_SENSE_RESISTOR 91 //in mOhms
481 506
   #define X_MICROSTEPS 16     //number of microsteps
482 507
 
483
-//#define X2_IS_TMC
508
+  //#define X2_IS_TMC
484 509
   #define X2_MAX_CURRENT 1000  //in mA
485 510
   #define X2_SENSE_RESISTOR 91 //in mOhms
486 511
   #define X2_MICROSTEPS 16     //number of microsteps
487 512
 
488
-//#define Y_IS_TMC
513
+  //#define Y_IS_TMC
489 514
   #define Y_MAX_CURRENT 1000  //in mA
490 515
   #define Y_SENSE_RESISTOR 91 //in mOhms
491 516
   #define Y_MICROSTEPS 16     //number of microsteps
492 517
 
493
-//#define Y2_IS_TMC
518
+  //#define Y2_IS_TMC
494 519
   #define Y2_MAX_CURRENT 1000  //in mA
495 520
   #define Y2_SENSE_RESISTOR 91 //in mOhms
496 521
   #define Y2_MICROSTEPS 16     //number of microsteps
497 522
 
498
-//#define Z_IS_TMC
523
+  //#define Z_IS_TMC
499 524
   #define Z_MAX_CURRENT 1000  //in mA
500 525
   #define Z_SENSE_RESISTOR 91 //in mOhms
501 526
   #define Z_MICROSTEPS 16     //number of microsteps
502 527
 
503
-//#define Z2_IS_TMC
528
+  //#define Z2_IS_TMC
504 529
   #define Z2_MAX_CURRENT 1000  //in mA
505 530
   #define Z2_SENSE_RESISTOR 91 //in mOhms
506 531
   #define Z2_MICROSTEPS 16     //number of microsteps
507 532
 
508
-//#define E0_IS_TMC
533
+  //#define E0_IS_TMC
509 534
   #define E0_MAX_CURRENT 1000  //in mA
510 535
   #define E0_SENSE_RESISTOR 91 //in mOhms
511 536
   #define E0_MICROSTEPS 16     //number of microsteps
512 537
 
513
-//#define E1_IS_TMC
538
+  //#define E1_IS_TMC
514 539
   #define E1_MAX_CURRENT 1000  //in mA
515 540
   #define E1_SENSE_RESISTOR 91 //in mOhms
516 541
   #define E1_MICROSTEPS 16     //number of microsteps
517 542
 
518
-//#define E2_IS_TMC
543
+  //#define E2_IS_TMC
519 544
   #define E2_MAX_CURRENT 1000  //in mA
520 545
   #define E2_SENSE_RESISTOR 91 //in mOhms
521 546
   #define E2_MICROSTEPS 16     //number of microsteps
522 547
 
523
-//#define E3_IS_TMC
548
+  //#define E3_IS_TMC
524 549
   #define E3_MAX_CURRENT 1000  //in mA
525 550
   #define E3_SENSE_RESISTOR 91 //in mOhms
526 551
   #define E3_MICROSTEPS 16     //number of microsteps
@@ -529,7 +554,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
529 554
 
530 555
 /******************************************************************************\
531 556
  * enable this section if you have L6470  motor drivers.
532
- * you need to import the L6470 library into the arduino IDE for this
557
+ * you need to import the L6470 library into the Arduino IDE for this
533 558
  ******************************************************************************/
534 559
 
535 560
 // @section l6470
@@ -537,63 +562,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
537 562
 //#define HAVE_L6470DRIVER
538 563
 #if ENABLED(HAVE_L6470DRIVER)
539 564
 
540
-//#define X_IS_L6470
565
+  //#define X_IS_L6470
541 566
   #define X_MICROSTEPS 16     //number of microsteps
542
-  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
567
+  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
543 568
   #define X_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
544 569
   #define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
545 570
 
546
-//#define X2_IS_L6470
571
+  //#define X2_IS_L6470
547 572
   #define X2_MICROSTEPS 16     //number of microsteps
548
-  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
573
+  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
549 574
   #define X2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
550 575
   #define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
551 576
 
552
-//#define Y_IS_L6470
577
+  //#define Y_IS_L6470
553 578
   #define Y_MICROSTEPS 16     //number of microsteps
554
-  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
579
+  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
555 580
   #define Y_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
556 581
   #define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
557 582
 
558
-//#define Y2_IS_L6470
583
+  //#define Y2_IS_L6470
559 584
   #define Y2_MICROSTEPS 16     //number of microsteps
560
-  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
585
+  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
561 586
   #define Y2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
562 587
   #define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
563 588
 
564
-//#define Z_IS_L6470
589
+  //#define Z_IS_L6470
565 590
   #define Z_MICROSTEPS 16     //number of microsteps
566
-  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
591
+  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
567 592
   #define Z_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
568 593
   #define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
569 594
 
570
-//#define Z2_IS_L6470
595
+  //#define Z2_IS_L6470
571 596
   #define Z2_MICROSTEPS 16     //number of microsteps
572
-  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
597
+  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
573 598
   #define Z2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
574 599
   #define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
575 600
 
576
-//#define E0_IS_L6470
601
+  //#define E0_IS_L6470
577 602
   #define E0_MICROSTEPS 16     //number of microsteps
578
-  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
603
+  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
579 604
   #define E0_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
580 605
   #define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
581 606
 
582
-//#define E1_IS_L6470
607
+  //#define E1_IS_L6470
583 608
   #define E1_MICROSTEPS 16     //number of microsteps
584
-  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
609
+  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
585 610
   #define E1_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
586 611
   #define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
587 612
 
588
-//#define E2_IS_L6470
613
+  //#define E2_IS_L6470
589 614
   #define E2_MICROSTEPS 16     //number of microsteps
590
-  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
615
+  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
591 616
   #define E2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
592 617
   #define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
593 618
 
594
-//#define E3_IS_L6470
619
+  //#define E3_IS_L6470
595 620
   #define E3_MICROSTEPS 16     //number of microsteps
596
-  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
621
+  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
597 622
   #define E3_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
598 623
   #define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
599 624
 

+ 153
- 103
Marlin/example_configurations/adafruit/ST7565/Configuration.h Näytä tiedosto

@@ -70,7 +70,7 @@ Here are some standard links for getting your machine calibrated:
70 70
 // The following define selects which electronics board you have.
71 71
 // Please choose the name from boards.h that matches your setup
72 72
 #ifndef MOTHERBOARD
73
-  #define MOTHERBOARD BOARD_RAMPS_13_EFB
73
+  #define MOTHERBOARD BOARD_RAMPS_14_EFB
74 74
 #endif
75 75
 
76 76
 // Optional custom name for your RepStrap or other custom machine
@@ -110,6 +110,7 @@ Here are some standard links for getting your machine calibrated:
110 110
 //--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
111 111
 //
112 112
 //// Temperature sensor settings:
113
+// -3 is thermocouple with MAX31855 (only for sensor 0)
113 114
 // -2 is thermocouple with MAX6675 (only for sensor 0)
114 115
 // -1 is thermocouple with AD595
115 116
 // 0 is not used
@@ -129,6 +130,7 @@ Here are some standard links for getting your machine calibrated:
129 130
 // 13 is 100k Hisens 3950  1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
130 131
 // 20 is the PT100 circuit found in the Ultimainboard V2.x
131 132
 // 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
133
+// 70 is the 100K thermistor found in the bq Hephestos 2
132 134
 //
133 135
 //    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
134 136
 //                          (but gives greater accuracy and more stable PID)
@@ -144,7 +146,7 @@ Here are some standard links for getting your machine calibrated:
144 146
 //     Use it for Testing or Development purposes. NEVER for production machine.
145 147
 //#define DUMMY_THERMISTOR_998_VALUE 25
146 148
 //#define DUMMY_THERMISTOR_999_VALUE 100
147
-// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
149
+// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-3': "Thermocouple + MAX31855 (only for sensor 0)", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
148 150
 #define TEMP_SENSOR_0 1
149 151
 #define TEMP_SENSOR_1 0
150 152
 #define TEMP_SENSOR_2 0
@@ -178,14 +180,9 @@ Here are some standard links for getting your machine calibrated:
178 180
 #define HEATER_3_MAXTEMP 275
179 181
 #define BED_MAXTEMP 150
180 182
 
181
-// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
182
-// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
183
-// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
184
-//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
185
-
186 183
 // If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
187
-//#define EXTRUDER_WATTS (12.0*12.0/6.7) //  P=I^2/R
188
-//#define BED_WATTS (12.0*12.0/1.1)      // P=I^2/R
184
+//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
185
+//#define BED_WATTS (12.0*12.0/1.1)      // P=U^2/R
189 186
 
190 187
 //===========================================================================
191 188
 //============================= PID Settings ================================
@@ -253,13 +250,13 @@ Here are some standard links for getting your machine calibrated:
253 250
 
254 251
   #define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
255 252
 
256
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
253
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
257 254
   //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
258 255
   #define  DEFAULT_bedKp 10.00
259 256
   #define  DEFAULT_bedKi .023
260 257
   #define  DEFAULT_bedKd 305.4
261 258
 
262
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
259
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
263 260
   //from pidautotune
264 261
   //#define  DEFAULT_bedKp 97.1
265 262
   //#define  DEFAULT_bedKi 1.41
@@ -284,16 +281,15 @@ Here are some standard links for getting your machine calibrated:
284 281
 //===========================================================================
285 282
 
286 283
 /**
287
- * Thermal Runaway Protection protects your printer from damage and fire if a
284
+ * Thermal Protection protects your printer from damage and fire if a
288 285
  * thermistor falls out or temperature sensors fail in any way.
289 286
  *
290 287
  * The issue: If a thermistor falls out or a temperature sensor fails,
291 288
  * Marlin can no longer sense the actual temperature. Since a disconnected
292 289
  * thermistor reads as a low temperature, the firmware will keep the heater on.
293 290
  *
294
- * The solution: Once the temperature reaches the target, start observing.
295
- * If the temperature stays too far below the target (hysteresis) for too long,
296
- * the firmware will halt as a safety precaution.
291
+ * If you get "Thermal Runaway" or "Heating failed" errors the
292
+ * details can be tuned in Configuration_adv.h
297 293
  */
298 294
 
299 295
 #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
@@ -341,10 +337,52 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
341 337
 //#define DISABLE_MAX_ENDSTOPS
342 338
 //#define DISABLE_MIN_ENDSTOPS
343 339
 
344
-// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
345
-// This only affects a Z probe endstop if you have separate Z min endstop as well and have
346
-// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
347
-// this has no effect.
340
+//===========================================================================
341
+//============================= Z Probe Options =============================
342
+//===========================================================================
343
+
344
+// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
345
+// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
346
+//
347
+// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
348
+//
349
+// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
350
+// Example: To park the head outside the bed area when homing with G28.
351
+//
352
+// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
353
+//
354
+// For a servo-based Z probe, you must set up servo support below, including
355
+// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
356
+//
357
+// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
358
+// - Use 5V for powered (usu. inductive) sensors.
359
+// - Otherwise connect:
360
+//   - normally-closed switches to GND and D32.
361
+//   - normally-open switches to 5V and D32.
362
+//
363
+// Normally-closed switches are advised and are the default.
364
+//
365
+// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
366
+// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
367
+// default pin for all RAMPS-based boards. Some other boards map differently.
368
+// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
369
+//
370
+// WARNING:
371
+// Setting the wrong pin may have unexpected and potentially disastrous consequences.
372
+// Use with caution and do your homework.
373
+//
374
+//#define Z_MIN_PROBE_ENDSTOP
375
+
376
+// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
377
+// The Z_MIN_PIN will then be used for both Z-homing and probing.
378
+#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
379
+
380
+// To use a probe you must enable one of the two options above!
381
+
382
+// This option disables the use of the Z_MIN_PROBE_PIN
383
+// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
384
+// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
385
+// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
348 386
 //#define DISABLE_Z_MIN_PROBE_ENDSTOP
349 387
 
350 388
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
@@ -354,11 +392,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
354 392
 #define Z_ENABLE_ON 0
355 393
 #define E_ENABLE_ON 0 // For all extruders
356 394
 
357
-// Disables axis when it's not being used.
395
+// Disables axis stepper immediately when it's not being used.
358 396
 // WARNING: When motors turn off there is a chance of losing position accuracy!
359 397
 #define DISABLE_X false
360 398
 #define DISABLE_Y false
361 399
 #define DISABLE_Z false
400
+// Warn on display about possibly reduced accuracy
401
+//#define DISABLE_REDUCED_ACCURACY_WARNING
362 402
 
363 403
 // @section extruder
364 404
 
@@ -381,6 +421,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
381 421
 #define INVERT_E3_DIR false
382 422
 
383 423
 // @section homing
424
+//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
425
+                                    // Be sure you have this distance over your Z_MAX_POS in case.
384 426
 
385 427
 // ENDSTOP SETTINGS:
386 428
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
@@ -416,24 +458,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
416 458
 #endif
417 459
 
418 460
 //===========================================================================
419
-//=========================== Manual Bed Leveling ===========================
461
+//============================ Mesh Bed Leveling ============================
420 462
 //===========================================================================
421 463
 
422
-//#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
423 464
 //#define MESH_BED_LEVELING    // Enable mesh bed leveling.
424 465
 
425
-#if ENABLED(MANUAL_BED_LEVELING)
426
-  #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
427
-#endif  // MANUAL_BED_LEVELING
428
-
429 466
 #if ENABLED(MESH_BED_LEVELING)
430 467
   #define MESH_MIN_X 10
431
-  #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
468
+  #define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
432 469
   #define MESH_MIN_Y 10
433
-  #define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
470
+  #define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
434 471
   #define MESH_NUM_X_POINTS 3  // Don't use more than 7 points per axis, implementation limited.
435 472
   #define MESH_NUM_Y_POINTS 3
436 473
   #define MESH_HOME_SEARCH_Z 4  // Z after Home, bed somewhere below but above 0.0.
474
+
475
+  //#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
476
+
477
+  #if ENABLED(MANUAL_BED_LEVELING)
478
+    #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
479
+  #endif  // MANUAL_BED_LEVELING
480
+
437 481
 #endif  // MESH_BED_LEVELING
438 482
 
439 483
 //===========================================================================
@@ -442,10 +486,9 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
442 486
 
443 487
 // @section bedlevel
444 488
 
445
-
446 489
 //#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
447 490
 //#define DEBUG_LEVELING_FEATURE
448
-#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
491
+#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
449 492
 
450 493
 #if ENABLED(AUTO_BED_LEVELING_FEATURE)
451 494
 
@@ -457,7 +500,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
457 500
   //   This mode is preferred because there are more measurements.
458 501
   //
459 502
   // - "3-point" mode
460
-  //   Probe 3 arbitrary points on the bed (that aren't colinear)
503
+  //   Probe 3 arbitrary points on the bed (that aren't collinear)
461 504
   //   You specify the XY coordinates of all 3 points.
462 505
 
463 506
   // Enable this to sample the bed in a grid (least squares solution).
@@ -471,7 +514,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
471 514
     #define FRONT_PROBE_BED_POSITION 20
472 515
     #define BACK_PROBE_BED_POSITION 170
473 516
 
474
-    #define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
517
+    #define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
475 518
 
476 519
     // Set the number of grid points per dimension.
477 520
     // You probably don't need more than 3 (squared=9).
@@ -479,25 +522,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
479 522
 
480 523
   #else  // !AUTO_BED_LEVELING_GRID
481 524
 
482
-      // Arbitrary points to probe.
483
-      // A simple cross-product is used to estimate the plane of the bed.
484
-      #define ABL_PROBE_PT_1_X 15
485
-      #define ABL_PROBE_PT_1_Y 180
486
-      #define ABL_PROBE_PT_2_X 15
487
-      #define ABL_PROBE_PT_2_Y 20
488
-      #define ABL_PROBE_PT_3_X 170
489
-      #define ABL_PROBE_PT_3_Y 20
525
+    // Arbitrary points to probe.
526
+    // A simple cross-product is used to estimate the plane of the bed.
527
+    #define ABL_PROBE_PT_1_X 15
528
+    #define ABL_PROBE_PT_1_Y 180
529
+    #define ABL_PROBE_PT_2_X 15
530
+    #define ABL_PROBE_PT_2_Y 20
531
+    #define ABL_PROBE_PT_3_X 170
532
+    #define ABL_PROBE_PT_3_Y 20
490 533
 
491 534
   #endif // AUTO_BED_LEVELING_GRID
492 535
 
493
-  // Offsets to the Z probe relative to the nozzle tip.
536
+  // Z Probe to nozzle (X,Y) offset, relative to (0, 0).
494 537
   // X and Y offsets must be integers.
495
-  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // Z probe to nozzle X offset: -left  +right
496
-  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Z probe to nozzle Y offset: -front +behind
497
-  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z probe to nozzle Z offset: -below (always!)
498
-
499
-  #define Z_RAISE_BEFORE_HOMING 4       // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
500
-                                        // Be sure you have this distance over your Z_MAX_POS in case.
538
+  //
539
+  // In the following example the X and Y offsets are both positive:
540
+  // #define X_PROBE_OFFSET_FROM_EXTRUDER 10
541
+  // #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
542
+  //
543
+  //    +-- BACK ---+
544
+  //    |           |
545
+  //  L |    (+) P  | R <-- probe (20,20)
546
+  //  E |           | I
547
+  //  F | (-) N (+) | G <-- nozzle (10,10)
548
+  //  T |           | H
549
+  //    |    (-)    | T
550
+  //    |           |
551
+  //    O-- FRONT --+
552
+  //  (0,0)
553
+  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // X offset: -left  [of the nozzle] +right
554
+  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Y offset: -front [of the nozzle] +behind
555
+  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z offset: -below [the nozzle] (always negative!)
501 556
 
502 557
   #define XY_TRAVEL_SPEED 8000         // X and Y axis travel speed between probes, in mm/min.
503 558
 
@@ -505,16 +560,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
505 560
   #define Z_RAISE_BETWEEN_PROBINGS 5  // How much the Z axis will be raised when traveling from between next probing points.
506 561
   #define Z_RAISE_AFTER_PROBING 15    // How much the Z axis will be raised after the last probing point.
507 562
 
508
-//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
509
-                                                                            // Useful to retract a deployable Z probe.
563
+  //#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
564
+                                                                             // Useful to retract a deployable Z probe.
565
+
566
+  // Probes are sensors/switches that need to be activated before they can be used
567
+  // and deactivated after the use.
568
+  // Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
569
+
570
+  // A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
571
+  // when the hardware endstops are active.
572
+  //#define FIX_MOUNTED_PROBE
573
+
574
+  // A Servo Probe can be defined in the servo section below.
510 575
 
511
-  //#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
576
+  // An Allen Key Probe is currently predefined only in the delta example configurations.
577
+
578
+  //#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
512 579
   //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
513 580
 
514
-// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
515
-// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
581
+  // If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
582
+  // it is highly recommended you leave Z_SAFE_HOMING enabled!
516 583
 
517
-  #define Z_SAFE_HOMING   // This feature is meant to avoid Z homing with Z probe outside the bed area.
584
+  #define Z_SAFE_HOMING   // Use the z-min-probe for homing to z-min - not the z-min-endstop.
585
+                          // This feature is meant to avoid Z homing with Z probe outside the bed area.
518 586
                           // When defined, it will:
519 587
                           // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
520 588
                           // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
@@ -528,37 +596,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
528 596
 
529 597
   #endif
530 598
 
531
-  // Support for a dedicated Z probe endstop separate from the Z min endstop.
532
-  // If you would like to use both a Z probe and a Z min endstop together,
533
-  // uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
534
-  // If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
535
-  // Example: To park the head outside the bed area when homing with G28.
536
-  //
537
-  // WARNING:
538
-  // The Z min endstop will need to set properly as it would without a Z probe
539
-  // to prevent head crashes and premature stopping during a print.
540
-  //
541
-  // To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
542
-  // defined in the pins_XXXXX.h file for your control board.
543
-  // If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
544
-  // Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
545
-  // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
546
-  // in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
547
-  // otherwise connect to ground and D32 for normally closed configuration
548
-  // and 5V and D32 for normally open configurations.
549
-  // Normally closed configuration is advised and assumed.
550
-  // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
551
-  // Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
552
-  // Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
553
-  // D32 is currently selected in the RAMPS 1.3/1.4 pin file.
554
-  // All other boards will need changes to the respective pins_XXXXX.h file.
555
-  //
556
-  // WARNING:
557
-  // Setting the wrong pin may have unexpected and potentially disastrous outcomes.
558
-  // Use with caution and do your homework.
559
-  //
560
-  //#define Z_MIN_PROBE_ENDSTOP
561
-
562 599
 #endif // AUTO_BED_LEVELING_FEATURE
563 600
 
564 601
 
@@ -633,6 +670,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
633 670
 #endif
634 671
 
635 672
 //
673
+// Host Keepalive
674
+//
675
+// By default Marlin will send a busy status message to the host
676
+// every 2 seconds when it can't accept commands.
677
+//
678
+//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
679
+
680
+//
636 681
 // M100 Free Memory Watcher
637 682
 //
638 683
 //#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
@@ -652,13 +697,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
652 697
 // @section lcd
653 698
 
654 699
 // Define your display language below. Replace (en) with your language code and uncomment.
655
-// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
700
+// en, pl, fr, de, es, ru, bg, it, pt, pt_utf8, pt-br, pt-br_utf8, fi, an, nl, ca, eu, kana, kana_utf8, cn, cz, test
656 701
 // See also language.h
657 702
 #define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
658 703
 
659 704
 // Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
660 705
 // To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
661
-// See also documentation/LCDLanguageFont.md
706
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
662 707
   #define DISPLAY_CHARSET_HD44780_JAPAN        // this is the most common hardware
663 708
   //#define DISPLAY_CHARSET_HD44780_WESTERN
664 709
   //#define DISPLAY_CHARSET_HD44780_CYRILLIC
@@ -666,11 +711,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
666 711
 //#define ULTRA_LCD  //general LCD support, also 16x2
667 712
 //#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
668 713
 #define SDSUPPORT // Enable SD Card Support in Hardware Console
669
-#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
670
-//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
714
+                  // Changed behaviour! If you need SDSUPPORT uncomment it!
715
+#define SPI_SPEED SPI_HALF_SPEED // (also SPI_QUARTER_SPEED, SPI_EIGHTH_SPEED) Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
671 716
 //#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
672 717
 //#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
673 718
 //#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
719
+//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
674 720
 //#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
675 721
 //#define ULTIPANEL  //the UltiPanel as on Thingiverse
676 722
 //#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
@@ -687,13 +733,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
687 733
 
688 734
 // The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
689 735
 // http://panucatt.com
690
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
736
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
691 737
 //#define VIKI2
692 738
 //#define miniVIKI
693 739
 
694 740
 // This is a new controller currently under development.  https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
695 741
 //
696
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
742
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
697 743
 #define ELB_FULL_GRAPHIC_CONTROLLER
698 744
 //#define SD_DETECT_INVERTED
699 745
 
@@ -708,7 +754,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
708 754
 // The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
709 755
 // http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
710 756
 //
711
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
757
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
712 758
 //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
713 759
 
714 760
 // The RepRapWorld REPRAPWORLD_KEYPAD v1.1
@@ -731,6 +777,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
731 777
 
732 778
 //#define LCD_I2C_SAINSMART_YWROBOT
733 779
 
780
+//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
781
+
734 782
 // PANELOLU2 LCD with status LEDs, separate encoder and click inputs
735 783
 //
736 784
 // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
@@ -744,7 +792,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
744 792
 //#define LCD_I2C_VIKI
745 793
 
746 794
 // SSD1306 OLED generic display support
747
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
795
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
748 796
 //#define U8GLIB_SSD1306
749 797
 
750 798
 // Shift register panels
@@ -756,7 +804,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
756 804
 
757 805
 // @section extras
758 806
 
759
-// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
807
+// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
760 808
 //#define FAST_PWM_FAN
761 809
 
762 810
 // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
@@ -838,19 +886,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
838 886
 // Uncomment below to enable
839 887
 //#define FILAMENT_SENSOR
840 888
 
841
-#define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
842
-#define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
843
-
844 889
 #define DEFAULT_NOMINAL_FILAMENT_DIA 3.00  //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
845
-#define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
846
-#define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
847
-#define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
848 890
 
849
-//defines used in the code
850
-#define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
891
+#if ENABLED(FILAMENT_SENSOR)
892
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
893
+  #define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
894
+
895
+  #define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
896
+  #define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
897
+  #define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
851 898
 
852
-//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
853
-//#define FILAMENT_LCD_DISPLAY
899
+  #define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
900
+
901
+  //When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
902
+  //#define FILAMENT_LCD_DISPLAY
903
+#endif
854 904
 
855 905
 #include "Configuration_adv.h"
856 906
 #include "thermistortables.h"

+ 158
- 104
Marlin/example_configurations/delta/biv2.5/Configuration.h Näytä tiedosto

@@ -110,6 +110,7 @@ Here are some standard links for getting your machine calibrated:
110 110
 //--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
111 111
 //
112 112
 //// Temperature sensor settings:
113
+// -3 is thermocouple with MAX31855 (only for sensor 0)
113 114
 // -2 is thermocouple with MAX6675 (only for sensor 0)
114 115
 // -1 is thermocouple with AD595
115 116
 // 0 is not used
@@ -129,6 +130,7 @@ Here are some standard links for getting your machine calibrated:
129 130
 // 13 is 100k Hisens 3950  1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
130 131
 // 20 is the PT100 circuit found in the Ultimainboard V2.x
131 132
 // 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
133
+// 70 is the 100K thermistor found in the bq Hephestos 2
132 134
 //
133 135
 //    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
134 136
 //                          (but gives greater accuracy and more stable PID)
@@ -144,7 +146,7 @@ Here are some standard links for getting your machine calibrated:
144 146
 //     Use it for Testing or Development purposes. NEVER for production machine.
145 147
 //#define DUMMY_THERMISTOR_998_VALUE 25
146 148
 //#define DUMMY_THERMISTOR_999_VALUE 100
147
-// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
149
+// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-3': "Thermocouple + MAX31855 (only for sensor 0)", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
148 150
 #define TEMP_SENSOR_0 5
149 151
 #define TEMP_SENSOR_1 5
150 152
 #define TEMP_SENSOR_2 0
@@ -178,14 +180,9 @@ Here are some standard links for getting your machine calibrated:
178 180
 #define HEATER_3_MAXTEMP 275
179 181
 #define BED_MAXTEMP 150
180 182
 
181
-// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
182
-// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
183
-// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
184
-//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
185
-
186 183
 // If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
187
-//#define EXTRUDER_WATTS (12.0*12.0/6.7) //  P=I^2/R
188
-//#define BED_WATTS (12.0*12.0/1.1)      // P=I^2/R
184
+//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
185
+//#define BED_WATTS (12.0*12.0/1.1)      // P=U^2/R
189 186
 
190 187
 //===========================================================================
191 188
 //============================= PID Settings ================================
@@ -253,13 +250,13 @@ Here are some standard links for getting your machine calibrated:
253 250
 
254 251
   #define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
255 252
 
256
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
253
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
257 254
   //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
258 255
   #define  DEFAULT_bedKp 10.00
259 256
   #define  DEFAULT_bedKi .023
260 257
   #define  DEFAULT_bedKd 305.4
261 258
 
262
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
259
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
263 260
   //from pidautotune
264 261
   //#define  DEFAULT_bedKp 97.1
265 262
   //#define  DEFAULT_bedKi 1.41
@@ -284,16 +281,15 @@ Here are some standard links for getting your machine calibrated:
284 281
 //===========================================================================
285 282
 
286 283
 /**
287
- * Thermal Runaway Protection protects your printer from damage and fire if a
284
+ * Thermal Protection protects your printer from damage and fire if a
288 285
  * thermistor falls out or temperature sensors fail in any way.
289 286
  *
290 287
  * The issue: If a thermistor falls out or a temperature sensor fails,
291 288
  * Marlin can no longer sense the actual temperature. Since a disconnected
292 289
  * thermistor reads as a low temperature, the firmware will keep the heater on.
293 290
  *
294
- * The solution: Once the temperature reaches the target, start observing.
295
- * If the temperature stays too far below the target (hysteresis) for too long,
296
- * the firmware will halt as a safety precaution.
291
+ * If you get "Thermal Runaway" or "Heating failed" errors the
292
+ * details can be tuned in Configuration_adv.h
297 293
  */
298 294
 
299 295
 #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
@@ -376,10 +372,52 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
376 372
 //#define DISABLE_MAX_ENDSTOPS
377 373
 #define DISABLE_MIN_ENDSTOPS // Deltas only use min endstops for probing.
378 374
 
379
-// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
380
-// This only affects a Z probe endstop if you have separate Z min endstop as well and have
381
-// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
382
-// this has no effect.
375
+//===========================================================================
376
+//============================= Z Probe Options =============================
377
+//===========================================================================
378
+
379
+// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
380
+// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
381
+//
382
+// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
383
+//
384
+// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
385
+// Example: To park the head outside the bed area when homing with G28.
386
+//
387
+// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
388
+//
389
+// For a servo-based Z probe, you must set up servo support below, including
390
+// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
391
+//
392
+// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
393
+// - Use 5V for powered (usu. inductive) sensors.
394
+// - Otherwise connect:
395
+//   - normally-closed switches to GND and D32.
396
+//   - normally-open switches to 5V and D32.
397
+//
398
+// Normally-closed switches are advised and are the default.
399
+//
400
+// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
401
+// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
402
+// default pin for all RAMPS-based boards. Some other boards map differently.
403
+// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
404
+//
405
+// WARNING:
406
+// Setting the wrong pin may have unexpected and potentially disastrous consequences.
407
+// Use with caution and do your homework.
408
+//
409
+//#define Z_MIN_PROBE_ENDSTOP
410
+
411
+// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
412
+// The Z_MIN_PIN will then be used for both Z-homing and probing.
413
+#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
414
+
415
+// To use a probe you must enable one of the two options above!
416
+
417
+// This option disables the use of the Z_MIN_PROBE_PIN
418
+// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
419
+// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
420
+// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
383 421
 //#define DISABLE_Z_MIN_PROBE_ENDSTOP
384 422
 
385 423
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
@@ -389,11 +427,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
389 427
 #define Z_ENABLE_ON 0
390 428
 #define E_ENABLE_ON 0 // For all extruders
391 429
 
392
-// Disables axis when it's not being used.
430
+// Disables axis stepper immediately when it's not being used.
393 431
 // WARNING: When motors turn off there is a chance of losing position accuracy!
394 432
 #define DISABLE_X false
395 433
 #define DISABLE_Y false
396 434
 #define DISABLE_Z false
435
+// Warn on display about possibly reduced accuracy
436
+//#define DISABLE_REDUCED_ACCURACY_WARNING
397 437
 
398 438
 // @section extruder
399 439
 
@@ -416,6 +456,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
416 456
 #define INVERT_E3_DIR false
417 457
 
418 458
 // @section homing
459
+//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
460
+                                    // Be sure you have this distance over your Z_MAX_POS in case.
419 461
 
420 462
 // ENDSTOP SETTINGS:
421 463
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
@@ -451,24 +493,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
451 493
 #endif
452 494
 
453 495
 //===========================================================================
454
-//=========================== Manual Bed Leveling ===========================
496
+//============================ Mesh Bed Leveling ============================
455 497
 //===========================================================================
456 498
 
457
-//#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
458 499
 //#define MESH_BED_LEVELING    // Enable mesh bed leveling.
459 500
 
460
-#if ENABLED(MANUAL_BED_LEVELING)
461
-  #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
462
-#endif  // MANUAL_BED_LEVELING
463
-
464 501
 #if ENABLED(MESH_BED_LEVELING)
465 502
   #define MESH_MIN_X 10
466
-  #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
503
+  #define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
467 504
   #define MESH_MIN_Y 10
468
-  #define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
505
+  #define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
469 506
   #define MESH_NUM_X_POINTS 3  // Don't use more than 7 points per axis, implementation limited.
470 507
   #define MESH_NUM_Y_POINTS 3
471 508
   #define MESH_HOME_SEARCH_Z 4  // Z after Home, bed somewhere below but above 0.0.
509
+
510
+  //#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
511
+
512
+  #if ENABLED(MANUAL_BED_LEVELING)
513
+    #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
514
+  #endif  // MANUAL_BED_LEVELING
515
+
472 516
 #endif  // MESH_BED_LEVELING
473 517
 
474 518
 //===========================================================================
@@ -479,7 +523,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
479 523
 
480 524
 //#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
481 525
 //#define DEBUG_LEVELING_FEATURE
482
-//#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
526
+//#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
483 527
 
484 528
 #if ENABLED(AUTO_BED_LEVELING_FEATURE)
485 529
 
@@ -491,7 +535,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
491 535
   //   This mode is preferred because there are more measurements.
492 536
   //
493 537
   // - "3-point" mode
494
-  //   Probe 3 arbitrary points on the bed (that aren't colinear)
538
+  //   Probe 3 arbitrary points on the bed (that aren't collinear)
495 539
   //   You specify the XY coordinates of all 3 points.
496 540
 
497 541
   // Enable this to sample the bed in a grid (least squares solution).
@@ -507,35 +551,47 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
507 551
     #define FRONT_PROBE_BED_POSITION -DELTA_PROBABLE_RADIUS
508 552
     #define BACK_PROBE_BED_POSITION DELTA_PROBABLE_RADIUS
509 553
 
510
-    #define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
554
+    #define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
511 555
 
512 556
     // Non-linear bed leveling will be used.
513 557
     // Compensate by interpolating between the nearest four Z probe values for each point.
514 558
     // Useful for deltas where the print surface may appear like a bowl or dome shape.
515
-    // Works best with ACCURATE_BED_LEVELING_POINTS 5 or higher.
559
+    // Works best with AUTO_BED_LEVELING_GRID_POINTS 5 or higher.
516 560
     #define AUTO_BED_LEVELING_GRID_POINTS 9
517 561
 
518 562
   #else  // !AUTO_BED_LEVELING_GRID
519 563
 
520
-      // Arbitrary points to probe.
521
-      // A simple cross-product is used to estimate the plane of the bed.
522
-      #define ABL_PROBE_PT_1_X 15
523
-      #define ABL_PROBE_PT_1_Y 180
524
-      #define ABL_PROBE_PT_2_X 15
525
-      #define ABL_PROBE_PT_2_Y 20
526
-      #define ABL_PROBE_PT_3_X 170
527
-      #define ABL_PROBE_PT_3_Y 20
564
+    // Arbitrary points to probe.
565
+    // A simple cross-product is used to estimate the plane of the bed.
566
+    #define ABL_PROBE_PT_1_X 15
567
+    #define ABL_PROBE_PT_1_Y 180
568
+    #define ABL_PROBE_PT_2_X 15
569
+    #define ABL_PROBE_PT_2_Y 20
570
+    #define ABL_PROBE_PT_3_X 170
571
+    #define ABL_PROBE_PT_3_Y 20
528 572
 
529 573
   #endif // AUTO_BED_LEVELING_GRID
530 574
 
531
-  // Offsets to the Z probe relative to the nozzle tip.
575
+  // Z Probe to nozzle (X,Y) offset, relative to (0, 0).
532 576
   // X and Y offsets must be integers.
533
-  #define X_PROBE_OFFSET_FROM_EXTRUDER 0     // Z probe to nozzle X offset: -left  +right
534
-  #define Y_PROBE_OFFSET_FROM_EXTRUDER -10   // Z probe to nozzle Y offset: -front +behind
535
-  #define Z_PROBE_OFFSET_FROM_EXTRUDER -3.5  // Z probe to nozzle Z offset: -below (always!)
536
-
537
-  #define Z_RAISE_BEFORE_HOMING 4       // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
538
-                                        // Be sure you have this distance over your Z_MAX_POS in case.
577
+  //
578
+  // In the following example the X and Y offsets are both positive:
579
+  // #define X_PROBE_OFFSET_FROM_EXTRUDER 10
580
+  // #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
581
+  //
582
+  //    +-- BACK ---+
583
+  //    |           |
584
+  //  L |    (+) P  | R <-- probe (20,20)
585
+  //  E |           | I
586
+  //  F | (-) N (+) | G <-- nozzle (10,10)
587
+  //  T |           | H
588
+  //    |    (-)    | T
589
+  //    |           |
590
+  //    O-- FRONT --+
591
+  //  (0,0)
592
+  #define X_PROBE_OFFSET_FROM_EXTRUDER 0     // X offset: -left  [of the nozzle] +right
593
+  #define Y_PROBE_OFFSET_FROM_EXTRUDER -10   // Y offset: -front [of the nozzle] +behind
594
+  #define Z_PROBE_OFFSET_FROM_EXTRUDER -3.5  // Z offset: -below [the nozzle] (always negative!)
539 595
 
540 596
   #define XY_TRAVEL_SPEED 4000         // X and Y axis travel speed between probes, in mm/min.
541 597
 
@@ -543,10 +599,22 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
543 599
   #define Z_RAISE_BETWEEN_PROBINGS 5  // How much the Z axis will be raised when traveling from between next probing points.
544 600
   #define Z_RAISE_AFTER_PROBING 50    // How much the Z axis will be raised after the last probing point.
545 601
 
546
-//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
547
-                                                                            // Useful to retract a deployable Z probe.
602
+  //#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
603
+                                                                             // Useful to retract a deployable Z probe.
604
+
605
+  // Probes are sensors/switches that need to be activated before they can be used
606
+  // and deactivated after the use.
607
+  // Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
608
+
609
+  // A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
610
+  // when the hardware endstops are active.
611
+  //#define FIX_MOUNTED_PROBE
612
+
613
+  // A Servo Probe can be defined in the servo section below.
614
+
615
+  // An Allen Key Probe is currently predefined only in the delta example configurations.
548 616
 
549
-  //#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
617
+  //#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
550 618
   //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
551 619
 
552 620
   // Allen key retractable Z probe as seen on many Kossel delta printers - http://reprap.org/wiki/Kossel#Automatic_bed_leveling_probe
@@ -630,10 +698,11 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
630 698
     #define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE HOMING_FEEDRATE_XYZ
631 699
   #endif
632 700
 
633
-// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
634
-// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
701
+  // If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
702
+  // it is highly recommended you leave Z_SAFE_HOMING enabled!
635 703
 
636
-  #define Z_SAFE_HOMING   // This feature is meant to avoid Z homing with Z probe outside the bed area.
704
+  #define Z_SAFE_HOMING   // Use the z-min-probe for homing to z-min - not the z-min-endstop.
705
+                          // This feature is meant to avoid Z homing with Z probe outside the bed area.
637 706
                           // When defined, it will:
638 707
                           // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
639 708
                           // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
@@ -647,37 +716,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
647 716
 
648 717
   #endif
649 718
 
650
-  // Support for a dedicated Z probe endstop separate from the Z min endstop.
651
-  // If you would like to use both a Z probe and a Z min endstop together,
652
-  // uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
653
-  // If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
654
-  // Example: To park the head outside the bed area when homing with G28.
655
-  //
656
-  // WARNING:
657
-  // The Z min endstop will need to set properly as it would without a Z probe
658
-  // to prevent head crashes and premature stopping during a print.
659
-  //
660
-  // To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
661
-  // defined in the pins_XXXXX.h file for your control board.
662
-  // If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
663
-  // Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
664
-  // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
665
-  // in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
666
-  // otherwise connect to ground and D32 for normally closed configuration
667
-  // and 5V and D32 for normally open configurations.
668
-  // Normally closed configuration is advised and assumed.
669
-  // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
670
-  // Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
671
-  // Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
672
-  // D32 is currently selected in the RAMPS 1.3/1.4 pin file.
673
-  // All other boards will need changes to the respective pins_XXXXX.h file.
674
-  //
675
-  // WARNING:
676
-  // Setting the wrong pin may have unexpected and potentially disastrous outcomes.
677
-  // Use with caution and do your homework.
678
-  //
679
-  //#define Z_MIN_PROBE_ENDSTOP
680
-
681 719
 #endif // AUTO_BED_LEVELING_FEATURE
682 720
 
683 721
 
@@ -710,7 +748,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
710 748
 // delta speeds must be the same on xyz
711 749
 #define DEFAULT_AXIS_STEPS_PER_UNIT   {72.9, 72.9, 72.9, 291}  // default steps per unit for BI v2.5 (cable drive)
712 750
 #define DEFAULT_MAX_FEEDRATE          {500, 500, 500, 150}    // (mm/sec)
713
-#define DEFAULT_MAX_ACCELERATION      {9000,9000,9000,10000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot.
751
+#define DEFAULT_MAX_ACCELERATION      {9000,9000,9000,10000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
714 752
 
715 753
 #define DEFAULT_ACCELERATION          3000    // X, Y, Z and E acceleration in mm/s^2 for printing moves
716 754
 #define DEFAULT_RETRACT_ACCELERATION  3000    // E acceleration in mm/s^2 for retracts
@@ -754,6 +792,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
754 792
 #endif
755 793
 
756 794
 //
795
+// Host Keepalive
796
+//
797
+// By default Marlin will send a busy status message to the host
798
+// every 2 seconds when it can't accept commands.
799
+//
800
+//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
801
+
802
+//
757 803
 // M100 Free Memory Watcher
758 804
 //
759 805
 //#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
@@ -773,13 +819,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
773 819
 // @section lcd
774 820
 
775 821
 // Define your display language below. Replace (en) with your language code and uncomment.
776
-// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
822
+// en, pl, fr, de, es, ru, bg, it, pt, pt_utf8, pt-br, pt-br_utf8, fi, an, nl, ca, eu, kana, kana_utf8, cn, cz, test
777 823
 // See also language.h
778 824
 #define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
779 825
 
780 826
 // Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
781 827
 // To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
782
-// See also documentation/LCDLanguageFont.md
828
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
783 829
   #define DISPLAY_CHARSET_HD44780_JAPAN        // this is the most common hardware
784 830
   //#define DISPLAY_CHARSET_HD44780_WESTERN
785 831
   //#define DISPLAY_CHARSET_HD44780_CYRILLIC
@@ -787,12 +833,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
787 833
 //#define ULTRA_LCD  //general LCD support, also 16x2
788 834
 //#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
789 835
 //#define SDSUPPORT // Enable SD Card Support in Hardware Console
790
-// Changed behaviour! If you need SDSUPPORT uncomment it!
791
-//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
792
-//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
836
+                    // Changed behaviour! If you need SDSUPPORT uncomment it!
837
+//#define SPI_SPEED SPI_HALF_SPEED // (also SPI_QUARTER_SPEED, SPI_EIGHTH_SPEED) Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
793 838
 //#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
794 839
 //#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
795 840
 //#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
841
+//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
796 842
 //#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
797 843
 //#define ULTIPANEL  //the UltiPanel as on Thingiverse
798 844
 //#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
@@ -809,13 +855,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
809 855
 
810 856
 // The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
811 857
 // http://panucatt.com
812
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
858
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
813 859
 //#define VIKI2
814 860
 //#define miniVIKI
815 861
 
816 862
 // This is a new controller currently under development.  https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
817 863
 //
818
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
864
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
819 865
 //#define ELB_FULL_GRAPHIC_CONTROLLER
820 866
 //#define SD_DETECT_INVERTED
821 867
 
@@ -830,7 +876,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
830 876
 // The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
831 877
 // http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
832 878
 //
833
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
879
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
834 880
 #define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
835 881
 
836 882
 // The RepRapWorld REPRAPWORLD_KEYPAD v1.1
@@ -843,6 +889,10 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
843 889
 // REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
844 890
 //#define RA_CONTROL_PANEL
845 891
 
892
+// The MakerLab Mini Panel with graphic controller and SD support
893
+// http://reprap.org/wiki/Mini_panel
894
+//#define MINIPANEL
895
+
846 896
 // Delta calibration menu
847 897
 // uncomment to add three points calibration menu option.
848 898
 // See http://minow.blogspot.com/index.html#4918805519571907051
@@ -856,6 +906,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
856 906
 
857 907
 //#define LCD_I2C_SAINSMART_YWROBOT
858 908
 
909
+//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
910
+
859 911
 // PANELOLU2 LCD with status LEDs, separate encoder and click inputs
860 912
 //
861 913
 // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
@@ -869,7 +921,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
869 921
 //#define LCD_I2C_VIKI
870 922
 
871 923
 // SSD1306 OLED generic display support
872
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
924
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
873 925
 //#define U8GLIB_SSD1306
874 926
 
875 927
 // Shift register panels
@@ -881,7 +933,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
881 933
 
882 934
 // @section extras
883 935
 
884
-// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
936
+// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
885 937
 //#define FAST_PWM_FAN
886 938
 
887 939
 // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
@@ -963,19 +1015,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
963 1015
 // Uncomment below to enable
964 1016
 //#define FILAMENT_SENSOR
965 1017
 
966
-#define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
967
-#define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
968
-
969 1018
 #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
970
-#define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
971
-#define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
972
-#define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
973 1019
 
974
-//defines used in the code
975
-#define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
1020
+#if ENABLED(FILAMENT_SENSOR)
1021
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
1022
+  #define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
1023
+
1024
+  #define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
1025
+  #define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
1026
+  #define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
976 1027
 
977
-//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
978
-//#define FILAMENT_LCD_DISPLAY
1028
+  #define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
1029
+
1030
+  //When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
1031
+  //#define FILAMENT_LCD_DISPLAY
1032
+#endif
979 1033
 
980 1034
 #include "Configuration_adv.h"
981 1035
 #include "thermistortables.h"

+ 85
- 59
Marlin/example_configurations/delta/biv2.5/Configuration_adv.h Näytä tiedosto

@@ -17,6 +17,20 @@
17 17
 /**
18 18
  * Thermal Protection parameters
19 19
  */
20
+  /**
21
+   * Thermal Protection protects your printer from damage and fire if a
22
+   * thermistor falls out or temperature sensors fail in any way.
23
+   *
24
+   * The issue: If a thermistor falls out or a temperature sensor fails,
25
+   * Marlin can no longer sense the actual temperature. Since a disconnected
26
+   * thermistor reads as a low temperature, the firmware will keep the heater on.
27
+   *
28
+   * The solution: Once the temperature reaches the target, start observing.
29
+   * If the temperature stays too far below the target (hysteresis) for too long (period),
30
+   * the firmware will halt the machine as a safety precaution.
31
+   *
32
+   * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
33
+   */
20 34
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
21 35
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
22 36
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
@@ -26,26 +40,24 @@
26 40
    * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
27 41
    * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
28 42
    * but only if the current temperature is far enough below the target for a reliable test.
43
+   *
44
+   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
45
+   * WATCH_TEMP_INCREASE should not be below 2.
29 46
    */
30 47
   #define WATCH_TEMP_PERIOD 16                // Seconds
31 48
   #define WATCH_TEMP_INCREASE 4               // Degrees Celsius
32 49
 #endif
33 50
 
51
+  /**
52
+   * Thermal Protection parameters for the bed
53
+   * are like the above for the hotends.
54
+   * WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
55
+   */
34 56
 #if ENABLED(THERMAL_PROTECTION_BED)
35 57
   #define THERMAL_PROTECTION_BED_PERIOD 120   // Seconds
36 58
   #define THERMAL_PROTECTION_BED_HYSTERESIS 4 // Degrees Celsius
37 59
 #endif
38 60
 
39
-/**
40
- * Automatic Temperature:
41
- * The hotend target temperature is calculated by all the buffered lines of gcode.
42
- * The maximum buffered steps/sec of the extruder motor is called "se".
43
- * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
44
- * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
45
- * mintemp and maxtemp. Turn this off by excuting M109 without F*
46
- * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
47
- * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
48
- */
49 61
 #if ENABLED(PIDTEMP)
50 62
   // this adds an experimental additional term to the heating power, proportional to the extrusion speed.
51 63
   // if Kc is chosen well, the additional required power due to increased melting should be compensated.
@@ -56,14 +68,16 @@
56 68
   #endif
57 69
 #endif
58 70
 
59
-
60
-//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
61
-//The maximum buffered steps/sec of the extruder motor are called "se".
62
-//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
63
-// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
64
-// you exit the value by any M109 without F*
65
-// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
66
-// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
71
+/**
72
+ * Automatic Temperature:
73
+ * The hotend target temperature is calculated by all the buffered lines of gcode.
74
+ * The maximum buffered steps/sec of the extruder motor is called "se".
75
+ * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
76
+ * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
77
+ * mintemp and maxtemp. Turn this off by executing M109 without F*
78
+ * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
79
+ * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
80
+ */
67 81
 #define AUTOTEMP
68 82
 #if ENABLED(AUTOTEMP)
69 83
   #define AUTOTEMP_OLDWEIGHT 0.98
@@ -240,7 +254,13 @@
240 254
 #define INVERT_E_STEP_PIN false
241 255
 
242 256
 // Default stepper release if idle. Set to 0 to deactivate.
257
+// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
258
+// Time can be set by M18 and M84.
243 259
 #define DEFAULT_STEPPER_DEACTIVE_TIME 0
260
+#define DISABLE_INACTIVE_X true
261
+#define DISABLE_INACTIVE_Y true
262
+#define DISABLE_INACTIVE_Z true  // set to false if the nozzle will fall down on your printed part when print has finished.
263
+#define DISABLE_INACTIVE_E true
244 264
 
245 265
 #define DEFAULT_MINIMUMFEEDRATE       0.0     // minimum feedrate
246 266
 #define DEFAULT_MINTRAVELFEEDRATE     0.0
@@ -278,6 +298,9 @@
278 298
 // Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
279 299
 #define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
280 300
 
301
+// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
302
+//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
303
+
281 304
 // uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
282 305
 //#define DIGIPOT_I2C
283 306
 // Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
@@ -354,13 +377,13 @@
354 377
 // @section more
355 378
 
356 379
 // The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
357
-//#define USE_WATCHDOG
380
+#define USE_WATCHDOG
358 381
 
359 382
 #if ENABLED(USE_WATCHDOG)
360
-// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
361
-// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
362
-//  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
363
-//#define WATCHDOG_RESET_MANUAL
383
+  // If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
384
+  // The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
385
+  //  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
386
+  //#define WATCHDOG_RESET_MANUAL
364 387
 #endif
365 388
 
366 389
 // @section lcd
@@ -371,6 +394,7 @@
371 394
 //#define BABYSTEPPING
372 395
 #if ENABLED(BABYSTEPPING)
373 396
   #define BABYSTEP_XY  //not only z, but also XY in the menu. more clutter, more functions
397
+                       //not implemented for deltabots!
374 398
   #define BABYSTEP_INVERT_Z false  //true for inverse movements in Z
375 399
   #define BABYSTEP_MULTIPLICATOR 1 //faster movements
376 400
 #endif
@@ -389,7 +413,6 @@
389 413
 #if ENABLED(ADVANCE)
390 414
   #define EXTRUDER_ADVANCE_K .0
391 415
   #define D_FILAMENT 2.85
392
-  #define STEPS_MM_E 836
393 416
 #endif
394 417
 
395 418
 // @section extras
@@ -398,7 +421,7 @@
398 421
 #define MM_PER_ARC_SEGMENT 1
399 422
 #define N_ARC_CORRECTION 25
400 423
 
401
-const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
424
+const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
402 425
 
403 426
 // @section temperature
404 427
 
@@ -447,11 +470,11 @@ const unsigned int dropsegments=5; //everything with less than this number of st
447 470
   #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
448 471
   #define RETRACT_LENGTH 5               //default retract length (positive mm)
449 472
   #define RETRACT_LENGTH_SWAP 13         //default swap retract length (positive mm), for extruder change
450
-  #define RETRACT_FEEDRATE 100            //default feedrate for retracting (mm/s)
473
+  #define RETRACT_FEEDRATE 100           //default feedrate for retracting (mm/s)
451 474
   #define RETRACT_ZLIFT 0                //default retract Z-lift
452 475
   #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
453 476
   #define RETRACT_RECOVER_LENGTH_SWAP 0  //default additional swap recover length (mm, added to retract length when recovering from extruder change)
454
-  #define RETRACT_RECOVER_FEEDRATE 100     //default feedrate for recovering from retraction (mm/s)
477
+  #define RETRACT_RECOVER_FEEDRATE 100   //default feedrate for recovering from retraction (mm/s)
455 478
 #endif
456 479
 
457 480
 // Add support for experimental filament exchange support M600; requires display
@@ -463,12 +486,15 @@ const unsigned int dropsegments=5; //everything with less than this number of st
463 486
     #define FILAMENTCHANGE_ZADD 10
464 487
     #define FILAMENTCHANGE_FIRSTRETRACT -2
465 488
     #define FILAMENTCHANGE_FINALRETRACT -100
489
+    #define AUTO_FILAMENT_CHANGE                //This extrude filament until you press the button on LCD
490
+    #define AUTO_FILAMENT_CHANGE_LENGTH 0.04    //Extrusion length on automatic extrusion loop
491
+    #define AUTO_FILAMENT_CHANGE_FEEDRATE 300   //Extrusion feedrate (mm/min) on automatic extrusion loop
466 492
   #endif
467 493
 #endif
468 494
 
469 495
 /******************************************************************************\
470 496
  * enable this section if you have TMC26X motor drivers.
471
- * you need to import the TMC26XStepper library into the arduino IDE for this
497
+ * you need to import the TMC26XStepper library into the Arduino IDE for this
472 498
  ******************************************************************************/
473 499
 
474 500
 // @section tmc
@@ -476,52 +502,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
476 502
 //#define HAVE_TMCDRIVER
477 503
 #if ENABLED(HAVE_TMCDRIVER)
478 504
 
479
-//#define X_IS_TMC
505
+  //#define X_IS_TMC
480 506
   #define X_MAX_CURRENT 1000  //in mA
481 507
   #define X_SENSE_RESISTOR 91 //in mOhms
482 508
   #define X_MICROSTEPS 16     //number of microsteps
483 509
 
484
-//#define X2_IS_TMC
510
+  //#define X2_IS_TMC
485 511
   #define X2_MAX_CURRENT 1000  //in mA
486 512
   #define X2_SENSE_RESISTOR 91 //in mOhms
487 513
   #define X2_MICROSTEPS 16     //number of microsteps
488 514
 
489
-//#define Y_IS_TMC
515
+  //#define Y_IS_TMC
490 516
   #define Y_MAX_CURRENT 1000  //in mA
491 517
   #define Y_SENSE_RESISTOR 91 //in mOhms
492 518
   #define Y_MICROSTEPS 16     //number of microsteps
493 519
 
494
-//#define Y2_IS_TMC
520
+  //#define Y2_IS_TMC
495 521
   #define Y2_MAX_CURRENT 1000  //in mA
496 522
   #define Y2_SENSE_RESISTOR 91 //in mOhms
497 523
   #define Y2_MICROSTEPS 16     //number of microsteps
498 524
 
499
-//#define Z_IS_TMC
525
+  //#define Z_IS_TMC
500 526
   #define Z_MAX_CURRENT 1000  //in mA
501 527
   #define Z_SENSE_RESISTOR 91 //in mOhms
502 528
   #define Z_MICROSTEPS 16     //number of microsteps
503 529
 
504
-//#define Z2_IS_TMC
530
+  //#define Z2_IS_TMC
505 531
   #define Z2_MAX_CURRENT 1000  //in mA
506 532
   #define Z2_SENSE_RESISTOR 91 //in mOhms
507 533
   #define Z2_MICROSTEPS 16     //number of microsteps
508 534
 
509
-//#define E0_IS_TMC
535
+  //#define E0_IS_TMC
510 536
   #define E0_MAX_CURRENT 1000  //in mA
511 537
   #define E0_SENSE_RESISTOR 91 //in mOhms
512 538
   #define E0_MICROSTEPS 16     //number of microsteps
513 539
 
514
-//#define E1_IS_TMC
540
+  //#define E1_IS_TMC
515 541
   #define E1_MAX_CURRENT 1000  //in mA
516 542
   #define E1_SENSE_RESISTOR 91 //in mOhms
517 543
   #define E1_MICROSTEPS 16     //number of microsteps
518 544
 
519
-//#define E2_IS_TMC
545
+  //#define E2_IS_TMC
520 546
   #define E2_MAX_CURRENT 1000  //in mA
521 547
   #define E2_SENSE_RESISTOR 91 //in mOhms
522 548
   #define E2_MICROSTEPS 16     //number of microsteps
523 549
 
524
-//#define E3_IS_TMC
550
+  //#define E3_IS_TMC
525 551
   #define E3_MAX_CURRENT 1000  //in mA
526 552
   #define E3_SENSE_RESISTOR 91 //in mOhms
527 553
   #define E3_MICROSTEPS 16     //number of microsteps
@@ -530,7 +556,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
530 556
 
531 557
 /******************************************************************************\
532 558
  * enable this section if you have L6470  motor drivers.
533
- * you need to import the L6470 library into the arduino IDE for this
559
+ * you need to import the L6470 library into the Arduino IDE for this
534 560
  ******************************************************************************/
535 561
 
536 562
 // @section l6470
@@ -538,63 +564,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
538 564
 //#define HAVE_L6470DRIVER
539 565
 #if ENABLED(HAVE_L6470DRIVER)
540 566
 
541
-//#define X_IS_L6470
567
+  //#define X_IS_L6470
542 568
   #define X_MICROSTEPS 16     //number of microsteps
543
-  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
569
+  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
544 570
   #define X_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
545 571
   #define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
546 572
 
547
-//#define X2_IS_L6470
573
+  //#define X2_IS_L6470
548 574
   #define X2_MICROSTEPS 16     //number of microsteps
549
-  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
575
+  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
550 576
   #define X2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
551 577
   #define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
552 578
 
553
-//#define Y_IS_L6470
579
+  //#define Y_IS_L6470
554 580
   #define Y_MICROSTEPS 16     //number of microsteps
555
-  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
581
+  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
556 582
   #define Y_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
557 583
   #define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
558 584
 
559
-//#define Y2_IS_L6470
585
+  //#define Y2_IS_L6470
560 586
   #define Y2_MICROSTEPS 16     //number of microsteps
561
-  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
587
+  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
562 588
   #define Y2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
563 589
   #define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
564 590
 
565
-//#define Z_IS_L6470
591
+  //#define Z_IS_L6470
566 592
   #define Z_MICROSTEPS 16     //number of microsteps
567
-  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
593
+  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
568 594
   #define Z_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
569 595
   #define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
570 596
 
571
-//#define Z2_IS_L6470
597
+  //#define Z2_IS_L6470
572 598
   #define Z2_MICROSTEPS 16     //number of microsteps
573
-  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
599
+  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
574 600
   #define Z2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
575 601
   #define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
576 602
 
577
-//#define E0_IS_L6470
603
+  //#define E0_IS_L6470
578 604
   #define E0_MICROSTEPS 16     //number of microsteps
579
-  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
605
+  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
580 606
   #define E0_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
581 607
   #define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
582 608
 
583
-//#define E1_IS_L6470
609
+  //#define E1_IS_L6470
584 610
   #define E1_MICROSTEPS 16     //number of microsteps
585
-  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
611
+  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
586 612
   #define E1_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
587 613
   #define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
588 614
 
589
-//#define E2_IS_L6470
615
+  //#define E2_IS_L6470
590 616
   #define E2_MICROSTEPS 16     //number of microsteps
591
-  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
617
+  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
592 618
   #define E2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
593 619
   #define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
594 620
 
595
-//#define E3_IS_L6470
621
+  //#define E3_IS_L6470
596 622
   #define E3_MICROSTEPS 16     //number of microsteps
597
-  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
623
+  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
598 624
   #define E3_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
599 625
   #define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
600 626
 

+ 161
- 112
Marlin/example_configurations/delta/generic/Configuration.h Näytä tiedosto

@@ -70,7 +70,7 @@ Here are some standard links for getting your machine calibrated:
70 70
 // The following define selects which electronics board you have.
71 71
 // Please choose the name from boards.h that matches your setup
72 72
 #ifndef MOTHERBOARD
73
-  #define MOTHERBOARD BOARD_RAMPS_13_EFB
73
+  #define MOTHERBOARD BOARD_RAMPS_14_EFB
74 74
 #endif
75 75
 
76 76
 // Optional custom name for your RepStrap or other custom machine
@@ -110,6 +110,7 @@ Here are some standard links for getting your machine calibrated:
110 110
 //--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
111 111
 //
112 112
 //// Temperature sensor settings:
113
+// -3 is thermocouple with MAX31855 (only for sensor 0)
113 114
 // -2 is thermocouple with MAX6675 (only for sensor 0)
114 115
 // -1 is thermocouple with AD595
115 116
 // 0 is not used
@@ -129,6 +130,7 @@ Here are some standard links for getting your machine calibrated:
129 130
 // 13 is 100k Hisens 3950  1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
130 131
 // 20 is the PT100 circuit found in the Ultimainboard V2.x
131 132
 // 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
133
+// 70 is the 100K thermistor found in the bq Hephestos 2
132 134
 //
133 135
 //    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
134 136
 //                          (but gives greater accuracy and more stable PID)
@@ -144,7 +146,7 @@ Here are some standard links for getting your machine calibrated:
144 146
 //     Use it for Testing or Development purposes. NEVER for production machine.
145 147
 //#define DUMMY_THERMISTOR_998_VALUE 25
146 148
 //#define DUMMY_THERMISTOR_999_VALUE 100
147
-// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
149
+// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-3': "Thermocouple + MAX31855 (only for sensor 0)", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
148 150
 #define TEMP_SENSOR_0 -1
149 151
 #define TEMP_SENSOR_1 -1
150 152
 #define TEMP_SENSOR_2 0
@@ -178,14 +180,9 @@ Here are some standard links for getting your machine calibrated:
178 180
 #define HEATER_3_MAXTEMP 275
179 181
 #define BED_MAXTEMP 150
180 182
 
181
-// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
182
-// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
183
-// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
184
-//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
185
-
186 183
 // If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
187
-//#define EXTRUDER_WATTS (12.0*12.0/6.7) //  P=I^2/R
188
-//#define BED_WATTS (12.0*12.0/1.1)      // P=I^2/R
184
+//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
185
+//#define BED_WATTS (12.0*12.0/1.1)      // P=U^2/R
189 186
 
190 187
 //===========================================================================
191 188
 //============================= PID Settings ================================
@@ -253,13 +250,13 @@ Here are some standard links for getting your machine calibrated:
253 250
 
254 251
   #define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
255 252
 
256
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
253
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
257 254
   //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
258 255
   #define  DEFAULT_bedKp 10.00
259 256
   #define  DEFAULT_bedKi .023
260 257
   #define  DEFAULT_bedKd 305.4
261 258
 
262
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
259
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
263 260
   //from pidautotune
264 261
   //#define  DEFAULT_bedKp 97.1
265 262
   //#define  DEFAULT_bedKi 1.41
@@ -284,16 +281,15 @@ Here are some standard links for getting your machine calibrated:
284 281
 //===========================================================================
285 282
 
286 283
 /**
287
- * Thermal Runaway Protection protects your printer from damage and fire if a
284
+ * Thermal Protection protects your printer from damage and fire if a
288 285
  * thermistor falls out or temperature sensors fail in any way.
289 286
  *
290 287
  * The issue: If a thermistor falls out or a temperature sensor fails,
291 288
  * Marlin can no longer sense the actual temperature. Since a disconnected
292 289
  * thermistor reads as a low temperature, the firmware will keep the heater on.
293 290
  *
294
- * The solution: Once the temperature reaches the target, start observing.
295
- * If the temperature stays too far below the target (hysteresis) for too long,
296
- * the firmware will halt as a safety precaution.
291
+ * If you get "Thermal Runaway" or "Heating failed" errors the
292
+ * details can be tuned in Configuration_adv.h
297 293
  */
298 294
 
299 295
 #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
@@ -376,10 +372,52 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
376 372
 //#define DISABLE_MAX_ENDSTOPS
377 373
 #define DISABLE_MIN_ENDSTOPS // Deltas only use min endstops for probing.
378 374
 
379
-// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
380
-// This only affects a Z probe endstop if you have separate Z min endstop as well and have
381
-// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
382
-// this has no effect.
375
+//===========================================================================
376
+//============================= Z Probe Options =============================
377
+//===========================================================================
378
+
379
+// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
380
+// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
381
+//
382
+// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
383
+//
384
+// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
385
+// Example: To park the head outside the bed area when homing with G28.
386
+//
387
+// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
388
+//
389
+// For a servo-based Z probe, you must set up servo support below, including
390
+// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
391
+//
392
+// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
393
+// - Use 5V for powered (usu. inductive) sensors.
394
+// - Otherwise connect:
395
+//   - normally-closed switches to GND and D32.
396
+//   - normally-open switches to 5V and D32.
397
+//
398
+// Normally-closed switches are advised and are the default.
399
+//
400
+// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
401
+// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
402
+// default pin for all RAMPS-based boards. Some other boards map differently.
403
+// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
404
+//
405
+// WARNING:
406
+// Setting the wrong pin may have unexpected and potentially disastrous consequences.
407
+// Use with caution and do your homework.
408
+//
409
+#define Z_MIN_PROBE_ENDSTOP
410
+
411
+// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
412
+// The Z_MIN_PIN will then be used for both Z-homing and probing.
413
+//#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
414
+
415
+// To use a probe you must enable one of the two options above!
416
+
417
+// This option disables the use of the Z_MIN_PROBE_PIN
418
+// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
419
+// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
420
+// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
383 421
 //#define DISABLE_Z_MIN_PROBE_ENDSTOP
384 422
 
385 423
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
@@ -389,11 +427,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
389 427
 #define Z_ENABLE_ON 0
390 428
 #define E_ENABLE_ON 0 // For all extruders
391 429
 
392
-// Disables axis when it's not being used.
430
+// Disables axis stepper immediately when it's not being used.
393 431
 // WARNING: When motors turn off there is a chance of losing position accuracy!
394 432
 #define DISABLE_X false
395 433
 #define DISABLE_Y false
396 434
 #define DISABLE_Z false
435
+// Warn on display about possibly reduced accuracy
436
+//#define DISABLE_REDUCED_ACCURACY_WARNING
397 437
 
398 438
 // @section extruder
399 439
 
@@ -416,6 +456,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
416 456
 #define INVERT_E3_DIR false
417 457
 
418 458
 // @section homing
459
+//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
460
+                                    // Be sure you have this distance over your Z_MAX_POS in case.
419 461
 
420 462
 // ENDSTOP SETTINGS:
421 463
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
@@ -451,24 +493,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
451 493
 #endif
452 494
 
453 495
 //===========================================================================
454
-//=========================== Manual Bed Leveling ===========================
496
+//============================ Mesh Bed Leveling ============================
455 497
 //===========================================================================
456 498
 
457
-//#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
458 499
 //#define MESH_BED_LEVELING    // Enable mesh bed leveling.
459 500
 
460
-#if ENABLED(MANUAL_BED_LEVELING)
461
-  #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
462
-#endif  // MANUAL_BED_LEVELING
463
-
464 501
 #if ENABLED(MESH_BED_LEVELING)
465 502
   #define MESH_MIN_X 10
466
-  #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
503
+  #define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
467 504
   #define MESH_MIN_Y 10
468
-  #define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
505
+  #define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
469 506
   #define MESH_NUM_X_POINTS 3  // Don't use more than 7 points per axis, implementation limited.
470 507
   #define MESH_NUM_Y_POINTS 3
471 508
   #define MESH_HOME_SEARCH_Z 4  // Z after Home, bed somewhere below but above 0.0.
509
+
510
+  //#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
511
+
512
+  #if ENABLED(MANUAL_BED_LEVELING)
513
+    #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
514
+  #endif  // MANUAL_BED_LEVELING
515
+
472 516
 #endif  // MESH_BED_LEVELING
473 517
 
474 518
 //===========================================================================
@@ -477,14 +521,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
477 521
 
478 522
 // @section bedlevel
479 523
 
480
-
481 524
 //#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
482 525
 //#define DEBUG_LEVELING_FEATURE
483
-//#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
526
+//#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
484 527
 
485 528
 #if ENABLED(AUTO_BED_LEVELING_FEATURE)
486 529
 
487
-  // There are 2 different ways to specify probing locations.
530
+  // There are 2 different ways to specify probing locations:
488 531
   //
489 532
   // - "grid" mode
490 533
   //   Probe several points in a rectangular grid.
@@ -492,7 +535,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
492 535
   //   This mode is preferred because there are more measurements.
493 536
   //
494 537
   // - "3-point" mode
495
-  //   Probe 3 arbitrary points on the bed (that aren't colinear)
538
+  //   Probe 3 arbitrary points on the bed (that aren't collinear)
496 539
   //   You specify the XY coordinates of all 3 points.
497 540
 
498 541
   // Enable this to sample the bed in a grid (least squares solution).
@@ -508,35 +551,47 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
508 551
     #define FRONT_PROBE_BED_POSITION -DELTA_PROBABLE_RADIUS
509 552
     #define BACK_PROBE_BED_POSITION DELTA_PROBABLE_RADIUS
510 553
 
511
-    #define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
554
+    #define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
512 555
 
513 556
     // Non-linear bed leveling will be used.
514 557
     // Compensate by interpolating between the nearest four Z probe values for each point.
515 558
     // Useful for deltas where the print surface may appear like a bowl or dome shape.
516
-    // Works best with ACCURATE_BED_LEVELING_POINTS 5 or higher.
559
+    // Works best with AUTO_BED_LEVELING_GRID_POINTS 5 or higher.
517 560
     #define AUTO_BED_LEVELING_GRID_POINTS 9
518 561
 
519 562
   #else  // !AUTO_BED_LEVELING_GRID
520 563
 
521
-      // Arbitrary points to probe.
522
-      // A simple cross-product is used to estimate the plane of the bed.
523
-      #define ABL_PROBE_PT_1_X 15
524
-      #define ABL_PROBE_PT_1_Y 180
525
-      #define ABL_PROBE_PT_2_X 15
526
-      #define ABL_PROBE_PT_2_Y 20
527
-      #define ABL_PROBE_PT_3_X 170
528
-      #define ABL_PROBE_PT_3_Y 20
564
+    // Arbitrary points to probe.
565
+    // A simple cross-product is used to estimate the plane of the bed.
566
+    #define ABL_PROBE_PT_1_X 15
567
+    #define ABL_PROBE_PT_1_Y 180
568
+    #define ABL_PROBE_PT_2_X 15
569
+    #define ABL_PROBE_PT_2_Y 20
570
+    #define ABL_PROBE_PT_3_X 170
571
+    #define ABL_PROBE_PT_3_Y 20
529 572
 
530 573
   #endif // AUTO_BED_LEVELING_GRID
531 574
 
532
-  // Offsets to the Z probe relative to the nozzle tip.
575
+  // Z Probe to nozzle (X,Y) offset, relative to (0, 0).
533 576
   // X and Y offsets must be integers.
534
-  #define X_PROBE_OFFSET_FROM_EXTRUDER 0     // Z probe to nozzle X offset: -left  +right
535
-  #define Y_PROBE_OFFSET_FROM_EXTRUDER -10   // Z probe to nozzle Y offset: -front +behind
536
-  #define Z_PROBE_OFFSET_FROM_EXTRUDER -3.5  // Z probe to nozzle Z offset: -below (always!)
537
-
538
-  #define Z_RAISE_BEFORE_HOMING 4       // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
539
-                                        // Be sure you have this distance over your Z_MAX_POS in case.
577
+  //
578
+  // In the following example the X and Y offsets are both positive:
579
+  // #define X_PROBE_OFFSET_FROM_EXTRUDER 10
580
+  // #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
581
+  //
582
+  //    +-- BACK ---+
583
+  //    |           |
584
+  //  L |    (+) P  | R <-- probe (20,20)
585
+  //  E |           | I
586
+  //  F | (-) N (+) | G <-- nozzle (10,10)
587
+  //  T |           | H
588
+  //    |    (-)    | T
589
+  //    |           |
590
+  //    O-- FRONT --+
591
+  //  (0,0)
592
+  #define X_PROBE_OFFSET_FROM_EXTRUDER 0     // X offset: -left  [of the nozzle] +right
593
+  #define Y_PROBE_OFFSET_FROM_EXTRUDER -10   // Y offset: -front [of the nozzle] +behind
594
+  #define Z_PROBE_OFFSET_FROM_EXTRUDER -3.5  // Z offset: -below [the nozzle] (always negative!)
540 595
 
541 596
   #define XY_TRAVEL_SPEED 4000         // X and Y axis travel speed between probes, in mm/min.
542 597
 
@@ -544,13 +599,25 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
544 599
   #define Z_RAISE_BETWEEN_PROBINGS 5  // How much the Z axis will be raised when traveling from between next probing points
545 600
   #define Z_RAISE_AFTER_PROBING 50    // How much the Z axis will be raised after the last probing point.
546 601
 
547
-//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
548
-                                                                            // Useful to retract a deployable Z probe.
602
+  //#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
603
+                                                                             // Useful to retract a deployable Z probe.
604
+
605
+  // Probes are sensors/switches that need to be activated before they can be used
606
+  // and deactivated after the use.
607
+  // Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
549 608
 
550
-  //#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
609
+  // A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
610
+  // when the hardware endstops are active.
611
+  //#define FIX_MOUNTED_PROBE
612
+
613
+  // A Servo Probe can be defined in the servo section below.
614
+
615
+  // An Allen Key Probe is currently predefined only in the delta example configurations.
616
+
617
+  //#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
551 618
   //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
552 619
 
553
-  // Allen key retractable z-probe as seen on many Kossel delta printers - http://reprap.org/wiki/Kossel#Automatic_bed_leveling_probe
620
+  // Allen key retractable Z probe as seen on many Kossel delta printers - http://reprap.org/wiki/Kossel#Automatic_bed_leveling_probe
554 621
   // Deploys by touching z-axis belt. Retracts by pushing the probe down. Uses Z_MIN_PIN.
555 622
   //#define Z_PROBE_ALLEN_KEY
556 623
 
@@ -631,10 +698,11 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
631 698
     //#define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE HOMING_FEEDRATE_XYZ
632 699
   #endif
633 700
 
634
-// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
635
-// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
701
+  // If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
702
+  // it is highly recommended you leave Z_SAFE_HOMING enabled!
636 703
 
637
-  #define Z_SAFE_HOMING   // This feature is meant to avoid Z homing with Z probe outside the bed area.
704
+  #define Z_SAFE_HOMING   // Use the z-min-probe for homing to z-min - not the z-min-endstop.
705
+                          // This feature is meant to avoid Z homing with Z probe outside the bed area.
638 706
                           // When defined, it will:
639 707
                           // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
640 708
                           // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
@@ -648,37 +716,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
648 716
 
649 717
   #endif
650 718
 
651
-  // Support for a dedicated Z probe endstop separate from the Z min endstop.
652
-  // If you would like to use both a Z probe and a Z min endstop together,
653
-  // uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
654
-  // If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
655
-  // Example: To park the head outside the bed area when homing with G28.
656
-  //
657
-  // WARNING:
658
-  // The Z min endstop will need to set properly as it would without a Z probe
659
-  // to prevent head crashes and premature stopping during a print.
660
-  //
661
-  // To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
662
-  // defined in the pins_XXXXX.h file for your control board.
663
-  // If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
664
-  // Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
665
-  // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
666
-  // in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
667
-  // otherwise connect to ground and D32 for normally closed configuration
668
-  // and 5V and D32 for normally open configurations.
669
-  // Normally closed configuration is advised and assumed.
670
-  // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
671
-  // Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
672
-  // Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
673
-  // D32 is currently selected in the RAMPS 1.3/1.4 pin file.
674
-  // All other boards will need changes to the respective pins_XXXXX.h file.
675
-  //
676
-  // WARNING:
677
-  // Setting the wrong pin may have unexpected and potentially disastrous outcomes.
678
-  // Use with caution and do your homework.
679
-  //
680
-  //#define Z_MIN_PROBE_ENDSTOP
681
-
682 719
 #endif // AUTO_BED_LEVELING_FEATURE
683 720
 
684 721
 
@@ -711,7 +748,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
711 748
 // delta speeds must be the same on xyz
712 749
 #define DEFAULT_AXIS_STEPS_PER_UNIT   {80, 80, 80, 760*1.1}  // default steps per unit for Kossel (GT2, 20 tooth)
713 750
 #define DEFAULT_MAX_FEEDRATE          {500, 500, 500, 25}    // (mm/sec)
714
-#define DEFAULT_MAX_ACCELERATION      {9000,9000,9000,10000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot.
751
+#define DEFAULT_MAX_ACCELERATION      {9000,9000,9000,10000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
715 752
 
716 753
 #define DEFAULT_ACCELERATION          3000    // X, Y, Z and E acceleration in mm/s^2 for printing moves
717 754
 #define DEFAULT_RETRACT_ACCELERATION  3000    // E acceleration in mm/s^2 for retracts
@@ -755,6 +792,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
755 792
 #endif
756 793
 
757 794
 //
795
+// Host Keepalive
796
+//
797
+// By default Marlin will send a busy status message to the host
798
+// every 2 seconds when it can't accept commands.
799
+//
800
+//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
801
+
802
+//
758 803
 // M100 Free Memory Watcher
759 804
 //
760 805
 //#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
@@ -774,13 +819,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
774 819
 // @section lcd
775 820
 
776 821
 // Define your display language below. Replace (en) with your language code and uncomment.
777
-// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
822
+// en, pl, fr, de, es, ru, bg, it, pt, pt_utf8, pt-br, pt-br_utf8, fi, an, nl, ca, eu, kana, kana_utf8, cn, cz, test
778 823
 // See also language.h
779 824
 #define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
780 825
 
781 826
 // Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
782 827
 // To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
783
-// See also documentation/LCDLanguageFont.md
828
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
784 829
   #define DISPLAY_CHARSET_HD44780_JAPAN        // this is the most common hardware
785 830
   //#define DISPLAY_CHARSET_HD44780_WESTERN
786 831
   //#define DISPLAY_CHARSET_HD44780_CYRILLIC
@@ -788,12 +833,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
788 833
 //#define ULTRA_LCD  //general LCD support, also 16x2
789 834
 //#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
790 835
 //#define SDSUPPORT // Enable SD Card Support in Hardware Console
791
-// Changed behaviour! If you need SDSUPPORT uncomment it!
792
-//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
793
-//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
836
+                    // Changed behaviour! If you need SDSUPPORT uncomment it!
837
+//#define SPI_SPEED SPI_HALF_SPEED // (also SPI_QUARTER_SPEED, SPI_EIGHTH_SPEED) Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
794 838
 //#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
795 839
 //#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
796 840
 //#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
841
+//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
797 842
 //#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
798 843
 //#define ULTIPANEL  //the UltiPanel as on Thingiverse
799 844
 //#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
@@ -810,13 +855,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
810 855
 
811 856
 // The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
812 857
 // http://panucatt.com
813
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
858
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
814 859
 //#define VIKI2
815 860
 //#define miniVIKI
816 861
 
817 862
 // This is a new controller currently under development.  https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
818 863
 //
819
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
864
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
820 865
 //#define ELB_FULL_GRAPHIC_CONTROLLER
821 866
 //#define SD_DETECT_INVERTED
822 867
 
@@ -831,7 +876,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
831 876
 // The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
832 877
 // http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
833 878
 //
834
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
879
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
835 880
 //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
836 881
 
837 882
 // The RepRapWorld REPRAPWORLD_KEYPAD v1.1
@@ -844,6 +889,10 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
844 889
 // REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
845 890
 //#define RA_CONTROL_PANEL
846 891
 
892
+// The MakerLab Mini Panel with graphic controller and SD support
893
+// http://reprap.org/wiki/Mini_panel
894
+//#define MINIPANEL
895
+
847 896
 // Delta calibration menu
848 897
 // uncomment to add three points calibration menu option.
849 898
 // See http://minow.blogspot.com/index.html#4918805519571907051
@@ -851,16 +900,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
851 900
 // in ultralcd.cpp@lcd_delta_calibrate_menu()
852 901
 //#define DELTA_CALIBRATION_MENU
853 902
 
854
-// The MakerLab Mini Panel with graphic controller and SD support
855
-// http://reprap.org/wiki/Mini_panel
856
-//#define MINIPANEL
857
-
858 903
 /**
859 904
  * I2C Panels
860 905
  */
861 906
 
862 907
 //#define LCD_I2C_SAINSMART_YWROBOT
863 908
 
909
+//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
910
+
864 911
 // PANELOLU2 LCD with status LEDs, separate encoder and click inputs
865 912
 //
866 913
 // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
@@ -874,7 +921,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
874 921
 //#define LCD_I2C_VIKI
875 922
 
876 923
 // SSD1306 OLED generic display support
877
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
924
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
878 925
 //#define U8GLIB_SSD1306
879 926
 
880 927
 // Shift register panels
@@ -886,7 +933,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
886 933
 
887 934
 // @section extras
888 935
 
889
-// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
936
+// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
890 937
 //#define FAST_PWM_FAN
891 938
 
892 939
 // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
@@ -968,19 +1015,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
968 1015
 // Uncomment below to enable
969 1016
 //#define FILAMENT_SENSOR
970 1017
 
971
-#define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
972
-#define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
973
-
974 1018
 #define DEFAULT_NOMINAL_FILAMENT_DIA 3.00  //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
975
-#define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
976
-#define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
977
-#define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
978 1019
 
979
-//defines used in the code
980
-#define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
1020
+#if ENABLED(FILAMENT_SENSOR)
1021
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
1022
+  #define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
981 1023
 
982
-//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
983
-//#define FILAMENT_LCD_DISPLAY
1024
+  #define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
1025
+  #define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
1026
+  #define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
1027
+
1028
+  #define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
1029
+
1030
+  //When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
1031
+  //#define FILAMENT_LCD_DISPLAY
1032
+#endif
984 1033
 
985 1034
 #include "Configuration_adv.h"
986 1035
 #include "thermistortables.h"

+ 83
- 58
Marlin/example_configurations/delta/generic/Configuration_adv.h Näytä tiedosto

@@ -17,6 +17,20 @@
17 17
 /**
18 18
  * Thermal Protection parameters
19 19
  */
20
+  /**
21
+   * Thermal Protection protects your printer from damage and fire if a
22
+   * thermistor falls out or temperature sensors fail in any way.
23
+   *
24
+   * The issue: If a thermistor falls out or a temperature sensor fails,
25
+   * Marlin can no longer sense the actual temperature. Since a disconnected
26
+   * thermistor reads as a low temperature, the firmware will keep the heater on.
27
+   *
28
+   * The solution: Once the temperature reaches the target, start observing.
29
+   * If the temperature stays too far below the target (hysteresis) for too long (period),
30
+   * the firmware will halt the machine as a safety precaution.
31
+   *
32
+   * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
33
+   */
20 34
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
21 35
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
22 36
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
@@ -26,26 +40,24 @@
26 40
    * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
27 41
    * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
28 42
    * but only if the current temperature is far enough below the target for a reliable test.
43
+   *
44
+   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
45
+   * WATCH_TEMP_INCREASE should not be below 2.
29 46
    */
30 47
   #define WATCH_TEMP_PERIOD 16                // Seconds
31 48
   #define WATCH_TEMP_INCREASE 4               // Degrees Celsius
32 49
 #endif
33 50
 
51
+  /**
52
+   * Thermal Protection parameters for the bed
53
+   * are like the above for the hotends.
54
+   * WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
55
+   */
34 56
 #if ENABLED(THERMAL_PROTECTION_BED)
35 57
   #define THERMAL_PROTECTION_BED_PERIOD 20    // Seconds
36 58
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
37 59
 #endif
38 60
 
39
-/**
40
- * Automatic Temperature:
41
- * The hotend target temperature is calculated by all the buffered lines of gcode.
42
- * The maximum buffered steps/sec of the extruder motor is called "se".
43
- * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
44
- * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
45
- * mintemp and maxtemp. Turn this off by excuting M109 without F*
46
- * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
47
- * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
48
- */
49 61
 #if ENABLED(PIDTEMP)
50 62
   // this adds an experimental additional term to the heating power, proportional to the extrusion speed.
51 63
   // if Kc is chosen well, the additional required power due to increased melting should be compensated.
@@ -56,14 +68,16 @@
56 68
   #endif
57 69
 #endif
58 70
 
59
-
60
-//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
61
-//The maximum buffered steps/sec of the extruder motor are called "se".
62
-//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
63
-// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
64
-// you exit the value by any M109 without F*
65
-// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
66
-// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
71
+/**
72
+ * Automatic Temperature:
73
+ * The hotend target temperature is calculated by all the buffered lines of gcode.
74
+ * The maximum buffered steps/sec of the extruder motor is called "se".
75
+ * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
76
+ * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
77
+ * mintemp and maxtemp. Turn this off by executing M109 without F*
78
+ * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
79
+ * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
80
+ */
67 81
 #define AUTOTEMP
68 82
 #if ENABLED(AUTOTEMP)
69 83
   #define AUTOTEMP_OLDWEIGHT 0.98
@@ -240,7 +254,13 @@
240 254
 #define INVERT_E_STEP_PIN false
241 255
 
242 256
 // Default stepper release if idle. Set to 0 to deactivate.
257
+// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
258
+// Time can be set by M18 and M84.
243 259
 #define DEFAULT_STEPPER_DEACTIVE_TIME 60
260
+#define DISABLE_INACTIVE_X true
261
+#define DISABLE_INACTIVE_Y true
262
+#define DISABLE_INACTIVE_Z true  // set to false if the nozzle will fall down on your printed part when print has finished.
263
+#define DISABLE_INACTIVE_E true
244 264
 
245 265
 #define DEFAULT_MINIMUMFEEDRATE       0.0     // minimum feedrate
246 266
 #define DEFAULT_MINTRAVELFEEDRATE     0.0
@@ -278,6 +298,9 @@
278 298
 // Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
279 299
 #define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
280 300
 
301
+// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
302
+//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
303
+
281 304
 // uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
282 305
 //#define DIGIPOT_I2C
283 306
 // Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
@@ -351,17 +374,16 @@
351 374
   //#define USE_SMALL_INFOFONT
352 375
 #endif // DOGLCD
353 376
 
354
-
355 377
 // @section more
356 378
 
357 379
 // The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
358
-//#define USE_WATCHDOG
380
+#define USE_WATCHDOG
359 381
 
360 382
 #if ENABLED(USE_WATCHDOG)
361
-// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
362
-// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
363
-//  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
364
-//#define WATCHDOG_RESET_MANUAL
383
+  // If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
384
+  // The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
385
+  //  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
386
+  //#define WATCHDOG_RESET_MANUAL
365 387
 #endif
366 388
 
367 389
 // @section lcd
@@ -372,6 +394,7 @@
372 394
 //#define BABYSTEPPING
373 395
 #if ENABLED(BABYSTEPPING)
374 396
   #define BABYSTEP_XY  //not only z, but also XY in the menu. more clutter, more functions
397
+                       //not implemented for deltabots!
375 398
   #define BABYSTEP_INVERT_Z false  //true for inverse movements in Z
376 399
   #define BABYSTEP_MULTIPLICATOR 1 //faster movements
377 400
 #endif
@@ -390,7 +413,6 @@
390 413
 #if ENABLED(ADVANCE)
391 414
   #define EXTRUDER_ADVANCE_K .0
392 415
   #define D_FILAMENT 2.85
393
-  #define STEPS_MM_E 836
394 416
 #endif
395 417
 
396 418
 // @section extras
@@ -399,7 +421,7 @@
399 421
 #define MM_PER_ARC_SEGMENT 1
400 422
 #define N_ARC_CORRECTION 25
401 423
 
402
-const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
424
+const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
403 425
 
404 426
 // @section temperature
405 427
 
@@ -464,12 +486,15 @@ const unsigned int dropsegments=5; //everything with less than this number of st
464 486
     #define FILAMENTCHANGE_ZADD 10
465 487
     #define FILAMENTCHANGE_FIRSTRETRACT -2
466 488
     #define FILAMENTCHANGE_FINALRETRACT -100
489
+    #define AUTO_FILAMENT_CHANGE                //This extrude filament until you press the button on LCD
490
+    #define AUTO_FILAMENT_CHANGE_LENGTH 0.04    //Extrusion length on automatic extrusion loop
491
+    #define AUTO_FILAMENT_CHANGE_FEEDRATE 300   //Extrusion feedrate (mm/min) on automatic extrusion loop
467 492
   #endif
468 493
 #endif
469 494
 
470 495
 /******************************************************************************\
471 496
  * enable this section if you have TMC26X motor drivers.
472
- * you need to import the TMC26XStepper library into the arduino IDE for this
497
+ * you need to import the TMC26XStepper library into the Arduino IDE for this
473 498
  ******************************************************************************/
474 499
 
475 500
 // @section tmc
@@ -477,52 +502,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
477 502
 //#define HAVE_TMCDRIVER
478 503
 #if ENABLED(HAVE_TMCDRIVER)
479 504
 
480
-//#define X_IS_TMC
505
+  //#define X_IS_TMC
481 506
   #define X_MAX_CURRENT 1000  //in mA
482 507
   #define X_SENSE_RESISTOR 91 //in mOhms
483 508
   #define X_MICROSTEPS 16     //number of microsteps
484 509
 
485
-//#define X2_IS_TMC
510
+  //#define X2_IS_TMC
486 511
   #define X2_MAX_CURRENT 1000  //in mA
487 512
   #define X2_SENSE_RESISTOR 91 //in mOhms
488 513
   #define X2_MICROSTEPS 16     //number of microsteps
489 514
 
490
-//#define Y_IS_TMC
515
+  //#define Y_IS_TMC
491 516
   #define Y_MAX_CURRENT 1000  //in mA
492 517
   #define Y_SENSE_RESISTOR 91 //in mOhms
493 518
   #define Y_MICROSTEPS 16     //number of microsteps
494 519
 
495
-//#define Y2_IS_TMC
520
+  //#define Y2_IS_TMC
496 521
   #define Y2_MAX_CURRENT 1000  //in mA
497 522
   #define Y2_SENSE_RESISTOR 91 //in mOhms
498 523
   #define Y2_MICROSTEPS 16     //number of microsteps
499 524
 
500
-//#define Z_IS_TMC
525
+  //#define Z_IS_TMC
501 526
   #define Z_MAX_CURRENT 1000  //in mA
502 527
   #define Z_SENSE_RESISTOR 91 //in mOhms
503 528
   #define Z_MICROSTEPS 16     //number of microsteps
504 529
 
505
-//#define Z2_IS_TMC
530
+  //#define Z2_IS_TMC
506 531
   #define Z2_MAX_CURRENT 1000  //in mA
507 532
   #define Z2_SENSE_RESISTOR 91 //in mOhms
508 533
   #define Z2_MICROSTEPS 16     //number of microsteps
509 534
 
510
-//#define E0_IS_TMC
535
+  //#define E0_IS_TMC
511 536
   #define E0_MAX_CURRENT 1000  //in mA
512 537
   #define E0_SENSE_RESISTOR 91 //in mOhms
513 538
   #define E0_MICROSTEPS 16     //number of microsteps
514 539
 
515
-//#define E1_IS_TMC
540
+  //#define E1_IS_TMC
516 541
   #define E1_MAX_CURRENT 1000  //in mA
517 542
   #define E1_SENSE_RESISTOR 91 //in mOhms
518 543
   #define E1_MICROSTEPS 16     //number of microsteps
519 544
 
520
-//#define E2_IS_TMC
545
+  //#define E2_IS_TMC
521 546
   #define E2_MAX_CURRENT 1000  //in mA
522 547
   #define E2_SENSE_RESISTOR 91 //in mOhms
523 548
   #define E2_MICROSTEPS 16     //number of microsteps
524 549
 
525
-//#define E3_IS_TMC
550
+  //#define E3_IS_TMC
526 551
   #define E3_MAX_CURRENT 1000  //in mA
527 552
   #define E3_SENSE_RESISTOR 91 //in mOhms
528 553
   #define E3_MICROSTEPS 16     //number of microsteps
@@ -531,7 +556,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
531 556
 
532 557
 /******************************************************************************\
533 558
  * enable this section if you have L6470  motor drivers.
534
- * you need to import the L6470 library into the arduino IDE for this
559
+ * you need to import the L6470 library into the Arduino IDE for this
535 560
  ******************************************************************************/
536 561
 
537 562
 // @section l6470
@@ -539,63 +564,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
539 564
 //#define HAVE_L6470DRIVER
540 565
 #if ENABLED(HAVE_L6470DRIVER)
541 566
 
542
-//#define X_IS_L6470
567
+  //#define X_IS_L6470
543 568
   #define X_MICROSTEPS 16     //number of microsteps
544
-  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
569
+  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
545 570
   #define X_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
546 571
   #define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
547 572
 
548
-//#define X2_IS_L6470
573
+  //#define X2_IS_L6470
549 574
   #define X2_MICROSTEPS 16     //number of microsteps
550
-  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
575
+  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
551 576
   #define X2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
552 577
   #define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
553 578
 
554
-//#define Y_IS_L6470
579
+  //#define Y_IS_L6470
555 580
   #define Y_MICROSTEPS 16     //number of microsteps
556
-  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
581
+  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
557 582
   #define Y_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
558 583
   #define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
559 584
 
560
-//#define Y2_IS_L6470
585
+  //#define Y2_IS_L6470
561 586
   #define Y2_MICROSTEPS 16     //number of microsteps
562
-  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
587
+  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
563 588
   #define Y2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
564 589
   #define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
565 590
 
566
-//#define Z_IS_L6470
591
+  //#define Z_IS_L6470
567 592
   #define Z_MICROSTEPS 16     //number of microsteps
568
-  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
593
+  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
569 594
   #define Z_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
570 595
   #define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
571 596
 
572
-//#define Z2_IS_L6470
597
+  //#define Z2_IS_L6470
573 598
   #define Z2_MICROSTEPS 16     //number of microsteps
574
-  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
599
+  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
575 600
   #define Z2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
576 601
   #define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
577 602
 
578
-//#define E0_IS_L6470
603
+  //#define E0_IS_L6470
579 604
   #define E0_MICROSTEPS 16     //number of microsteps
580
-  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
605
+  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
581 606
   #define E0_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
582 607
   #define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
583 608
 
584
-//#define E1_IS_L6470
609
+  //#define E1_IS_L6470
585 610
   #define E1_MICROSTEPS 16     //number of microsteps
586
-  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
611
+  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
587 612
   #define E1_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
588 613
   #define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
589 614
 
590
-//#define E2_IS_L6470
615
+  //#define E2_IS_L6470
591 616
   #define E2_MICROSTEPS 16     //number of microsteps
592
-  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
617
+  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
593 618
   #define E2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
594 619
   #define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
595 620
 
596
-//#define E3_IS_L6470
621
+  //#define E3_IS_L6470
597 622
   #define E3_MICROSTEPS 16     //number of microsteps
598
-  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
623
+  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
599 624
   #define E3_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
600 625
   #define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
601 626
 

+ 160
- 107
Marlin/example_configurations/delta/kossel_mini/Configuration.h Näytä tiedosto

@@ -70,7 +70,7 @@ Here are some standard links for getting your machine calibrated:
70 70
 // The following define selects which electronics board you have.
71 71
 // Please choose the name from boards.h that matches your setup
72 72
 #ifndef MOTHERBOARD
73
-  #define MOTHERBOARD BOARD_RAMPS_13_EFB
73
+  #define MOTHERBOARD BOARD_RAMPS_14_EFB
74 74
 #endif
75 75
 
76 76
 // Optional custom name for your RepStrap or other custom machine
@@ -110,6 +110,7 @@ Here are some standard links for getting your machine calibrated:
110 110
 //--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
111 111
 //
112 112
 //// Temperature sensor settings:
113
+// -3 is thermocouple with MAX31855 (only for sensor 0)
113 114
 // -2 is thermocouple with MAX6675 (only for sensor 0)
114 115
 // -1 is thermocouple with AD595
115 116
 // 0 is not used
@@ -129,6 +130,7 @@ Here are some standard links for getting your machine calibrated:
129 130
 // 13 is 100k Hisens 3950  1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
130 131
 // 20 is the PT100 circuit found in the Ultimainboard V2.x
131 132
 // 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
133
+// 70 is the 100K thermistor found in the bq Hephestos 2
132 134
 //
133 135
 //    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
134 136
 //                          (but gives greater accuracy and more stable PID)
@@ -144,7 +146,7 @@ Here are some standard links for getting your machine calibrated:
144 146
 //     Use it for Testing or Development purposes. NEVER for production machine.
145 147
 //#define DUMMY_THERMISTOR_998_VALUE 25
146 148
 //#define DUMMY_THERMISTOR_999_VALUE 100
147
-// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
149
+// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-3': "Thermocouple + MAX31855 (only for sensor 0)", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
148 150
 #define TEMP_SENSOR_0 7
149 151
 #define TEMP_SENSOR_1 0
150 152
 #define TEMP_SENSOR_2 0
@@ -178,14 +180,9 @@ Here are some standard links for getting your machine calibrated:
178 180
 #define HEATER_3_MAXTEMP 275
179 181
 #define BED_MAXTEMP 150
180 182
 
181
-// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
182
-// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
183
-// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
184
-//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
185
-
186 183
 // If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
187
-//#define EXTRUDER_WATTS (12.0*12.0/6.7) //  P=I^2/R
188
-//#define BED_WATTS (12.0*12.0/1.1)      // P=I^2/R
184
+//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
185
+//#define BED_WATTS (12.0*12.0/1.1)      // P=U^2/R
189 186
 
190 187
 //===========================================================================
191 188
 //============================= PID Settings ================================
@@ -253,13 +250,13 @@ Here are some standard links for getting your machine calibrated:
253 250
 
254 251
   #define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
255 252
 
256
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
253
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
257 254
   //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
258 255
   #define  DEFAULT_bedKp 10.00
259 256
   #define  DEFAULT_bedKi .023
260 257
   #define  DEFAULT_bedKd 305.4
261 258
 
262
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
259
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
263 260
   //from pidautotune
264 261
   //#define  DEFAULT_bedKp 97.1
265 262
   //#define  DEFAULT_bedKi 1.41
@@ -284,16 +281,15 @@ Here are some standard links for getting your machine calibrated:
284 281
 //===========================================================================
285 282
 
286 283
 /**
287
- * Thermal Runaway Protection protects your printer from damage and fire if a
284
+ * Thermal Protection protects your printer from damage and fire if a
288 285
  * thermistor falls out or temperature sensors fail in any way.
289 286
  *
290 287
  * The issue: If a thermistor falls out or a temperature sensor fails,
291 288
  * Marlin can no longer sense the actual temperature. Since a disconnected
292 289
  * thermistor reads as a low temperature, the firmware will keep the heater on.
293 290
  *
294
- * The solution: Once the temperature reaches the target, start observing.
295
- * If the temperature stays too far below the target (hysteresis) for too long,
296
- * the firmware will halt as a safety precaution.
291
+ * If you get "Thermal Runaway" or "Heating failed" errors the
292
+ * details can be tuned in Configuration_adv.h
297 293
  */
298 294
 
299 295
 #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
@@ -376,10 +372,52 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
376 372
 //#define DISABLE_MAX_ENDSTOPS
377 373
 //#define DISABLE_MIN_ENDSTOPS // Deltas only use min endstops for probing.
378 374
 
379
-// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
380
-// This only affects a Z probe endstop if you have separate Z min endstop as well and have
381
-// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
382
-// this has no effect.
375
+//===========================================================================
376
+//============================= Z Probe Options =============================
377
+//===========================================================================
378
+
379
+// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
380
+// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
381
+//
382
+// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
383
+//
384
+// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
385
+// Example: To park the head outside the bed area when homing with G28.
386
+//
387
+// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
388
+//
389
+// For a servo-based Z probe, you must set up servo support below, including
390
+// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
391
+//
392
+// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
393
+// - Use 5V for powered (usu. inductive) sensors.
394
+// - Otherwise connect:
395
+//   - normally-closed switches to GND and D32.
396
+//   - normally-open switches to 5V and D32.
397
+//
398
+// Normally-closed switches are advised and are the default.
399
+//
400
+// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
401
+// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
402
+// default pin for all RAMPS-based boards. Some other boards map differently.
403
+// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
404
+//
405
+// WARNING:
406
+// Setting the wrong pin may have unexpected and potentially disastrous consequences.
407
+// Use with caution and do your homework.
408
+//
409
+//#define Z_MIN_PROBE_ENDSTOP
410
+
411
+// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
412
+// The Z_MIN_PIN will then be used for both Z-homing and probing.
413
+#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
414
+
415
+// To use a probe you must enable one of the two options above!
416
+
417
+// This option disables the use of the Z_MIN_PROBE_PIN
418
+// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
419
+// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
420
+// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
383 421
 //#define DISABLE_Z_MIN_PROBE_ENDSTOP
384 422
 
385 423
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
@@ -389,11 +427,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
389 427
 #define Z_ENABLE_ON 0
390 428
 #define E_ENABLE_ON 0 // For all extruders
391 429
 
392
-// Disables axis when it's not being used.
430
+// Disables axis stepper immediately when it's not being used.
393 431
 // WARNING: When motors turn off there is a chance of losing position accuracy!
394 432
 #define DISABLE_X false
395 433
 #define DISABLE_Y false
396 434
 #define DISABLE_Z false
435
+// Warn on display about possibly reduced accuracy
436
+//#define DISABLE_REDUCED_ACCURACY_WARNING
397 437
 
398 438
 // @section extruder
399 439
 
@@ -416,6 +456,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
416 456
 #define INVERT_E3_DIR false
417 457
 
418 458
 // @section homing
459
+//#define MIN_Z_HEIGHT_FOR_HOMING 15// (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
460
+                                    // Be sure you have this distance over your Z_MAX_POS in case.
419 461
 
420 462
 // ENDSTOP SETTINGS:
421 463
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
@@ -451,24 +493,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
451 493
 #endif
452 494
 
453 495
 //===========================================================================
454
-//=========================== Manual Bed Leveling ===========================
496
+//============================ Mesh Bed Leveling ============================
455 497
 //===========================================================================
456 498
 
457
-//#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
458 499
 //#define MESH_BED_LEVELING    // Enable mesh bed leveling.
459 500
 
460
-#if ENABLED(MANUAL_BED_LEVELING)
461
-  #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
462
-#endif  // MANUAL_BED_LEVELING
463
-
464 501
 #if ENABLED(MESH_BED_LEVELING)
465 502
   #define MESH_MIN_X 10
466
-  #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
503
+  #define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
467 504
   #define MESH_MIN_Y 10
468
-  #define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
505
+  #define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
469 506
   #define MESH_NUM_X_POINTS 3  // Don't use more than 7 points per axis, implementation limited.
470 507
   #define MESH_NUM_Y_POINTS 3
471 508
   #define MESH_HOME_SEARCH_Z 4  // Z after Home, bed somewhere below but above 0.0.
509
+
510
+  //#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
511
+
512
+  #if ENABLED(MANUAL_BED_LEVELING)
513
+    #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
514
+  #endif  // MANUAL_BED_LEVELING
515
+
472 516
 #endif  // MESH_BED_LEVELING
473 517
 
474 518
 //===========================================================================
@@ -477,10 +521,9 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
477 521
 
478 522
 // @section bedlevel
479 523
 
480
-
481 524
 //#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
482 525
 //#define DEBUG_LEVELING_FEATURE
483
-//#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
526
+//#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
484 527
 
485 528
 #if ENABLED(AUTO_BED_LEVELING_FEATURE)
486 529
 
@@ -492,7 +535,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
492 535
   //   This mode is preferred because there are more measurements.
493 536
   //
494 537
   // - "3-point" mode
495
-  //   Probe 3 arbitrary points on the bed (that aren't colinear)
538
+  //   Probe 3 arbitrary points on the bed (that aren't collinear)
496 539
   //   You specify the XY coordinates of all 3 points.
497 540
 
498 541
   // Enable this to sample the bed in a grid (least squares solution).
@@ -508,35 +551,47 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
508 551
     #define FRONT_PROBE_BED_POSITION -DELTA_PROBABLE_RADIUS
509 552
     #define BACK_PROBE_BED_POSITION DELTA_PROBABLE_RADIUS
510 553
 
511
-    #define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
554
+    #define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
512 555
 
513 556
     // Non-linear bed leveling will be used.
514 557
     // Compensate by interpolating between the nearest four Z probe values for each point.
515 558
     // Useful for deltas where the print surface may appear like a bowl or dome shape.
516
-    // Works best with ACCURATE_BED_LEVELING_POINTS 5 or higher.
559
+    // Works best with AUTO_BED_LEVELING_GRID_POINTS 5 or higher.
517 560
     #define AUTO_BED_LEVELING_GRID_POINTS 9
518 561
 
519 562
   #else  // !AUTO_BED_LEVELING_GRID
520 563
 
521
-      // Arbitrary points to probe.
522
-      // A simple cross-product is used to estimate the plane of the bed.
523
-      #define ABL_PROBE_PT_1_X 15
524
-      #define ABL_PROBE_PT_1_Y 180
525
-      #define ABL_PROBE_PT_2_X 15
526
-      #define ABL_PROBE_PT_2_Y 20
527
-      #define ABL_PROBE_PT_3_X 170
528
-      #define ABL_PROBE_PT_3_Y 20
564
+    // Arbitrary points to probe.
565
+    // A simple cross-product is used to estimate the plane of the bed.
566
+    #define ABL_PROBE_PT_1_X 15
567
+    #define ABL_PROBE_PT_1_Y 180
568
+    #define ABL_PROBE_PT_2_X 15
569
+    #define ABL_PROBE_PT_2_Y 20
570
+    #define ABL_PROBE_PT_3_X 170
571
+    #define ABL_PROBE_PT_3_Y 20
529 572
 
530 573
   #endif // AUTO_BED_LEVELING_GRID
531 574
 
532
-  // Offsets to the Z probe relative to the nozzle tip.
575
+  // Z Probe to nozzle (X,Y) offset, relative to (0, 0).
533 576
   // X and Y offsets must be integers.
534
-  #define X_PROBE_OFFSET_FROM_EXTRUDER 0     // Z probe to nozzle X offset: -left  +right
535
-  #define Y_PROBE_OFFSET_FROM_EXTRUDER -10   // Z probe to nozzle Y offset: -front +behind
536
-  #define Z_PROBE_OFFSET_FROM_EXTRUDER -3.5  // Z probe to nozzle Z offset: -below (always!)
537
-
538
-  #define Z_RAISE_BEFORE_HOMING 15      // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
539
-                                        // Be sure you have this distance over your Z_MAX_POS in case.
577
+  //
578
+  // In the following example the X and Y offsets are both positive:
579
+  // #define X_PROBE_OFFSET_FROM_EXTRUDER 10
580
+  // #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
581
+  //
582
+  //    +-- BACK ---+
583
+  //    |           |
584
+  //  L |    (+) P  | R <-- probe (20,20)
585
+  //  E |           | I
586
+  //  F | (-) N (+) | G <-- nozzle (10,10)
587
+  //  T |           | H
588
+  //    |    (-)    | T
589
+  //    |           |
590
+  //    O-- FRONT --+
591
+  //  (0,0)
592
+  #define X_PROBE_OFFSET_FROM_EXTRUDER 0     // X offset: -left  [of the nozzle] +right
593
+  #define Y_PROBE_OFFSET_FROM_EXTRUDER -10   // Y offset: -front [of the nozzle] +behind
594
+  #define Z_PROBE_OFFSET_FROM_EXTRUDER -3.5  // Z offset: -below [the nozzle] (always negative!)
540 595
 
541 596
   #define XY_TRAVEL_SPEED 4000         // X and Y axis travel speed between probes, in mm/min.
542 597
 
@@ -544,13 +599,25 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
544 599
   #define Z_RAISE_BETWEEN_PROBINGS 5  // How much the Z axis will be raised when traveling from between next probing points
545 600
   #define Z_RAISE_AFTER_PROBING 50    // How much the Z axis will be raised after the last probing point.
546 601
 
547
-//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
548
-                                                                            // Useful to retract a deployable Z probe.
602
+  //#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
603
+                                                                             // Useful to retract a deployable Z probe.
604
+
605
+  // Probes are sensors/switches that need to be activated before they can be used
606
+  // and deactivated after the use.
607
+  // Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
608
+
609
+  // A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
610
+  // when the hardware endstops are active.
611
+  //#define FIX_MOUNTED_PROBE
612
+
613
+  // A Servo Probe can be defined in the servo section below.
614
+
615
+  // An Allen Key Probe is currently predefined only in the delta example configurations.
549 616
 
550
-  //#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
617
+  //#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
551 618
   //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
552 619
 
553
-  // Allen key retractable z-probe as seen on many Kossel delta printers - http://reprap.org/wiki/Kossel#Automatic_bed_leveling_probe
620
+  // Allen key retractable Z probe as seen on many Kossel delta printers - http://reprap.org/wiki/Kossel#Automatic_bed_leveling_probe
554 621
   // Deploys by touching z-axis belt. Retracts by pushing the probe down. Uses Z_MIN_PIN.
555 622
   #define Z_PROBE_ALLEN_KEY
556 623
 
@@ -635,10 +702,11 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
635 702
     //#define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE HOMING_FEEDRATE_XYZ
636 703
   #endif
637 704
 
638
-// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
639
-// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
705
+  // If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
706
+  // it is highly recommended you leave Z_SAFE_HOMING enabled!
640 707
 
641
-  #define Z_SAFE_HOMING   // This feature is meant to avoid Z homing with Z probe outside the bed area.
708
+  #define Z_SAFE_HOMING   // Use the z-min-probe for homing to z-min - not the z-min-endstop.
709
+                          // This feature is meant to avoid Z homing with Z probe outside the bed area.
642 710
                           // When defined, it will:
643 711
                           // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
644 712
                           // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
@@ -652,37 +720,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
652 720
 
653 721
   #endif
654 722
 
655
-  // Support for a dedicated Z probe endstop separate from the Z min endstop.
656
-  // If you would like to use both a Z probe and a Z min endstop together,
657
-  // uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
658
-  // If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
659
-  // Example: To park the head outside the bed area when homing with G28.
660
-  //
661
-  // WARNING:
662
-  // The Z min endstop will need to set properly as it would without a Z probe
663
-  // to prevent head crashes and premature stopping during a print.
664
-  //
665
-  // To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
666
-  // defined in the pins_XXXXX.h file for your control board.
667
-  // If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
668
-  // Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
669
-  // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
670
-  // in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
671
-  // otherwise connect to ground and D32 for normally closed configuration
672
-  // and 5V and D32 for normally open configurations.
673
-  // Normally closed configuration is advised and assumed.
674
-  // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
675
-  // Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
676
-  // Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
677
-  // D32 is currently selected in the RAMPS 1.3/1.4 pin file.
678
-  // All other boards will need changes to the respective pins_XXXXX.h file.
679
-  //
680
-  // WARNING:
681
-  // Setting the wrong pin may have unexpected and potentially disastrous outcomes.
682
-  // Use with caution and do your homework.
683
-  //
684
-  //#define Z_MIN_PROBE_ENDSTOP
685
-
686 723
 #endif // AUTO_BED_LEVELING_FEATURE
687 724
 
688 725
 
@@ -715,7 +752,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
715 752
 // delta speeds must be the same on xyz
716 753
 #define DEFAULT_AXIS_STEPS_PER_UNIT   {80, 80, 80, 760*1.1}  // default steps per unit for Kossel (GT2, 20 tooth)
717 754
 #define DEFAULT_MAX_FEEDRATE          {500, 500, 500, 25}    // (mm/sec)
718
-#define DEFAULT_MAX_ACCELERATION      {9000,9000,9000,10000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot.
755
+#define DEFAULT_MAX_ACCELERATION      {9000,9000,9000,10000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
719 756
 
720 757
 #define DEFAULT_ACCELERATION          3000    // X, Y, Z and E acceleration in mm/s^2 for printing moves
721 758
 #define DEFAULT_RETRACT_ACCELERATION  3000    // E acceleration in mm/s^2 for retracts
@@ -759,6 +796,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
759 796
 #endif
760 797
 
761 798
 //
799
+// Host Keepalive
800
+//
801
+// By default Marlin will send a busy status message to the host
802
+// every 2 seconds when it can't accept commands.
803
+//
804
+//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
805
+
806
+//
762 807
 // M100 Free Memory Watcher
763 808
 //
764 809
 //#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
@@ -778,13 +823,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
778 823
 // @section lcd
779 824
 
780 825
 // Define your display language below. Replace (en) with your language code and uncomment.
781
-// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
826
+// en, pl, fr, de, es, ru, bg, it, pt, pt_utf8, pt-br, pt-br_utf8, fi, an, nl, ca, eu, kana, kana_utf8, cn, cz, test
782 827
 // See also language.h
783 828
 #define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
784 829
 
785 830
 // Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
786 831
 // To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
787
-// See also documentation/LCDLanguageFont.md
832
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
788 833
   #define DISPLAY_CHARSET_HD44780_JAPAN        // this is the most common hardware
789 834
   //#define DISPLAY_CHARSET_HD44780_WESTERN
790 835
   //#define DISPLAY_CHARSET_HD44780_CYRILLIC
@@ -792,12 +837,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
792 837
 //#define ULTRA_LCD  //general LCD support, also 16x2
793 838
 //#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
794 839
 //#define SDSUPPORT // Enable SD Card Support in Hardware Console
795
-// Changed behaviour! If you need SDSUPPORT uncomment it!
796
-//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
797
-//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
840
+                    // Changed behaviour! If you need SDSUPPORT uncomment it!
841
+//#define SPI_SPEED SPI_HALF_SPEED // (also SPI_QUARTER_SPEED, SPI_EIGHTH_SPEED) Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
798 842
 //#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
799 843
 //#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
800 844
 //#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
845
+//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
801 846
 //#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
802 847
 //#define ULTIPANEL  //the UltiPanel as on Thingiverse
803 848
 //#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
@@ -814,13 +859,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
814 859
 
815 860
 // The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
816 861
 // http://panucatt.com
817
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
862
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
818 863
 //#define VIKI2
819 864
 //#define miniVIKI
820 865
 
821 866
 // This is a new controller currently under development.  https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
822 867
 //
823
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
868
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
824 869
 //#define ELB_FULL_GRAPHIC_CONTROLLER
825 870
 //#define SD_DETECT_INVERTED
826 871
 
@@ -835,7 +880,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
835 880
 // The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
836 881
 // http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
837 882
 //
838
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
883
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
839 884
 //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
840 885
 
841 886
 // The RepRapWorld REPRAPWORLD_KEYPAD v1.1
@@ -848,6 +893,10 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
848 893
 // REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
849 894
 //#define RA_CONTROL_PANEL
850 895
 
896
+// The MakerLab Mini Panel with graphic controller and SD support
897
+// http://reprap.org/wiki/Mini_panel
898
+//#define MINIPANEL
899
+
851 900
 // Delta calibration menu
852 901
 // uncomment to add three points calibration menu option.
853 902
 // See http://minow.blogspot.com/index.html#4918805519571907051
@@ -861,6 +910,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
861 910
 
862 911
 //#define LCD_I2C_SAINSMART_YWROBOT
863 912
 
913
+//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
914
+
864 915
 // PANELOLU2 LCD with status LEDs, separate encoder and click inputs
865 916
 //
866 917
 // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
@@ -874,7 +925,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
874 925
 //#define LCD_I2C_VIKI
875 926
 
876 927
 // SSD1306 OLED generic display support
877
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
928
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
878 929
 //#define U8GLIB_SSD1306
879 930
 
880 931
 // Shift register panels
@@ -886,7 +937,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
886 937
 
887 938
 // @section extras
888 939
 
889
-// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
940
+// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
890 941
 //#define FAST_PWM_FAN
891 942
 
892 943
 // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
@@ -968,19 +1019,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
968 1019
 // Uncomment below to enable
969 1020
 //#define FILAMENT_SENSOR
970 1021
 
971
-#define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
972
-#define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
973
-
974 1022
 #define DEFAULT_NOMINAL_FILAMENT_DIA 3.00  //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
975
-#define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
976
-#define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
977
-#define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
978 1023
 
979
-//defines used in the code
980
-#define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
1024
+#if ENABLED(FILAMENT_SENSOR)
1025
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
1026
+  #define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
1027
+
1028
+  #define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
1029
+  #define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
1030
+  #define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
981 1031
 
982
-//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
983
-//#define FILAMENT_LCD_DISPLAY
1032
+  #define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
1033
+
1034
+  //When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
1035
+  //#define FILAMENT_LCD_DISPLAY
1036
+#endif
984 1037
 
985 1038
 #include "Configuration_adv.h"
986 1039
 #include "thermistortables.h"

+ 83
- 58
Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h Näytä tiedosto

@@ -17,6 +17,20 @@
17 17
 /**
18 18
  * Thermal Protection parameters
19 19
  */
20
+  /**
21
+   * Thermal Protection protects your printer from damage and fire if a
22
+   * thermistor falls out or temperature sensors fail in any way.
23
+   *
24
+   * The issue: If a thermistor falls out or a temperature sensor fails,
25
+   * Marlin can no longer sense the actual temperature. Since a disconnected
26
+   * thermistor reads as a low temperature, the firmware will keep the heater on.
27
+   *
28
+   * The solution: Once the temperature reaches the target, start observing.
29
+   * If the temperature stays too far below the target (hysteresis) for too long (period),
30
+   * the firmware will halt the machine as a safety precaution.
31
+   *
32
+   * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
33
+   */
20 34
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
21 35
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
22 36
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
@@ -26,26 +40,24 @@
26 40
    * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
27 41
    * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
28 42
    * but only if the current temperature is far enough below the target for a reliable test.
43
+   *
44
+   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
45
+   * WATCH_TEMP_INCREASE should not be below 2.
29 46
    */
30 47
   #define WATCH_TEMP_PERIOD 16                // Seconds
31 48
   #define WATCH_TEMP_INCREASE 4               // Degrees Celsius
32 49
 #endif
33 50
 
51
+  /**
52
+   * Thermal Protection parameters for the bed
53
+   * are like the above for the hotends.
54
+   * WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
55
+   */
34 56
 #if ENABLED(THERMAL_PROTECTION_BED)
35 57
   #define THERMAL_PROTECTION_BED_PERIOD 20    // Seconds
36 58
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
37 59
 #endif
38 60
 
39
-/**
40
- * Automatic Temperature:
41
- * The hotend target temperature is calculated by all the buffered lines of gcode.
42
- * The maximum buffered steps/sec of the extruder motor is called "se".
43
- * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
44
- * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
45
- * mintemp and maxtemp. Turn this off by excuting M109 without F*
46
- * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
47
- * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
48
- */
49 61
 #if ENABLED(PIDTEMP)
50 62
   // this adds an experimental additional term to the heating power, proportional to the extrusion speed.
51 63
   // if Kc is chosen well, the additional required power due to increased melting should be compensated.
@@ -56,14 +68,16 @@
56 68
   #endif
57 69
 #endif
58 70
 
59
-
60
-//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
61
-//The maximum buffered steps/sec of the extruder motor are called "se".
62
-//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
63
-// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
64
-// you exit the value by any M109 without F*
65
-// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
66
-// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
71
+/**
72
+ * Automatic Temperature:
73
+ * The hotend target temperature is calculated by all the buffered lines of gcode.
74
+ * The maximum buffered steps/sec of the extruder motor is called "se".
75
+ * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
76
+ * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
77
+ * mintemp and maxtemp. Turn this off by executing M109 without F*
78
+ * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
79
+ * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
80
+ */
67 81
 #define AUTOTEMP
68 82
 #if ENABLED(AUTOTEMP)
69 83
   #define AUTOTEMP_OLDWEIGHT 0.98
@@ -240,7 +254,13 @@
240 254
 #define INVERT_E_STEP_PIN false
241 255
 
242 256
 // Default stepper release if idle. Set to 0 to deactivate.
257
+// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
258
+// Time can be set by M18 and M84.
243 259
 #define DEFAULT_STEPPER_DEACTIVE_TIME 60
260
+#define DISABLE_INACTIVE_X true
261
+#define DISABLE_INACTIVE_Y true
262
+#define DISABLE_INACTIVE_Z true  // set to false if the nozzle will fall down on your printed part when print has finished.
263
+#define DISABLE_INACTIVE_E true
244 264
 
245 265
 #define DEFAULT_MINIMUMFEEDRATE       0.0     // minimum feedrate
246 266
 #define DEFAULT_MINTRAVELFEEDRATE     0.0
@@ -277,6 +297,9 @@
277 297
 // Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
278 298
 #define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
279 299
 
300
+// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
301
+//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
302
+
280 303
 // uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
281 304
 //#define DIGIPOT_I2C
282 305
 // Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
@@ -350,17 +373,16 @@
350 373
   //#define USE_SMALL_INFOFONT
351 374
 #endif // DOGLCD
352 375
 
353
-
354 376
 // @section more
355 377
 
356 378
 // The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
357
-//#define USE_WATCHDOG
379
+#define USE_WATCHDOG
358 380
 
359 381
 #if ENABLED(USE_WATCHDOG)
360
-// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
361
-// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
362
-//  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
363
-//#define WATCHDOG_RESET_MANUAL
382
+  // If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
383
+  // The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
384
+  //  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
385
+  //#define WATCHDOG_RESET_MANUAL
364 386
 #endif
365 387
 
366 388
 // @section lcd
@@ -371,6 +393,7 @@
371 393
 //#define BABYSTEPPING
372 394
 #if ENABLED(BABYSTEPPING)
373 395
   #define BABYSTEP_XY  //not only z, but also XY in the menu. more clutter, more functions
396
+                       //not implemented for deltabots!
374 397
   #define BABYSTEP_INVERT_Z false  //true for inverse movements in Z
375 398
   #define BABYSTEP_MULTIPLICATOR 1 //faster movements
376 399
 #endif
@@ -389,7 +412,6 @@
389 412
 #if ENABLED(ADVANCE)
390 413
   #define EXTRUDER_ADVANCE_K .0
391 414
   #define D_FILAMENT 2.85
392
-  #define STEPS_MM_E 836
393 415
 #endif
394 416
 
395 417
 // @section extras
@@ -398,7 +420,7 @@
398 420
 #define MM_PER_ARC_SEGMENT 1
399 421
 #define N_ARC_CORRECTION 25
400 422
 
401
-const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
423
+const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
402 424
 
403 425
 // @section temperature
404 426
 
@@ -463,12 +485,15 @@ const unsigned int dropsegments=5; //everything with less than this number of st
463 485
     #define FILAMENTCHANGE_ZADD 10
464 486
     #define FILAMENTCHANGE_FIRSTRETRACT -2
465 487
     #define FILAMENTCHANGE_FINALRETRACT -100
488
+    #define AUTO_FILAMENT_CHANGE                //This extrude filament until you press the button on LCD
489
+    #define AUTO_FILAMENT_CHANGE_LENGTH 0.04    //Extrusion length on automatic extrusion loop
490
+    #define AUTO_FILAMENT_CHANGE_FEEDRATE 300   //Extrusion feedrate (mm/min) on automatic extrusion loop
466 491
   #endif
467 492
 #endif
468 493
 
469 494
 /******************************************************************************\
470 495
  * enable this section if you have TMC26X motor drivers.
471
- * you need to import the TMC26XStepper library into the arduino IDE for this
496
+ * you need to import the TMC26XStepper library into the Arduino IDE for this
472 497
  ******************************************************************************/
473 498
 
474 499
 // @section tmc
@@ -476,52 +501,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
476 501
 //#define HAVE_TMCDRIVER
477 502
 #if ENABLED(HAVE_TMCDRIVER)
478 503
 
479
-//#define X_IS_TMC
504
+  //#define X_IS_TMC
480 505
   #define X_MAX_CURRENT 1000  //in mA
481 506
   #define X_SENSE_RESISTOR 91 //in mOhms
482 507
   #define X_MICROSTEPS 16     //number of microsteps
483 508
 
484
-//#define X2_IS_TMC
509
+  //#define X2_IS_TMC
485 510
   #define X2_MAX_CURRENT 1000  //in mA
486 511
   #define X2_SENSE_RESISTOR 91 //in mOhms
487 512
   #define X2_MICROSTEPS 16     //number of microsteps
488 513
 
489
-//#define Y_IS_TMC
514
+  //#define Y_IS_TMC
490 515
   #define Y_MAX_CURRENT 1000  //in mA
491 516
   #define Y_SENSE_RESISTOR 91 //in mOhms
492 517
   #define Y_MICROSTEPS 16     //number of microsteps
493 518
 
494
-//#define Y2_IS_TMC
519
+  //#define Y2_IS_TMC
495 520
   #define Y2_MAX_CURRENT 1000  //in mA
496 521
   #define Y2_SENSE_RESISTOR 91 //in mOhms
497 522
   #define Y2_MICROSTEPS 16     //number of microsteps
498 523
 
499
-//#define Z_IS_TMC
524
+  //#define Z_IS_TMC
500 525
   #define Z_MAX_CURRENT 1000  //in mA
501 526
   #define Z_SENSE_RESISTOR 91 //in mOhms
502 527
   #define Z_MICROSTEPS 16     //number of microsteps
503 528
 
504
-//#define Z2_IS_TMC
529
+  //#define Z2_IS_TMC
505 530
   #define Z2_MAX_CURRENT 1000  //in mA
506 531
   #define Z2_SENSE_RESISTOR 91 //in mOhms
507 532
   #define Z2_MICROSTEPS 16     //number of microsteps
508 533
 
509
-//#define E0_IS_TMC
534
+  //#define E0_IS_TMC
510 535
   #define E0_MAX_CURRENT 1000  //in mA
511 536
   #define E0_SENSE_RESISTOR 91 //in mOhms
512 537
   #define E0_MICROSTEPS 16     //number of microsteps
513 538
 
514
-//#define E1_IS_TMC
539
+  //#define E1_IS_TMC
515 540
   #define E1_MAX_CURRENT 1000  //in mA
516 541
   #define E1_SENSE_RESISTOR 91 //in mOhms
517 542
   #define E1_MICROSTEPS 16     //number of microsteps
518 543
 
519
-//#define E2_IS_TMC
544
+  //#define E2_IS_TMC
520 545
   #define E2_MAX_CURRENT 1000  //in mA
521 546
   #define E2_SENSE_RESISTOR 91 //in mOhms
522 547
   #define E2_MICROSTEPS 16     //number of microsteps
523 548
 
524
-//#define E3_IS_TMC
549
+  //#define E3_IS_TMC
525 550
   #define E3_MAX_CURRENT 1000  //in mA
526 551
   #define E3_SENSE_RESISTOR 91 //in mOhms
527 552
   #define E3_MICROSTEPS 16     //number of microsteps
@@ -530,7 +555,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
530 555
 
531 556
 /******************************************************************************\
532 557
  * enable this section if you have L6470  motor drivers.
533
- * you need to import the L6470 library into the arduino IDE for this
558
+ * you need to import the L6470 library into the Arduino IDE for this
534 559
  ******************************************************************************/
535 560
 
536 561
 // @section l6470
@@ -538,63 +563,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
538 563
 //#define HAVE_L6470DRIVER
539 564
 #if ENABLED(HAVE_L6470DRIVER)
540 565
 
541
-//#define X_IS_L6470
566
+  //#define X_IS_L6470
542 567
   #define X_MICROSTEPS 16     //number of microsteps
543
-  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
568
+  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
544 569
   #define X_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
545 570
   #define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
546 571
 
547
-//#define X2_IS_L6470
572
+  //#define X2_IS_L6470
548 573
   #define X2_MICROSTEPS 16     //number of microsteps
549
-  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
574
+  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
550 575
   #define X2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
551 576
   #define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
552 577
 
553
-//#define Y_IS_L6470
578
+  //#define Y_IS_L6470
554 579
   #define Y_MICROSTEPS 16     //number of microsteps
555
-  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
580
+  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
556 581
   #define Y_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
557 582
   #define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
558 583
 
559
-//#define Y2_IS_L6470
584
+  //#define Y2_IS_L6470
560 585
   #define Y2_MICROSTEPS 16     //number of microsteps
561
-  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
586
+  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
562 587
   #define Y2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
563 588
   #define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
564 589
 
565
-//#define Z_IS_L6470
590
+  //#define Z_IS_L6470
566 591
   #define Z_MICROSTEPS 16     //number of microsteps
567
-  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
592
+  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
568 593
   #define Z_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
569 594
   #define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
570 595
 
571
-//#define Z2_IS_L6470
596
+  //#define Z2_IS_L6470
572 597
   #define Z2_MICROSTEPS 16     //number of microsteps
573
-  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
598
+  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
574 599
   #define Z2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
575 600
   #define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
576 601
 
577
-//#define E0_IS_L6470
602
+  //#define E0_IS_L6470
578 603
   #define E0_MICROSTEPS 16     //number of microsteps
579
-  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
604
+  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
580 605
   #define E0_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
581 606
   #define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
582 607
 
583
-//#define E1_IS_L6470
608
+  //#define E1_IS_L6470
584 609
   #define E1_MICROSTEPS 16     //number of microsteps
585
-  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
610
+  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
586 611
   #define E1_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
587 612
   #define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
588 613
 
589
-//#define E2_IS_L6470
614
+  //#define E2_IS_L6470
590 615
   #define E2_MICROSTEPS 16     //number of microsteps
591
-  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
616
+  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
592 617
   #define E2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
593 618
   #define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
594 619
 
595
-//#define E3_IS_L6470
620
+  //#define E3_IS_L6470
596 621
   #define E3_MICROSTEPS 16     //number of microsteps
597
-  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
622
+  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
598 623
   #define E3_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
599 624
   #define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
600 625
 

+ 163
- 109
Marlin/example_configurations/delta/kossel_pro/Configuration.h Näytä tiedosto

@@ -66,7 +66,7 @@ Here are some standard links for getting your machine calibrated:
66 66
 
67 67
 // This determines the communication speed of the printer
68 68
 // :[2400,9600,19200,38400,57600,115200,250000]
69
-#define BAUDRATE 250000
69
+#define BAUDRATE 115200
70 70
 
71 71
 // Enable the Bluetooth serial interface on AT90USB devices
72 72
 //#define BLUETOOTH
@@ -114,6 +114,7 @@ Here are some standard links for getting your machine calibrated:
114 114
 //--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
115 115
 //
116 116
 //// Temperature sensor settings:
117
+// -3 is thermocouple with MAX31855 (only for sensor 0)
117 118
 // -2 is thermocouple with MAX6675 (only for sensor 0)
118 119
 // -1 is thermocouple with AD595
119 120
 // 0 is not used
@@ -133,6 +134,7 @@ Here are some standard links for getting your machine calibrated:
133 134
 // 13 is 100k Hisens 3950  1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
134 135
 // 20 is the PT100 circuit found in the Ultimainboard V2.x
135 136
 // 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
137
+// 70 is the 100K thermistor found in the bq Hephestos 2
136 138
 //
137 139
 //    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
138 140
 //                          (but gives greater accuracy and more stable PID)
@@ -148,7 +150,7 @@ Here are some standard links for getting your machine calibrated:
148 150
 //     Use it for Testing or Development purposes. NEVER for production machine.
149 151
 //#define DUMMY_THERMISTOR_998_VALUE 25
150 152
 //#define DUMMY_THERMISTOR_999_VALUE 100
151
-// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
153
+// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-3': "Thermocouple + MAX31855 (only for sensor 0)", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
152 154
 #define TEMP_SENSOR_0 5
153 155
 #define TEMP_SENSOR_1 0
154 156
 #define TEMP_SENSOR_2 0
@@ -182,14 +184,9 @@ Here are some standard links for getting your machine calibrated:
182 184
 #define HEATER_3_MAXTEMP 275
183 185
 #define BED_MAXTEMP 150
184 186
 
185
-// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
186
-// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
187
-// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
188
-//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
189
-
190 187
 // If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
191
-//#define EXTRUDER_WATTS (12.0*12.0/6.7) //  P=I^2/R
192
-//#define BED_WATTS (12.0*12.0/1.1)      // P=I^2/R
188
+//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
189
+//#define BED_WATTS (12.0*12.0/1.1)      // P=U^2/R
193 190
 
194 191
 //===========================================================================
195 192
 //============================= PID Settings ================================
@@ -271,16 +268,15 @@ Here are some standard links for getting your machine calibrated:
271 268
 //===========================================================================
272 269
 
273 270
 /**
274
- * Thermal Runaway Protection protects your printer from damage and fire if a
271
+ * Thermal Protection protects your printer from damage and fire if a
275 272
  * thermistor falls out or temperature sensors fail in any way.
276 273
  *
277 274
  * The issue: If a thermistor falls out or a temperature sensor fails,
278 275
  * Marlin can no longer sense the actual temperature. Since a disconnected
279 276
  * thermistor reads as a low temperature, the firmware will keep the heater on.
280 277
  *
281
- * The solution: Once the temperature reaches the target, start observing.
282
- * If the temperature stays too far below the target (hysteresis) for too long,
283
- * the firmware will halt as a safety precaution.
278
+ * If you get "Thermal Runaway" or "Heating failed" errors the
279
+ * details can be tuned in Configuration_adv.h
284 280
  */
285 281
 
286 282
 #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
@@ -363,10 +359,52 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
363 359
 //#define DISABLE_MAX_ENDSTOPS
364 360
 //#define DISABLE_MIN_ENDSTOPS // Deltas only use min endstops for probing.
365 361
 
366
-// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
367
-// This only affects a Z probe endstop if you have separate Z min endstop as well and have
368
-// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
369
-// this has no effect.
362
+//===========================================================================
363
+//============================= Z Probe Options =============================
364
+//===========================================================================
365
+
366
+// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
367
+// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
368
+//
369
+// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
370
+//
371
+// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
372
+// Example: To park the head outside the bed area when homing with G28.
373
+//
374
+// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
375
+//
376
+// For a servo-based Z probe, you must set up servo support below, including
377
+// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
378
+//
379
+// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
380
+// - Use 5V for powered (usu. inductive) sensors.
381
+// - Otherwise connect:
382
+//   - normally-closed switches to GND and D32.
383
+//   - normally-open switches to 5V and D32.
384
+//
385
+// Normally-closed switches are advised and are the default.
386
+//
387
+// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
388
+// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
389
+// default pin for all RAMPS-based boards. Some other boards map differently.
390
+// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
391
+//
392
+// WARNING:
393
+// Setting the wrong pin may have unexpected and potentially disastrous consequences.
394
+// Use with caution and do your homework.
395
+//
396
+//#define Z_MIN_PROBE_ENDSTOP
397
+
398
+// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
399
+// The Z_MIN_PIN will then be used for both Z-homing and probing.
400
+#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
401
+
402
+// To use a probe you must enable one of the two options above!
403
+
404
+// This option disables the use of the Z_MIN_PROBE_PIN
405
+// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
406
+// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
407
+// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
370 408
 //#define DISABLE_Z_MIN_PROBE_ENDSTOP
371 409
 
372 410
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
@@ -376,11 +414,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
376 414
 #define Z_ENABLE_ON 0
377 415
 #define E_ENABLE_ON 0 // For all extruders
378 416
 
379
-// Disables axis when it's not being used.
417
+// Disables axis stepper immediately when it's not being used.
380 418
 // WARNING: When motors turn off there is a chance of losing position accuracy!
381 419
 #define DISABLE_X false
382 420
 #define DISABLE_Y false
383 421
 #define DISABLE_Z false
422
+// Warn on display about possibly reduced accuracy
423
+//#define DISABLE_REDUCED_ACCURACY_WARNING
384 424
 
385 425
 // @section extruder
386 426
 
@@ -403,6 +443,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
403 443
 #define INVERT_E3_DIR false
404 444
 
405 445
 // @section homing
446
+//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
447
+                                    // Be sure you have this distance over your Z_MAX_POS in case.
406 448
 
407 449
 // ENDSTOP SETTINGS:
408 450
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
@@ -438,24 +480,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
438 480
 #endif
439 481
 
440 482
 //===========================================================================
441
-//=========================== Manual Bed Leveling ===========================
483
+//============================ Mesh Bed Leveling ============================
442 484
 //===========================================================================
443 485
 
444
-//#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
445 486
 //#define MESH_BED_LEVELING    // Enable mesh bed leveling.
446 487
 
447
-#if ENABLED(MANUAL_BED_LEVELING)
448
-  #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
449
-#endif  // MANUAL_BED_LEVELING
450
-
451 488
 #if ENABLED(MESH_BED_LEVELING)
452 489
   #define MESH_MIN_X 10
453
-  #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
490
+  #define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
454 491
   #define MESH_MIN_Y 10
455
-  #define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
492
+  #define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
456 493
   #define MESH_NUM_X_POINTS 3  // Don't use more than 7 points per axis, implementation limited.
457 494
   #define MESH_NUM_Y_POINTS 3
458 495
   #define MESH_HOME_SEARCH_Z 4  // Z after Home, bed somewhere below but above 0.0.
496
+
497
+  //#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
498
+
499
+  #if ENABLED(MANUAL_BED_LEVELING)
500
+    #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
501
+  #endif  // MANUAL_BED_LEVELING
502
+
459 503
 #endif  // MESH_BED_LEVELING
460 504
 
461 505
 //===========================================================================
@@ -464,10 +508,9 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
464 508
 
465 509
 // @section bedlevel
466 510
 
467
-
468
-//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
511
+#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
469 512
 //#define DEBUG_LEVELING_FEATURE
470
-//#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
513
+//#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
471 514
 
472 515
 #if ENABLED(AUTO_BED_LEVELING_FEATURE)
473 516
 
@@ -479,7 +522,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
479 522
   //   This mode is preferred because there are more measurements.
480 523
   //
481 524
   // - "3-point" mode
482
-  //   Probe 3 arbitrary points on the bed (that aren't colinear)
525
+  //   Probe 3 arbitrary points on the bed (that aren't collinear)
483 526
   //   You specify the XY coordinates of all 3 points.
484 527
 
485 528
   // Enable this to sample the bed in a grid (least squares solution).
@@ -495,51 +538,75 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
495 538
     #define FRONT_PROBE_BED_POSITION -DELTA_PROBABLE_RADIUS
496 539
     #define BACK_PROBE_BED_POSITION DELTA_PROBABLE_RADIUS
497 540
 
498
-    #define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
541
+    #define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
499 542
 
500 543
     // Non-linear bed leveling will be used.
501 544
     // Compensate by interpolating between the nearest four Z probe values for each point.
502 545
     // Useful for deltas where the print surface may appear like a bowl or dome shape.
503
-    // Works best with ACCURATE_BED_LEVELING_POINTS 5 or higher.
546
+    // Works best with AUTO_BED_LEVELING_GRID_POINTS 5 or higher.
504 547
     #define AUTO_BED_LEVELING_GRID_POINTS 7
505 548
 
506 549
   #else  // !AUTO_BED_LEVELING_GRID
507 550
 
508
-      // Arbitrary points to probe.
509
-      // A simple cross-product is used to estimate the plane of the bed.
510
-      #define ABL_PROBE_PT_1_X 15
511
-      #define ABL_PROBE_PT_1_Y 180
512
-      #define ABL_PROBE_PT_2_X 15
513
-      #define ABL_PROBE_PT_2_Y 20
514
-      #define ABL_PROBE_PT_3_X 170
515
-      #define ABL_PROBE_PT_3_Y 20
551
+    // Arbitrary points to probe.
552
+    // A simple cross-product is used to estimate the plane of the bed.
553
+    #define ABL_PROBE_PT_1_X 15
554
+    #define ABL_PROBE_PT_1_Y 180
555
+    #define ABL_PROBE_PT_2_X 15
556
+    #define ABL_PROBE_PT_2_Y 20
557
+    #define ABL_PROBE_PT_3_X 170
558
+    #define ABL_PROBE_PT_3_Y 20
516 559
 
517 560
   #endif // AUTO_BED_LEVELING_GRID
518 561
 
519
-  // Offsets to the Z probe relative to the nozzle tip.
562
+  // Z Probe to nozzle (X,Y) offset, relative to (0, 0).
520 563
   // X and Y offsets must be integers.
564
+  //
565
+  // In the following example the X and Y offsets are both positive:
566
+  // #define X_PROBE_OFFSET_FROM_EXTRUDER 10
567
+  // #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
568
+  //
569
+  //    +-- BACK ---+
570
+  //    |           |
571
+  //  L |    (+) P  | R <-- probe (20,20)
572
+  //  E |           | I
573
+  //  F | (-) N (+) | G <-- nozzle (10,10)
574
+  //  T |           | H
575
+  //    |    (-)    | T
576
+  //    |           |
577
+  //    O-- FRONT --+
578
+  //  (0,0)
521 579
   #define X_PROBE_OFFSET_FROM_EXTRUDER -23 // KosselPro actual: -22.919
522 580
   #define Y_PROBE_OFFSET_FROM_EXTRUDER -6  // KosselPro actual: -6.304
523 581
   // Kossel Pro note: The correct value is likely -17.45 but I'd rather err on the side of
524 582
   // not giving someone a head crash. Use something like G29 Z-0.2 to adjust as needed.
525 583
   #define Z_PROBE_OFFSET_FROM_EXTRUDER -17.25  // Increase this if the first layer is too thin (remember: it's a negative number so increase means closer to zero).
526 584
 
527
-  #define Z_RAISE_BEFORE_HOMING 4       // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
528
-                                        // Be sure you have this distance over your Z_MAX_POS in case.
529
-
530 585
   #define XY_TRAVEL_SPEED 8000         // X and Y axis travel speed between probes, in mm/min.
531 586
 
532 587
   #define Z_RAISE_BEFORE_PROBING 100  // How much the Z axis will be raised before traveling to the first probing point.
533 588
   #define Z_RAISE_BETWEEN_PROBINGS 5  // How much the Z axis will be raised when traveling from between next probing points.
534 589
   #define Z_RAISE_AFTER_PROBING 15    // How much the Z axis will be raised after the last probing point.
535 590
 
536
-//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
537
-                                                                            // Useful to retract a deployable Z probe.
591
+  //#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
592
+                                                                             // Useful to retract a deployable Z probe.
593
+
594
+  // Probes are sensors/switches that need to be activated before they can be used
595
+  // and deactivated after the use.
596
+  // Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
597
+
598
+  // A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
599
+  // when the hardware endstops are active.
600
+  //#define FIX_MOUNTED_PROBE
601
+
602
+  // A Servo Probe can be defined in the servo section below.
603
+
604
+  // An Allen Key Probe is currently predefined only in the delta example configurations.
538 605
 
539
-  //#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
606
+  //#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
540 607
   //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
541 608
 
542
-  // Allen key retractable z-probe as seen on many Kossel delta printers - http://reprap.org/wiki/Kossel#Automatic_bed_leveling_probe
609
+  // Allen key retractable Z probe as seen on many Kossel delta printers - http://reprap.org/wiki/Kossel#Automatic_bed_leveling_probe
543 610
   // Deploys by touching z-axis belt. Retracts by pushing the probe down. Uses Z_MIN_PIN.
544 611
   #define Z_PROBE_ALLEN_KEY
545 612
 
@@ -599,20 +666,20 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
599 666
     #define Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE HOMING_FEEDRATE_XYZ
600 667
     #define Z_PROBE_ALLEN_KEY_DEPLOY_2_X -110.00 // Move outward to position deploy pin to the left of the arm
601 668
     #define Z_PROBE_ALLEN_KEY_DEPLOY_2_Y -125.00
602
-    #define Z_PROBE_ALLEN_KEY_DEPLOY_2_Z 100.0
669
+    #define Z_PROBE_ALLEN_KEY_DEPLOY_2_Z Z_PROBE_ALLEN_KEY_DEPLOY_1_Z
603 670
     #define Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE HOMING_FEEDRATE_XYZ
604 671
     #define Z_PROBE_ALLEN_KEY_DEPLOY_3_X 45.00 // Move right to trigger deploy pin
605 672
     #define Z_PROBE_ALLEN_KEY_DEPLOY_3_Y -125.00
606
-    #define Z_PROBE_ALLEN_KEY_DEPLOY_3_Z 100.0
673
+    #define Z_PROBE_ALLEN_KEY_DEPLOY_3_Z Z_PROBE_ALLEN_KEY_DEPLOY_2_Z
607 674
     #define Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE (HOMING_FEEDRATE_XYZ/2)
608 675
 
609 676
     #define Z_PROBE_ALLEN_KEY_STOW_1_X 36.00 // Line up with bed retaining clip
610
-    #define Z_PROBE_ALLEN_KEY_STOW_1_Y -122.00
677
+    #define Z_PROBE_ALLEN_KEY_STOW_1_Y -125.00
611 678
     #define Z_PROBE_ALLEN_KEY_STOW_1_Z 75.0
612 679
     #define Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE HOMING_FEEDRATE_XYZ
613
-    #define Z_PROBE_ALLEN_KEY_STOW_2_X 36.00 // move down to retract probe
614
-    #define Z_PROBE_ALLEN_KEY_STOW_2_Y -122.00
615
-    #define Z_PROBE_ALLEN_KEY_STOW_2_Z 25.0
680
+    #define Z_PROBE_ALLEN_KEY_STOW_2_X Z_PROBE_ALLEN_KEY_STOW_1_X // move down to retract probe
681
+    #define Z_PROBE_ALLEN_KEY_STOW_2_Y Z_PROBE_ALLEN_KEY_STOW_1_Y
682
+    #define Z_PROBE_ALLEN_KEY_STOW_2_Z 0.0
616 683
     #define Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE (HOMING_FEEDRATE_XYZ/2)
617 684
     #define Z_PROBE_ALLEN_KEY_STOW_3_X 0.0  // return to 0,0,100
618 685
     #define Z_PROBE_ALLEN_KEY_STOW_3_Y 0.0
@@ -620,10 +687,11 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
620 687
     #define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE HOMING_FEEDRATE_XYZ
621 688
   #endif
622 689
 
623
-// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
624
-// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
690
+  // If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
691
+  // it is highly recommended you leave Z_SAFE_HOMING enabled!
625 692
 
626
-  #define Z_SAFE_HOMING   // This feature is meant to avoid Z homing with Z probe outside the bed area.
693
+  #define Z_SAFE_HOMING   // Use the z-min-probe for homing to z-min - not the z-min-endstop.
694
+                          // This feature is meant to avoid Z homing with Z probe outside the bed area.
627 695
                           // When defined, it will:
628 696
                           // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
629 697
                           // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
@@ -637,37 +705,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
637 705
 
638 706
   #endif
639 707
 
640
-  // Support for a dedicated Z probe endstop separate from the Z min endstop.
641
-  // If you would like to use both a Z probe and a Z min endstop together,
642
-  // uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
643
-  // If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
644
-  // Example: To park the head outside the bed area when homing with G28.
645
-  //
646
-  // WARNING:
647
-  // The Z min endstop will need to set properly as it would without a Z probe
648
-  // to prevent head crashes and premature stopping during a print.
649
-  //
650
-  // To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
651
-  // defined in the pins_XXXXX.h file for your control board.
652
-  // If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
653
-  // Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
654
-  // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
655
-  // in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
656
-  // otherwise connect to ground and D32 for normally closed configuration
657
-  // and 5V and D32 for normally open configurations.
658
-  // Normally closed configuration is advised and assumed.
659
-  // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
660
-  // Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
661
-  // Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
662
-  // D32 is currently selected in the RAMPS 1.3/1.4 pin file.
663
-  // All other boards will need changes to the respective pins_XXXXX.h file.
664
-  //
665
-  // WARNING:
666
-  // Setting the wrong pin may have unexpected and potentially disastrous outcomes.
667
-  // Use with caution and do your homework.
668
-  //
669
-  //#define Z_MIN_PROBE_ENDSTOP
670
-
671 708
 #endif // AUTO_BED_LEVELING_FEATURE
672 709
 
673 710
 
@@ -700,13 +737,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
700 737
 #define XYZ_MICROSTEPS 32
701 738
 #define XYZ_BELT_PITCH 2
702 739
 #define XYZ_PULLEY_TEETH 20
703
-#define XYZ_STEPS (XYZ_FULL_STEPS_PER_ROTATION * XYZ_MICROSTEPS / double(XYZ_BELT_PITCH) / double(XYZ_PULLEY_TEETH))
740
+#define XYZ_STEPS ((XYZ_FULL_STEPS_PER_ROTATION) * (XYZ_MICROSTEPS) / double(XYZ_BELT_PITCH) / double(XYZ_PULLEY_TEETH))
704 741
 
705 742
 // default settings
706 743
 // delta speeds must be the same on xyz
707 744
 #define DEFAULT_AXIS_STEPS_PER_UNIT   {XYZ_STEPS, XYZ_STEPS, XYZ_STEPS, 184.8}
708 745
 #define DEFAULT_MAX_FEEDRATE          {200, 200, 200, 200}    // (mm/sec)
709
-#define DEFAULT_MAX_ACCELERATION      {9000,9000,9000,9000}    // X, Y, Z, E maximum start speed for accelerated moves.
746
+#define DEFAULT_MAX_ACCELERATION      {9000,9000,9000,9000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
710 747
 
711 748
 #define DEFAULT_ACCELERATION          3000    // X, Y, Z and E acceleration in mm/s^2 for printing moves
712 749
 #define DEFAULT_RETRACT_ACCELERATION  3000    // E acceleration in mm/s^2 for retracts
@@ -750,6 +787,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
750 787
 #endif
751 788
 
752 789
 //
790
+// Host Keepalive
791
+//
792
+// By default Marlin will send a busy status message to the host
793
+// every 2 seconds when it can't accept commands.
794
+//
795
+//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
796
+
797
+//
753 798
 // M100 Free Memory Watcher
754 799
 //
755 800
 //#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
@@ -769,13 +814,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
769 814
 // @section lcd
770 815
 
771 816
 // Define your display language below. Replace (en) with your language code and uncomment.
772
-// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
817
+// en, pl, fr, de, es, ru, bg, it, pt, pt_utf8, pt-br, pt-br_utf8, fi, an, nl, ca, eu, kana, kana_utf8, cn, cz, test
773 818
 // See also language.h
774 819
 #define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
775 820
 
776 821
 // Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
777 822
 // To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
778
-// See also documentation/LCDLanguageFont.md
823
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
779 824
   #define DISPLAY_CHARSET_HD44780_JAPAN        // this is the most common hardware
780 825
   //#define DISPLAY_CHARSET_HD44780_WESTERN
781 826
   //#define DISPLAY_CHARSET_HD44780_CYRILLIC
@@ -783,11 +828,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
783 828
 //#define ULTRA_LCD  //general LCD support, also 16x2
784 829
 //#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
785 830
 #define SDSUPPORT // Enable SD Card Support in Hardware Console
786
-//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
787
-//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
831
+                  // Changed behaviour! If you need SDSUPPORT uncomment it!
832
+//#define SPI_SPEED SPI_HALF_SPEED // (also SPI_QUARTER_SPEED, SPI_EIGHTH_SPEED) Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
788 833
 //#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
789 834
 //#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
790 835
 //#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
836
+//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
791 837
 //#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
792 838
 //#define ULTIPANEL  //the UltiPanel as on Thingiverse
793 839
 //#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
@@ -804,13 +850,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
804 850
 
805 851
 // The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
806 852
 // http://panucatt.com
807
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
853
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
808 854
 //#define VIKI2
809 855
 //#define miniVIKI
810 856
 
811 857
 // This is a new controller currently under development.  https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
812 858
 //
813
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
859
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
814 860
 //#define ELB_FULL_GRAPHIC_CONTROLLER
815 861
 //#define SD_DETECT_INVERTED
816 862
 
@@ -825,7 +871,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
825 871
 // The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
826 872
 // http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
827 873
 //
828
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
874
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
829 875
 //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
830 876
 
831 877
 // The RepRapWorld REPRAPWORLD_KEYPAD v1.1
@@ -838,6 +884,10 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
838 884
 // REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
839 885
 //#define RA_CONTROL_PANEL
840 886
 
887
+// The MakerLab Mini Panel with graphic controller and SD support
888
+// http://reprap.org/wiki/Mini_panel
889
+//#define MINIPANEL
890
+
841 891
 // Delta calibration menu
842 892
 // uncomment to add three points calibration menu option.
843 893
 // See http://minow.blogspot.com/index.html#4918805519571907051
@@ -851,6 +901,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
851 901
 
852 902
 //#define LCD_I2C_SAINSMART_YWROBOT
853 903
 
904
+//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
905
+
854 906
 // PANELOLU2 LCD with status LEDs, separate encoder and click inputs
855 907
 //
856 908
 // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
@@ -864,7 +916,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
864 916
 //#define LCD_I2C_VIKI
865 917
 
866 918
 // SSD1306 OLED generic display support
867
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
919
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
868 920
 //#define U8GLIB_SSD1306
869 921
 
870 922
 // Shift register panels
@@ -876,7 +928,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
876 928
 
877 929
 // @section extras
878 930
 
879
-// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
931
+// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
880 932
 //#define FAST_PWM_FAN
881 933
 
882 934
 // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
@@ -958,19 +1010,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
958 1010
 // Uncomment below to enable
959 1011
 //#define FILAMENT_SENSOR
960 1012
 
961
-#define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
962
-#define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
963
-
964 1013
 #define DEFAULT_NOMINAL_FILAMENT_DIA 3.00  //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
965
-#define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
966
-#define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
967
-#define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
968 1014
 
969
-//defines used in the code
970
-#define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
1015
+#if ENABLED(FILAMENT_SENSOR)
1016
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
1017
+  #define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
1018
+
1019
+  #define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
1020
+  #define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
1021
+  #define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
971 1022
 
972
-//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
973
-//#define FILAMENT_LCD_DISPLAY
1023
+  #define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
1024
+
1025
+  //When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
1026
+  //#define FILAMENT_LCD_DISPLAY
1027
+#endif
974 1028
 
975 1029
 #include "Configuration_adv.h"
976 1030
 #include "thermistortables.h"

+ 83
- 58
Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h Näytä tiedosto

@@ -21,6 +21,20 @@
21 21
 /**
22 22
  * Thermal Protection parameters
23 23
  */
24
+  /**
25
+   * Thermal Protection protects your printer from damage and fire if a
26
+   * thermistor falls out or temperature sensors fail in any way.
27
+   *
28
+   * The issue: If a thermistor falls out or a temperature sensor fails,
29
+   * Marlin can no longer sense the actual temperature. Since a disconnected
30
+   * thermistor reads as a low temperature, the firmware will keep the heater on.
31
+   *
32
+   * The solution: Once the temperature reaches the target, start observing.
33
+   * If the temperature stays too far below the target (hysteresis) for too long (period),
34
+   * the firmware will halt the machine as a safety precaution.
35
+   *
36
+   * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
37
+   */
24 38
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
25 39
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
26 40
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
@@ -30,26 +44,24 @@
30 44
    * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
31 45
    * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
32 46
    * but only if the current temperature is far enough below the target for a reliable test.
47
+   *
48
+   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
49
+   * WATCH_TEMP_INCREASE should not be below 2.
33 50
    */
34 51
   #define WATCH_TEMP_PERIOD 16                // Seconds
35 52
   #define WATCH_TEMP_INCREASE 4               // Degrees Celsius
36 53
 #endif
37 54
 
55
+  /**
56
+   * Thermal Protection parameters for the bed
57
+   * are like the above for the hotends.
58
+   * WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
59
+   */
38 60
 #if ENABLED(THERMAL_PROTECTION_BED)
39 61
   #define THERMAL_PROTECTION_BED_PERIOD 20    // Seconds
40 62
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
41 63
 #endif
42 64
 
43
-/**
44
- * Automatic Temperature:
45
- * The hotend target temperature is calculated by all the buffered lines of gcode.
46
- * The maximum buffered steps/sec of the extruder motor is called "se".
47
- * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
48
- * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
49
- * mintemp and maxtemp. Turn this off by excuting M109 without F*
50
- * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
51
- * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
52
- */
53 65
 #if ENABLED(PIDTEMP)
54 66
   // this adds an experimental additional term to the heating power, proportional to the extrusion speed.
55 67
   // if Kc is chosen well, the additional required power due to increased melting should be compensated.
@@ -60,14 +72,16 @@
60 72
   #endif
61 73
 #endif
62 74
 
63
-
64
-//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
65
-//The maximum buffered steps/sec of the extruder motor are called "se".
66
-//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
67
-// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
68
-// you exit the value by any M109 without F*
69
-// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
70
-// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
75
+/**
76
+ * Automatic Temperature:
77
+ * The hotend target temperature is calculated by all the buffered lines of gcode.
78
+ * The maximum buffered steps/sec of the extruder motor is called "se".
79
+ * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
80
+ * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
81
+ * mintemp and maxtemp. Turn this off by executing M109 without F*
82
+ * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
83
+ * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
84
+ */
71 85
 #define AUTOTEMP
72 86
 #if ENABLED(AUTOTEMP)
73 87
   #define AUTOTEMP_OLDWEIGHT 0.98
@@ -244,7 +258,13 @@
244 258
 #define INVERT_E_STEP_PIN false
245 259
 
246 260
 // Default stepper release if idle. Set to 0 to deactivate.
261
+// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
262
+// Time can be set by M18 and M84.
247 263
 #define DEFAULT_STEPPER_DEACTIVE_TIME 60
264
+#define DISABLE_INACTIVE_X true
265
+#define DISABLE_INACTIVE_Y true
266
+#define DISABLE_INACTIVE_Z true  // set to false if the nozzle will fall down on your printed part when print has finished.
267
+#define DISABLE_INACTIVE_E true
248 268
 
249 269
 #define DEFAULT_MINIMUMFEEDRATE       0.0     // minimum feedrate
250 270
 #define DEFAULT_MINTRAVELFEEDRATE     0.0
@@ -281,6 +301,9 @@
281 301
 // Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
282 302
 #define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
283 303
 
304
+// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
305
+//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
306
+
284 307
 // uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
285 308
 //#define DIGIPOT_I2C
286 309
 // Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
@@ -354,17 +377,16 @@
354 377
   //#define USE_SMALL_INFOFONT
355 378
 #endif // DOGLCD
356 379
 
357
-
358 380
 // @section more
359 381
 
360 382
 // The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
361
-//#define USE_WATCHDOG
383
+#define USE_WATCHDOG
362 384
 
363 385
 #if ENABLED(USE_WATCHDOG)
364
-// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
365
-// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
366
-//  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
367
-//#define WATCHDOG_RESET_MANUAL
386
+  // If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
387
+  // The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
388
+  //  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
389
+  //#define WATCHDOG_RESET_MANUAL
368 390
 #endif
369 391
 
370 392
 // @section lcd
@@ -375,6 +397,7 @@
375 397
 //#define BABYSTEPPING
376 398
 #if ENABLED(BABYSTEPPING)
377 399
   #define BABYSTEP_XY  //not only z, but also XY in the menu. more clutter, more functions
400
+                       //not implemented for deltabots!
378 401
   #define BABYSTEP_INVERT_Z false  //true for inverse movements in Z
379 402
   #define BABYSTEP_MULTIPLICATOR 1 //faster movements
380 403
 #endif
@@ -393,7 +416,6 @@
393 416
 #if ENABLED(ADVANCE)
394 417
   #define EXTRUDER_ADVANCE_K .0
395 418
   #define D_FILAMENT 2.85
396
-  #define STEPS_MM_E 836
397 419
 #endif
398 420
 
399 421
 // @section extras
@@ -402,7 +424,7 @@
402 424
 #define MM_PER_ARC_SEGMENT 1
403 425
 #define N_ARC_CORRECTION 25
404 426
 
405
-const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
427
+const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
406 428
 
407 429
 // @section temperature
408 430
 
@@ -467,12 +489,15 @@ const unsigned int dropsegments=5; //everything with less than this number of st
467 489
     #define FILAMENTCHANGE_ZADD 10
468 490
     #define FILAMENTCHANGE_FIRSTRETRACT -2
469 491
     #define FILAMENTCHANGE_FINALRETRACT -100
492
+    #define AUTO_FILAMENT_CHANGE                //This extrude filament until you press the button on LCD
493
+    #define AUTO_FILAMENT_CHANGE_LENGTH 0.04    //Extrusion length on automatic extrusion loop
494
+    #define AUTO_FILAMENT_CHANGE_FEEDRATE 300   //Extrusion feedrate (mm/min) on automatic extrusion loop
470 495
   #endif
471 496
 #endif
472 497
 
473 498
 /******************************************************************************\
474 499
  * enable this section if you have TMC26X motor drivers.
475
- * you need to import the TMC26XStepper library into the arduino IDE for this
500
+ * you need to import the TMC26XStepper library into the Arduino IDE for this
476 501
  ******************************************************************************/
477 502
 
478 503
 // @section tmc
@@ -480,52 +505,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
480 505
 //#define HAVE_TMCDRIVER
481 506
 #if ENABLED(HAVE_TMCDRIVER)
482 507
 
483
-//#define X_IS_TMC
508
+  //#define X_IS_TMC
484 509
   #define X_MAX_CURRENT 1000  //in mA
485 510
   #define X_SENSE_RESISTOR 91 //in mOhms
486 511
   #define X_MICROSTEPS 16     //number of microsteps
487 512
 
488
-//#define X2_IS_TMC
513
+  //#define X2_IS_TMC
489 514
   #define X2_MAX_CURRENT 1000  //in mA
490 515
   #define X2_SENSE_RESISTOR 91 //in mOhms
491 516
   #define X2_MICROSTEPS 16     //number of microsteps
492 517
 
493
-//#define Y_IS_TMC
518
+  //#define Y_IS_TMC
494 519
   #define Y_MAX_CURRENT 1000  //in mA
495 520
   #define Y_SENSE_RESISTOR 91 //in mOhms
496 521
   #define Y_MICROSTEPS 16     //number of microsteps
497 522
 
498
-//#define Y2_IS_TMC
523
+  //#define Y2_IS_TMC
499 524
   #define Y2_MAX_CURRENT 1000  //in mA
500 525
   #define Y2_SENSE_RESISTOR 91 //in mOhms
501 526
   #define Y2_MICROSTEPS 16     //number of microsteps
502 527
 
503
-//#define Z_IS_TMC
528
+  //#define Z_IS_TMC
504 529
   #define Z_MAX_CURRENT 1000  //in mA
505 530
   #define Z_SENSE_RESISTOR 91 //in mOhms
506 531
   #define Z_MICROSTEPS 16     //number of microsteps
507 532
 
508
-//#define Z2_IS_TMC
533
+  //#define Z2_IS_TMC
509 534
   #define Z2_MAX_CURRENT 1000  //in mA
510 535
   #define Z2_SENSE_RESISTOR 91 //in mOhms
511 536
   #define Z2_MICROSTEPS 16     //number of microsteps
512 537
 
513
-//#define E0_IS_TMC
538
+  //#define E0_IS_TMC
514 539
   #define E0_MAX_CURRENT 1000  //in mA
515 540
   #define E0_SENSE_RESISTOR 91 //in mOhms
516 541
   #define E0_MICROSTEPS 16     //number of microsteps
517 542
 
518
-//#define E1_IS_TMC
543
+  //#define E1_IS_TMC
519 544
   #define E1_MAX_CURRENT 1000  //in mA
520 545
   #define E1_SENSE_RESISTOR 91 //in mOhms
521 546
   #define E1_MICROSTEPS 16     //number of microsteps
522 547
 
523
-//#define E2_IS_TMC
548
+  //#define E2_IS_TMC
524 549
   #define E2_MAX_CURRENT 1000  //in mA
525 550
   #define E2_SENSE_RESISTOR 91 //in mOhms
526 551
   #define E2_MICROSTEPS 16     //number of microsteps
527 552
 
528
-//#define E3_IS_TMC
553
+  //#define E3_IS_TMC
529 554
   #define E3_MAX_CURRENT 1000  //in mA
530 555
   #define E3_SENSE_RESISTOR 91 //in mOhms
531 556
   #define E3_MICROSTEPS 16     //number of microsteps
@@ -534,7 +559,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
534 559
 
535 560
 /******************************************************************************\
536 561
  * enable this section if you have L6470  motor drivers.
537
- * you need to import the L6470 library into the arduino IDE for this
562
+ * you need to import the L6470 library into the Arduino IDE for this
538 563
  ******************************************************************************/
539 564
 
540 565
 // @section l6470
@@ -542,63 +567,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
542 567
 //#define HAVE_L6470DRIVER
543 568
 #if ENABLED(HAVE_L6470DRIVER)
544 569
 
545
-//#define X_IS_L6470
570
+  //#define X_IS_L6470
546 571
   #define X_MICROSTEPS 16     //number of microsteps
547
-  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
572
+  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
548 573
   #define X_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
549 574
   #define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
550 575
 
551
-//#define X2_IS_L6470
576
+  //#define X2_IS_L6470
552 577
   #define X2_MICROSTEPS 16     //number of microsteps
553
-  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
578
+  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
554 579
   #define X2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
555 580
   #define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
556 581
 
557
-//#define Y_IS_L6470
582
+  //#define Y_IS_L6470
558 583
   #define Y_MICROSTEPS 16     //number of microsteps
559
-  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
584
+  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
560 585
   #define Y_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
561 586
   #define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
562 587
 
563
-//#define Y2_IS_L6470
588
+  //#define Y2_IS_L6470
564 589
   #define Y2_MICROSTEPS 16     //number of microsteps
565
-  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
590
+  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
566 591
   #define Y2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
567 592
   #define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
568 593
 
569
-//#define Z_IS_L6470
594
+  //#define Z_IS_L6470
570 595
   #define Z_MICROSTEPS 16     //number of microsteps
571
-  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
596
+  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
572 597
   #define Z_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
573 598
   #define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
574 599
 
575
-//#define Z2_IS_L6470
600
+  //#define Z2_IS_L6470
576 601
   #define Z2_MICROSTEPS 16     //number of microsteps
577
-  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
602
+  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
578 603
   #define Z2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
579 604
   #define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
580 605
 
581
-//#define E0_IS_L6470
606
+  //#define E0_IS_L6470
582 607
   #define E0_MICROSTEPS 16     //number of microsteps
583
-  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
608
+  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
584 609
   #define E0_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
585 610
   #define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
586 611
 
587
-//#define E1_IS_L6470
612
+  //#define E1_IS_L6470
588 613
   #define E1_MICROSTEPS 16     //number of microsteps
589
-  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
614
+  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
590 615
   #define E1_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
591 616
   #define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
592 617
 
593
-//#define E2_IS_L6470
618
+  //#define E2_IS_L6470
594 619
   #define E2_MICROSTEPS 16     //number of microsteps
595
-  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
620
+  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
596 621
   #define E2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
597 622
   #define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
598 623
 
599
-//#define E3_IS_L6470
624
+  //#define E3_IS_L6470
600 625
   #define E3_MICROSTEPS 16     //number of microsteps
601
-  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
626
+  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
602 627
   #define E3_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
603 628
   #define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
604 629
 

+ 944
- 0
Marlin/example_configurations/delta/kossel_xl/Configuration.h Näytä tiedosto

@@ -0,0 +1,944 @@
1
+#ifndef CONFIGURATION_H
2
+#define CONFIGURATION_H
3
+
4
+#include "boards.h"
5
+#include "macros.h"
6
+
7
+//===========================================================================
8
+//============================= Getting Started =============================
9
+//===========================================================================
10
+/*
11
+Here are some standard links for getting your machine calibrated:
12
+ * http://reprap.org/wiki/Calibration
13
+ * http://youtu.be/wAL9d7FgInk
14
+ * http://calculator.josefprusa.cz
15
+ * http://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide
16
+ * http://www.thingiverse.com/thing:5573
17
+ * https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
18
+ * http://www.thingiverse.com/thing:298812
19
+*/
20
+
21
+// This configuration file contains the basic settings.
22
+// Advanced settings can be found in Configuration_adv.h
23
+// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
24
+
25
+//===========================================================================
26
+//============================= DELTA Printer ===============================
27
+//===========================================================================
28
+// For a Delta printer replace the configuration files with the files in the
29
+// example_configurations/delta directory.
30
+//
31
+
32
+#define DELTA
33
+#if ENABLED(DELTA)
34
+
35
+  // Make delta curves from many straight lines (linear interpolation).
36
+  // This is a trade-off between visible corners (not enough segments)
37
+  // and processor overload (too many expensive sqrt calls).
38
+  #define DELTA_SEGMENTS_PER_SECOND 160
39
+
40
+  // NOTE NB all values for DELTA_* values MUST be floating point, so always have a decimal point in them
41
+
42
+  // Center-to-center distance of the holes in the diagonal push rods.
43
+  #define DELTA_DIAGONAL_ROD 317.3 + 2.5 // mm
44
+
45
+  // Horizontal offset from middle of printer to smooth rod center.
46
+  #define DELTA_SMOOTH_ROD_OFFSET 220.1 // mm
47
+
48
+  // Horizontal offset of the universal joints on the end effector.
49
+  #define DELTA_EFFECTOR_OFFSET 24.0 // mm
50
+
51
+  // Horizontal offset of the universal joints on the carriages.
52
+  #define DELTA_CARRIAGE_OFFSET 22.0 // mm
53
+
54
+  // Horizontal distance bridged by diagonal push rods when effector is centered.
55
+  #define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET-DELTA_EFFECTOR_OFFSET-DELTA_CARRIAGE_OFFSET + 1)
56
+
57
+  // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers).
58
+  #define DELTA_PRINTABLE_RADIUS 140.0
59
+
60
+#endif
61
+
62
+// @section info
63
+
64
+#if ENABLED(USE_AUTOMATIC_VERSIONING)
65
+  #include "_Version.h"
66
+#else
67
+  #include "Default_Version.h"
68
+#endif
69
+
70
+// User-specified version info of this build to display in [Pronterface, etc] terminal window during
71
+// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
72
+// build by the user have been successfully uploaded into firmware.
73
+#define STRING_CONFIG_H_AUTHOR "(oxivanisher)" // Who made the changes.
74
+#define SHOW_BOOTSCREEN
75
+#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
76
+#define STRING_SPLASH_LINE2 STRING_DISTRIBUTION_DATE // will be shown during bootup in line 2
77
+
78
+// @section machine
79
+
80
+// SERIAL_PORT selects which serial port should be used for communication with the host.
81
+// This allows the connection of wireless adapters (for instance) to non-default port pins.
82
+// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
83
+// :[0,1,2,3,4,5,6,7]
84
+#define SERIAL_PORT 0
85
+
86
+// This determines the communication speed of the printer
87
+// :[2400,9600,19200,38400,57600,115200,250000]
88
+#define BAUDRATE 250000
89
+
90
+// Enable the Bluetooth serial interface on AT90USB devices
91
+//#define BLUETOOTH
92
+
93
+// The following define selects which electronics board you have.
94
+// Please choose the name from boards.h that matches your setup
95
+#ifndef MOTHERBOARD
96
+  #define MOTHERBOARD BOARD_RAMPS_14_EFB
97
+#endif
98
+
99
+// Optional custom name for your RepStrap or other custom machine
100
+// Displayed in the LCD "Ready" message
101
+#define CUSTOM_MACHINE_NAME "Kossel k800XL"
102
+
103
+// Define this to set a unique identifier for this printer, (Used by some programs to differentiate between machines)
104
+// You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4)
105
+//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
106
+
107
+// This defines the number of extruders
108
+// :[1,2,3,4]
109
+#define EXTRUDERS 1
110
+
111
+// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
112
+// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder).
113
+// For the other hotends it is their distance from the extruder 0 hotend.
114
+//#define EXTRUDER_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
115
+//#define EXTRUDER_OFFSET_Y {0.0, 5.00}  // (in mm) for each extruder, offset of the hotend on the Y axis
116
+
117
+//// The following define selects which power supply you have. Please choose the one that matches your setup
118
+// 1 = ATX
119
+// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
120
+// :{1:'ATX',2:'X-Box 360'}
121
+
122
+#define POWER_SUPPLY 2
123
+
124
+// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
125
+#define PS_DEFAULT_OFF
126
+
127
+// @section temperature
128
+
129
+//===========================================================================
130
+//============================= Thermal Settings ============================
131
+//===========================================================================
132
+//
133
+//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
134
+//
135
+//// Temperature sensor settings:
136
+// -3 is thermocouple with MAX31855 (only for sensor 0)
137
+// -2 is thermocouple with MAX6675 (only for sensor 0)
138
+// -1 is thermocouple with AD595
139
+// 0 is not used
140
+// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
141
+// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
142
+// 3 is Mendel-parts thermistor (4.7k pullup)
143
+// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
144
+// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
145
+// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
146
+// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
147
+// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
148
+// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
149
+// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
150
+// 10 is 100k RS thermistor 198-961 (4.7k pullup)
151
+// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
152
+// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
153
+// 13 is 100k Hisens 3950  1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
154
+// 20 is the PT100 circuit found in the Ultimainboard V2.x
155
+// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
156
+// 70 is the 100K thermistor found in the bq Hephestos 2
157
+//
158
+//    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
159
+//                          (but gives greater accuracy and more stable PID)
160
+// 51 is 100k thermistor - EPCOS (1k pullup)
161
+// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
162
+// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
163
+//
164
+// 1047 is Pt1000 with 4k7 pullup
165
+// 1010 is Pt1000 with 1k pullup (non standard)
166
+// 147 is Pt100 with 4k7 pullup
167
+// 110 is Pt100 with 1k pullup (non standard)
168
+// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
169
+//     Use it for Testing or Development purposes. NEVER for production machine.
170
+//#define DUMMY_THERMISTOR_998_VALUE 25
171
+//#define DUMMY_THERMISTOR_999_VALUE 100
172
+// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-3': "Thermocouple + MAX31855 (only for sensor 0)", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
173
+#define TEMP_SENSOR_0 5
174
+#define TEMP_SENSOR_1 0
175
+#define TEMP_SENSOR_2 0
176
+#define TEMP_SENSOR_3 0
177
+#define TEMP_SENSOR_BED 5
178
+
179
+// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
180
+//#define TEMP_SENSOR_1_AS_REDUNDANT
181
+#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
182
+
183
+// Actual temperature must be close to target for this long before M109 returns success
184
+#define TEMP_RESIDENCY_TIME 10  // (seconds)
185
+#define TEMP_HYSTERESIS 3       // (degC) range of +/- temperatures considered "close" to the target one
186
+#define TEMP_WINDOW     1       // (degC) Window around target to start the residency timer x degC early.
187
+
188
+// The minimal temperature defines the temperature below which the heater will not be enabled It is used
189
+// to check that the wiring to the thermistor is not broken.
190
+// Otherwise this would lead to the heater being powered on all the time.
191
+#define HEATER_0_MINTEMP 5
192
+#define HEATER_1_MINTEMP 5
193
+#define HEATER_2_MINTEMP 5
194
+#define HEATER_3_MINTEMP 5
195
+#define BED_MINTEMP 5
196
+
197
+// When temperature exceeds max temp, your heater will be switched off.
198
+// This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure!
199
+// You should use MINTEMP for thermistor short/failure protection.
200
+#define HEATER_0_MAXTEMP 275
201
+#define HEATER_1_MAXTEMP 275
202
+#define HEATER_2_MAXTEMP 275
203
+#define HEATER_3_MAXTEMP 275
204
+#define BED_MAXTEMP 150
205
+
206
+// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
207
+//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
208
+//#define BED_WATTS (12.0*12.0/1.1)      // P=U^2/R
209
+
210
+//===========================================================================
211
+//============================= PID Settings ================================
212
+//===========================================================================
213
+// PID Tuning Guide here: http://reprap.org/wiki/PID_Tuning
214
+
215
+// Comment the following line to disable PID and enable bang-bang.
216
+#define PIDTEMP
217
+#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
218
+#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
219
+#if ENABLED(PIDTEMP)
220
+  //#define PID_DEBUG // Sends debug data to the serial port.
221
+  //#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
222
+  //#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay
223
+  //#define PID_PARAMS_PER_EXTRUDER // Uses separate PID parameters for each extruder (useful for mismatched extruders)
224
+                                    // Set/get with gcode: M301 E[extruder number, 0-2]
225
+  #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
226
+                                  // is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
227
+  #define PID_INTEGRAL_DRIVE_MAX PID_MAX  //limit for the integral term
228
+  #define K1 0.95 //smoothing factor within the PID
229
+
230
+  // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
231
+  // oXis Kossel k800 XL
232
+  #define DEFAULT_Kp 22.04
233
+  #define DEFAULT_Ki 1.65
234
+  #define DEFAULT_Kd 73.67
235
+
236
+  // Kossel k800 XL
237
+  //#define DEFAULT_Kp 22.25
238
+  //#define DEFAULT_Ki 1.45
239
+  //#define DEFAULT_Kd 85.30
240
+
241
+  // MakerGear
242
+  //#define  DEFAULT_Kp 7.0
243
+  //#define  DEFAULT_Ki 0.1
244
+  //#define  DEFAULT_Kd 12
245
+
246
+  // Mendel Parts V9 on 12V
247
+  //#define  DEFAULT_Kp 63.0
248
+  //#define  DEFAULT_Ki 2.25
249
+  //#define  DEFAULT_Kd 440
250
+
251
+#endif // PIDTEMP
252
+
253
+//===========================================================================
254
+//============================= PID > Bed Temperature Control ===============
255
+//===========================================================================
256
+// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
257
+//
258
+// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
259
+// If your PID_dT is the default, and correct for your hardware/configuration, that means 7.689Hz,
260
+// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
261
+// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
262
+// If your configuration is significantly different than this and you don't understand the issues involved, you probably
263
+// shouldn't use bed PID until someone else verifies your hardware works.
264
+// If this is enabled, find your own PID constants below.
265
+//#define PIDTEMPBED
266
+
267
+//#define BED_LIMIT_SWITCHING
268
+
269
+// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
270
+// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
271
+// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
272
+// so you shouldn't use it unless you are OK with PWM on your bed.  (see the comment on enabling PIDTEMPBED)
273
+#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
274
+
275
+//#define PID_BED_DEBUG // Sends debug data to the serial port.
276
+
277
+#if ENABLED(PIDTEMPBED)
278
+
279
+  #define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
280
+
281
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
282
+  //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
283
+  #define  DEFAULT_bedKp 15.00
284
+  #define  DEFAULT_bedKi .04
285
+  #define  DEFAULT_bedKd 305.4
286
+
287
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
288
+  //from pidautotune
289
+  //#define  DEFAULT_bedKp 97.1
290
+  //#define  DEFAULT_bedKi 1.41
291
+  //#define  DEFAULT_bedKd 1675.16
292
+
293
+  // FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
294
+#endif // PIDTEMPBED
295
+
296
+// @section extruder
297
+
298
+//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
299
+//can be software-disabled for whatever purposes by
300
+#define PREVENT_DANGEROUS_EXTRUDE
301
+//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
302
+#define PREVENT_LENGTHY_EXTRUDE
303
+
304
+#define EXTRUDE_MINTEMP 170
305
+#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
306
+
307
+//===========================================================================
308
+//======================== Thermal Runaway Protection =======================
309
+//===========================================================================
310
+
311
+/**
312
+ * Thermal Protection protects your printer from damage and fire if a
313
+ * thermistor falls out or temperature sensors fail in any way.
314
+ *
315
+ * The issue: If a thermistor falls out or a temperature sensor fails,
316
+ * Marlin can no longer sense the actual temperature. Since a disconnected
317
+ * thermistor reads as a low temperature, the firmware will keep the heater on.
318
+ *
319
+ * If you get "Thermal Runaway" or "Heating failed" errors the
320
+ * details can be tuned in Configuration_adv.h
321
+ */
322
+
323
+#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
324
+#define THERMAL_PROTECTION_BED     // Enable thermal protection for the heated bed
325
+
326
+//===========================================================================
327
+//============================= Mechanical Settings =========================
328
+//===========================================================================
329
+
330
+// @section machine
331
+
332
+// Uncomment this option to enable CoreXY kinematics
333
+//#define COREXY
334
+
335
+// Uncomment this option to enable CoreXZ kinematics
336
+//#define COREXZ
337
+
338
+// Enable this option for Toshiba steppers
339
+//#define CONFIG_STEPPERS_TOSHIBA
340
+
341
+// @section homing
342
+
343
+// coarse Endstop Settings
344
+//#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
345
+
346
+#if DISABLED(ENDSTOPPULLUPS)
347
+  // fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined
348
+  #define ENDSTOPPULLUP_XMAX
349
+  #define ENDSTOPPULLUP_YMAX
350
+  #define ENDSTOPPULLUP_ZMAX
351
+  //#define ENDSTOPPULLUP_XMIN
352
+  //#define ENDSTOPPULLUP_YMIN
353
+  #define ENDSTOPPULLUP_ZMIN
354
+  //#define ENDSTOPPULLUP_ZMIN_PROBE
355
+#endif
356
+
357
+// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
358
+const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
359
+const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
360
+const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
361
+const bool X_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
362
+const bool Y_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
363
+const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
364
+const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
365
+//#define DISABLE_MAX_ENDSTOPS
366
+//#define DISABLE_MIN_ENDSTOPS
367
+
368
+//===========================================================================
369
+//============================= Z Probe Options =============================
370
+//===========================================================================
371
+
372
+// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
373
+// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
374
+//
375
+// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
376
+//
377
+// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
378
+// Example: To park the head outside the bed area when homing with G28.
379
+//
380
+// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
381
+//
382
+// For a servo-based Z probe, you must set up servo support below, including
383
+// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
384
+//
385
+// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
386
+// - Use 5V for powered (usu. inductive) sensors.
387
+// - Otherwise connect:
388
+//   - normally-closed switches to GND and D32.
389
+//   - normally-open switches to 5V and D32.
390
+//
391
+// Normally-closed switches are advised and are the default.
392
+//
393
+// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
394
+// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
395
+// default pin for all RAMPS-based boards. Some other boards map differently.
396
+// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
397
+//
398
+// WARNING:
399
+// Setting the wrong pin may have unexpected and potentially disastrous consequences.
400
+// Use with caution and do your homework.
401
+//
402
+//#define Z_MIN_PROBE_ENDSTOP
403
+
404
+// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
405
+// The Z_MIN_PIN will then be used for both Z-homing and probing.
406
+#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
407
+
408
+// To use a probe you must enable one of the two options above!
409
+
410
+// This option disables the use of the Z_MIN_PROBE_PIN
411
+// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
412
+// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
413
+// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
414
+//#define DISABLE_Z_MIN_PROBE_ENDSTOP
415
+
416
+// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
417
+// :{0:'Low',1:'High'}
418
+#define X_ENABLE_ON 0
419
+#define Y_ENABLE_ON 0
420
+#define Z_ENABLE_ON 0
421
+#define E_ENABLE_ON 0 // For all extruders
422
+
423
+// Disables axis stepper immediately when it's not being used.
424
+// WARNING: When motors turn off there is a chance of losing position accuracy!
425
+#define DISABLE_X false
426
+#define DISABLE_Y false
427
+#define DISABLE_Z false
428
+// Warn on display about possibly reduced accuracy
429
+//#define DISABLE_REDUCED_ACCURACY_WARNING
430
+
431
+// @section extruder
432
+
433
+#define DISABLE_E false // For all extruders
434
+#define DISABLE_INACTIVE_EXTRUDER true //disable only inactive extruders and keep active extruder enabled
435
+
436
+// @section machine
437
+
438
+// Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way.
439
+#define INVERT_X_DIR false
440
+#define INVERT_Y_DIR false
441
+#define INVERT_Z_DIR false
442
+
443
+// @section extruder
444
+
445
+// For direct drive extruder v9 set to true, for geared extruder set to false.
446
+#define INVERT_E0_DIR true
447
+#define INVERT_E1_DIR false
448
+#define INVERT_E2_DIR false
449
+#define INVERT_E3_DIR false
450
+
451
+// @section homing
452
+//#define MIN_Z_HEIGHT_FOR_HOMING 7 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
453
+                                    // Be sure you have this distance over your Z_MAX_POS in case.
454
+
455
+// ENDSTOP SETTINGS:
456
+// Sets direction of endstops when homing; 1=MAX, -1=MIN
457
+// :[-1,1]
458
+#define X_HOME_DIR 1
459
+#define Y_HOME_DIR 1
460
+#define Z_HOME_DIR 1
461
+
462
+#define min_software_endstops false // If true, axis won't move to coordinates less than HOME_POS.
463
+#define max_software_endstops true  // If true, axis won't move to coordinates greater than the defined lengths below.
464
+
465
+// @section machine
466
+
467
+// Travel limits after homing (units are in mm)
468
+#define X_MIN_POS -DELTA_PRINTABLE_RADIUS
469
+#define Y_MIN_POS -DELTA_PRINTABLE_RADIUS
470
+#define Z_MIN_POS 0
471
+#define X_MAX_POS DELTA_PRINTABLE_RADIUS
472
+#define Y_MAX_POS DELTA_PRINTABLE_RADIUS
473
+#define Z_MAX_POS MANUAL_Z_HOME_POS
474
+
475
+//===========================================================================
476
+//========================= Filament Runout Sensor ==========================
477
+//===========================================================================
478
+//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
479
+                                 // In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
480
+                                 // It is assumed that when logic high = filament available
481
+                                 //                    when logic  low = filament ran out
482
+#if ENABLED(FILAMENT_RUNOUT_SENSOR)
483
+  const bool FIL_RUNOUT_INVERTING = true;  // Should be uncommented and true or false should assigned
484
+  #define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
485
+  #define FILAMENT_RUNOUT_SCRIPT "M600"
486
+#endif
487
+
488
+//===========================================================================
489
+//============================ Mesh Bed Leveling ============================
490
+//===========================================================================
491
+
492
+//#define MESH_BED_LEVELING    // Enable mesh bed leveling.
493
+
494
+#if ENABLED(MESH_BED_LEVELING)
495
+  #define MESH_MIN_X 10
496
+  #define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
497
+  #define MESH_MIN_Y 10
498
+  #define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
499
+  #define MESH_NUM_X_POINTS 3  // Don't use more than 7 points per axis, implementation limited.
500
+  #define MESH_NUM_Y_POINTS 3
501
+  #define MESH_HOME_SEARCH_Z 4  // Z after Home, bed somewhere below but above 0.0.
502
+
503
+  //#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
504
+
505
+  #if ENABLED(MANUAL_BED_LEVELING)
506
+    #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
507
+  #endif  // MANUAL_BED_LEVELING
508
+
509
+#endif  // MESH_BED_LEVELING
510
+
511
+//===========================================================================
512
+//============================ Bed Auto Leveling ============================
513
+//===========================================================================
514
+
515
+// @section bedlevel
516
+
517
+#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
518
+//#define DEBUG_LEVELING_FEATURE
519
+//#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
520
+
521
+#if ENABLED(AUTO_BED_LEVELING_FEATURE)
522
+
523
+  // There are 2 different ways to specify probing locations:
524
+  //
525
+  // - "grid" mode
526
+  //   Probe several points in a rectangular grid.
527
+  //   You specify the rectangle and the density of sample points.
528
+  //   This mode is preferred because there are more measurements.
529
+  //
530
+  // - "3-point" mode
531
+  //   Probe 3 arbitrary points on the bed (that aren't collinear)
532
+  //   You specify the XY coordinates of all 3 points.
533
+
534
+  // Enable this to sample the bed in a grid (least squares solution).
535
+  // Note: this feature generates 10KB extra code size.
536
+  #define AUTO_BED_LEVELING_GRID
537
+
538
+  #if ENABLED(AUTO_BED_LEVELING_GRID)
539
+
540
+    #define DELTA_PROBABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10)
541
+    #define LEFT_PROBE_BED_POSITION -DELTA_PROBABLE_RADIUS
542
+    #define RIGHT_PROBE_BED_POSITION DELTA_PROBABLE_RADIUS
543
+    #define FRONT_PROBE_BED_POSITION -DELTA_PROBABLE_RADIUS
544
+    #define BACK_PROBE_BED_POSITION DELTA_PROBABLE_RADIUS
545
+
546
+    #define MIN_PROBE_EDGE 20 // The Z probe minimum square sides can be no smaller than this.
547
+
548
+    // Non-linear bed leveling will be used.
549
+    // Compensate by interpolating between the nearest four Z probe values for each point.
550
+    // Useful for deltas where the print surface may appear like a bowl or dome shape.
551
+    // Works best with AUTO_BED_LEVELING_GRID_POINTS 5 or higher.
552
+    #define AUTO_BED_LEVELING_GRID_POINTS 7
553
+
554
+  #else  // !AUTO_BED_LEVELING_GRID
555
+
556
+    // Arbitrary points to probe.
557
+    // A simple cross-product is used to estimate the plane of the bed.
558
+    #define ABL_PROBE_PT_1_X 15
559
+    #define ABL_PROBE_PT_1_Y 180
560
+    #define ABL_PROBE_PT_2_X 15
561
+    #define ABL_PROBE_PT_2_Y 20
562
+    #define ABL_PROBE_PT_3_X 170
563
+    #define ABL_PROBE_PT_3_Y 20
564
+
565
+  #endif // AUTO_BED_LEVELING_GRID
566
+
567
+  // Z Probe to nozzle (X,Y) offset, relative to (0, 0).
568
+  // X and Y offsets must be integers.
569
+  //
570
+  // In the following example the X and Y offsets are both positive:
571
+  // #define X_PROBE_OFFSET_FROM_EXTRUDER 10
572
+  // #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
573
+  //
574
+  //    +-- BACK ---+
575
+  //    |           |
576
+  //  L |    (+) P  | R <-- probe (20,20)
577
+  //  E |           | I
578
+  //  F | (-) N (+) | G <-- nozzle (10,10)
579
+  //  T |           | H
580
+  //    |    (-)    | T
581
+  //    |           |
582
+  //    O-- FRONT --+
583
+  //  (0,0)
584
+  #define X_PROBE_OFFSET_FROM_EXTRUDER 0.0     // X offset: -left  [of the nozzle] +right
585
+  #define Y_PROBE_OFFSET_FROM_EXTRUDER 0.0     // Y offset: -front [of the nozzle] +behind
586
+  #define Z_PROBE_OFFSET_FROM_EXTRUDER 0.3     // Z offset: -below [the nozzle] (always negative!)
587
+
588
+  #define XY_TRAVEL_SPEED 7000         // X and Y axis travel speed between probes, in mm/min.
589
+
590
+  #define Z_RAISE_BEFORE_PROBING 20   // How much the Z axis will be raised before traveling to the first probing point.
591
+  #define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
592
+  #define Z_RAISE_AFTER_PROBING 20    // How much the Z axis will be raised after the last probing point.
593
+
594
+  #define Z_PROBE_END_SCRIPT "G1 Z20 X0 Y0 F7000"
595
+//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
596
+                                                                            // Useful to retract a deployable Z probe.
597
+
598
+  // Probes are sensors/switches that need to be activated before they can be used
599
+  // and deactivated after the use.
600
+  // Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
601
+
602
+  // A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
603
+  // when the hardware endstops are active.
604
+  //#define FIX_MOUNTED_PROBE
605
+
606
+  // A Servo Probe can be defined in the servo section below.
607
+
608
+  // An Allen Key Probe is currently predefined only in the delta example configurations.
609
+
610
+  //#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
611
+  //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
612
+
613
+  // If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
614
+  // it is highly recommended you leave Z_SAFE_HOMING enabled!
615
+
616
+  #define Z_SAFE_HOMING   // Use the z-min-probe for homing to z-min - not the z-min-endstop.
617
+                          // This feature is meant to avoid Z homing with Z probe outside the bed area.
618
+                          // When defined, it will:
619
+                          // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
620
+                          // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
621
+                          // - Position the Z probe in a defined XY point before Z Homing when homing all axis (G28).
622
+                          // - Block Z homing only when the Z probe is outside bed area.
623
+
624
+  #if ENABLED(Z_SAFE_HOMING)
625
+
626
+    #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2)    // X point for Z homing when homing all axis (G28).
627
+    #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)    // Y point for Z homing when homing all axis (G28).
628
+
629
+  #endif
630
+
631
+#endif // AUTO_BED_LEVELING_FEATURE
632
+
633
+
634
+// @section homing
635
+
636
+// The position of the homing switches
637
+#define MANUAL_HOME_POSITIONS  // If defined, MANUAL_*_HOME_POS below will be used
638
+#define BED_CENTER_AT_0_0  // If defined, the center of the bed is at (X=0, Y=0)
639
+
640
+// Manual homing switch locations:
641
+// For deltabots this means top and center of the Cartesian print volume.
642
+#if ENABLED(MANUAL_HOME_POSITIONS)
643
+  #define MANUAL_X_HOME_POS 0
644
+  #define MANUAL_Y_HOME_POS 0
645
+  #define MANUAL_Z_HOME_POS 386.5 // For delta: Distance between nozzle and print surface after homing.
646
+#endif
647
+
648
+// @section movement
649
+
650
+/**
651
+ * MOVEMENT SETTINGS
652
+ */
653
+
654
+#define HOMING_FEEDRATE {60*60, 60*60, 60*60, 0}  // set the homing speeds (mm/min)
655
+
656
+// default settings
657
+#define XYZ_FULL_STEPS_PER_ROTATION 200
658
+#define XYZ_MICROSTEPS 16
659
+#define XYZ_BELT_PITCH 2
660
+#define XYZ_PULLEY_TEETH 16
661
+#define XYZ_STEPS ((XYZ_FULL_STEPS_PER_ROTATION) * (XYZ_MICROSTEPS) / double(XYZ_BELT_PITCH) / double(XYZ_PULLEY_TEETH))
662
+
663
+#define DEFAULT_AXIS_STEPS_PER_UNIT   {XYZ_STEPS, XYZ_STEPS, XYZ_STEPS, 158}   // default steps per unit for PowerWasp
664
+#define DEFAULT_MAX_FEEDRATE          {200, 200, 200, 200}    // (mm/sec)
665
+#define DEFAULT_MAX_ACCELERATION      {9000,9000,9000,9000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
666
+
667
+#define DEFAULT_ACCELERATION          2000    // X, Y, Z and E acceleration in mm/s^2 for printing moves
668
+#define DEFAULT_RETRACT_ACCELERATION  3000    // E acceleration in mm/s^2 for retracts
669
+#define DEFAULT_TRAVEL_ACCELERATION   3000    // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
670
+
671
+// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
672
+#define DEFAULT_XYJERK                20.0    // (mm/sec)
673
+#define DEFAULT_ZJERK                 20.0    // (mm/sec)
674
+#define DEFAULT_EJERK                 20.0    // (mm/sec)
675
+
676
+
677
+//=============================================================================
678
+//============================= Additional Features ===========================
679
+//=============================================================================
680
+
681
+// @section more
682
+
683
+// Custom M code points
684
+#define CUSTOM_M_CODES
685
+#if ENABLED(CUSTOM_M_CODES)
686
+  #if ENABLED(AUTO_BED_LEVELING_FEATURE)
687
+    #define CUSTOM_M_CODE_SET_Z_PROBE_OFFSET 851
688
+    #define Z_PROBE_OFFSET_RANGE_MIN -20
689
+    #define Z_PROBE_OFFSET_RANGE_MAX 20
690
+  #endif
691
+#endif
692
+
693
+// @section extras
694
+
695
+// EEPROM
696
+// The microcontroller can store settings in the EEPROM, e.g. max velocity...
697
+// M500 - stores parameters in EEPROM
698
+// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
699
+// M502 - reverts to the default "factory settings".  You still need to store them in EEPROM afterwards if you want to.
700
+//define this to enable EEPROM support
701
+#define EEPROM_SETTINGS
702
+
703
+#if ENABLED(EEPROM_SETTINGS)
704
+  // To disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
705
+  #define EEPROM_CHITCHAT // Please keep turned on if you can.
706
+#endif
707
+
708
+//
709
+// Host Keepalive
710
+//
711
+// By default Marlin will send a busy status message to the host
712
+// every 2 seconds when it can't accept commands.
713
+//
714
+//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
715
+
716
+//
717
+// M100 Free Memory Watcher
718
+//
719
+//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
720
+
721
+// @section temperature
722
+
723
+// Preheat Constants
724
+#define PLA_PREHEAT_HOTEND_TEMP 180
725
+#define PLA_PREHEAT_HPB_TEMP 70
726
+#define PLA_PREHEAT_FAN_SPEED 100   // Insert Value between 0 and 255
727
+
728
+#define ABS_PREHEAT_HOTEND_TEMP 240
729
+#define ABS_PREHEAT_HPB_TEMP 110
730
+#define ABS_PREHEAT_FAN_SPEED 100   // Insert Value between 0 and 255
731
+
732
+//==============================LCD and SD support=============================
733
+// @section lcd
734
+
735
+// Define your display language below. Replace (en) with your language code and uncomment.
736
+// en, pl, fr, de, es, ru, bg, it, pt, pt_utf8, pt-br, pt-br_utf8, fi, an, nl, ca, eu, kana, kana_utf8, cn, cz, test
737
+// See also language.h
738
+#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
739
+
740
+// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
741
+// To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
742
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
743
+  #define DISPLAY_CHARSET_HD44780_JAPAN        // this is the most common hardware
744
+  //#define DISPLAY_CHARSET_HD44780_WESTERN
745
+  //#define DISPLAY_CHARSET_HD44780_CYRILLIC
746
+
747
+//#define ULTRA_LCD  //general LCD support, also 16x2
748
+//#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
749
+//#define SDSUPPORT // Enable SD Card Support in Hardware Console
750
+                    // Changed behaviour! If you need SDSUPPORT uncomment it!
751
+//#define SPI_SPEED SPI_HALF_SPEED // (also SPI_QUARTER_SPEED, SPI_EIGHTH_SPEED) Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
752
+//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
753
+//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
754
+//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
755
+//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
756
+//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
757
+//#define ULTIPANEL  //the UltiPanel as on Thingiverse
758
+//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
759
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
760
+//#define LCD_FEEDBACK_FREQUENCY_HZ 1000         // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
761
+                                                 // 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
762
+// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
763
+// http://reprap.org/wiki/PanelOne
764
+//#define PANEL_ONE
765
+
766
+// The MaKr3d Makr-Panel with graphic controller and SD support
767
+// http://reprap.org/wiki/MaKr3d_MaKrPanel
768
+//#define MAKRPANEL
769
+
770
+// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
771
+// http://panucatt.com
772
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
773
+//#define VIKI2
774
+//#define miniVIKI
775
+
776
+// This is a new controller currently under development.  https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
777
+//
778
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
779
+//#define ELB_FULL_GRAPHIC_CONTROLLER
780
+//#define SD_DETECT_INVERTED
781
+
782
+// The RepRapDiscount Smart Controller (white PCB)
783
+// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
784
+#define REPRAP_DISCOUNT_SMART_CONTROLLER
785
+
786
+// The GADGETS3D G3D LCD/SD Controller (blue PCB)
787
+// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel
788
+//#define G3D_PANEL
789
+
790
+// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
791
+// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
792
+//
793
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
794
+//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
795
+
796
+// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
797
+// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
798
+//#define REPRAPWORLD_KEYPAD
799
+//#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 // how much should be moved when a key is pressed, eg 10.0 means 10mm per click
800
+
801
+// The Elefu RA Board Control Panel
802
+// http://www.elefu.com/index.php?route=product/product&product_id=53
803
+// REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
804
+//#define RA_CONTROL_PANEL
805
+
806
+// The MakerLab Mini Panel with graphic controller and SD support
807
+// http://reprap.org/wiki/Mini_panel
808
+//#define MINIPANEL
809
+
810
+/**
811
+ * I2C Panels
812
+ */
813
+
814
+//#define LCD_I2C_SAINSMART_YWROBOT
815
+
816
+//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
817
+
818
+// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
819
+//
820
+// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
821
+// Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory.
822
+// (v1.2.3 no longer requires you to define PANELOLU in the LiquidTWI2.h library header file)
823
+// Note: The PANELOLU2 encoder click input can either be directly connected to a pin
824
+//       (if BTN_ENC defined to != -1) or read through I2C (when BTN_ENC == -1).
825
+//#define LCD_I2C_PANELOLU2
826
+
827
+// Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs
828
+//#define LCD_I2C_VIKI
829
+
830
+// SSD1306 OLED generic display support
831
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
832
+//#define U8GLIB_SSD1306
833
+
834
+// Shift register panels
835
+// ---------------------
836
+// 2 wire Non-latching LCD SR from:
837
+// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
838
+// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
839
+//#define SAV_3DLCD
840
+
841
+// @section extras
842
+
843
+// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
844
+//#define FAST_PWM_FAN
845
+
846
+// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
847
+// which is not as annoying as with the hardware PWM. On the other hand, if this frequency
848
+// is too low, you should also increment SOFT_PWM_SCALE.
849
+//#define FAN_SOFT_PWM
850
+
851
+// Incrementing this by 1 will double the software PWM frequency,
852
+// affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
853
+// However, control resolution will be halved for each increment;
854
+// at zero value, there are 128 effective control positions.
855
+#define SOFT_PWM_SCALE 0
856
+
857
+// Temperature status LEDs that display the hotend and bet temperature.
858
+// If all hotends and bed temperature and temperature setpoint are < 54C then the BLUE led is on.
859
+// Otherwise the RED led is on. There is 1C hysteresis.
860
+//#define TEMP_STAT_LEDS
861
+
862
+// M240  Triggers a camera by emulating a Canon RC-1 Remote
863
+// Data from: http://www.doc-diy.net/photo/rc-1_hacked/
864
+//#define PHOTOGRAPH_PIN     23
865
+
866
+// SkeinForge sends the wrong arc g-codes when using Arc Point as fillet procedure
867
+//#define SF_ARC_FIX
868
+
869
+// Support for the BariCUDA Paste Extruder.
870
+//#define BARICUDA
871
+
872
+//define BlinkM/CyzRgb Support
873
+//#define BLINKM
874
+
875
+/*********************************************************************\
876
+* R/C SERVO support
877
+* Sponsored by TrinityLabs, Reworked by codexmas
878
+**********************************************************************/
879
+
880
+// Number of servos
881
+//
882
+// If you select a configuration below, this will receive a default value and does not need to be set manually
883
+// set it manually if you have more servos than extruders and wish to manually control some
884
+// leaving it undefined or defining as 0 will disable the servo subsystem
885
+// If unsure, leave commented / disabled
886
+//
887
+//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
888
+
889
+// Servo Endstops
890
+//
891
+// This allows for servo actuated endstops, primary usage is for the Z Axis to eliminate calibration or bed height changes.
892
+// Use M851 to set the Z probe vertical offset from the nozzle. Store that setting with M500.
893
+//
894
+//#define X_ENDSTOP_SERVO_NR 1
895
+//#define Y_ENDSTOP_SERVO_NR 2
896
+//#define Z_ENDSTOP_SERVO_NR 0
897
+//#define SERVO_ENDSTOP_ANGLES {{0,0}, {0,0}, {70,0}} // X,Y,Z Axis Extend and Retract angles
898
+
899
+// Servo deactivation
900
+//
901
+// With this option servos are powered only during movement, then turned off to prevent jitter.
902
+//#define DEACTIVATE_SERVOS_AFTER_MOVE
903
+
904
+#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
905
+  // Delay (in microseconds) before turning the servo off. This depends on the servo speed.
906
+  // 300ms is a good value but you can try less delay.
907
+  // If the servo can't reach the requested position, increase it.
908
+  #define SERVO_DEACTIVATION_DELAY 300
909
+#endif
910
+
911
+/**********************************************************************\
912
+ * Support for a filament diameter sensor
913
+ * Also allows adjustment of diameter at print time (vs  at slicing)
914
+ * Single extruder only at this point (extruder 0)
915
+ *
916
+ * Motherboards
917
+ * 34 - RAMPS1.4 - uses Analog input 5 on the AUX2 connector
918
+ * 81 - Printrboard - Uses Analog input 2 on the Exp1 connector (version B,C,D,E)
919
+ * 301 - Rambo  - uses Analog input 3
920
+ * Note may require analog pins to be defined for different motherboards
921
+ **********************************************************************/
922
+// Uncomment below to enable
923
+//#define FILAMENT_SENSOR
924
+
925
+#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
926
+
927
+#if ENABLED(FILAMENT_SENSOR)
928
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
929
+  #define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
930
+
931
+  #define MEASURED_UPPER_LIMIT         2.00  //upper limit factor used for sensor reading validation in mm
932
+  #define MEASURED_LOWER_LIMIT         1.60  //lower limit factor for sensor reading validation in mm
933
+  #define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
934
+
935
+  #define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
936
+
937
+  //When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
938
+  //#define FILAMENT_LCD_DISPLAY
939
+#endif
940
+
941
+#include "Configuration_adv.h"
942
+#include "thermistortables.h"
943
+
944
+#endif //CONFIGURATION_H

Marlin/configurator/config/Configuration_adv.h → Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h Näytä tiedosto

@@ -17,6 +17,20 @@
17 17
 /**
18 18
  * Thermal Protection parameters
19 19
  */
20
+  /**
21
+   * Thermal Protection protects your printer from damage and fire if a
22
+   * thermistor falls out or temperature sensors fail in any way.
23
+   *
24
+   * The issue: If a thermistor falls out or a temperature sensor fails,
25
+   * Marlin can no longer sense the actual temperature. Since a disconnected
26
+   * thermistor reads as a low temperature, the firmware will keep the heater on.
27
+   *
28
+   * The solution: Once the temperature reaches the target, start observing.
29
+   * If the temperature stays too far below the target (hysteresis) for too long (period),
30
+   * the firmware will halt the machine as a safety precaution.
31
+   *
32
+   * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
33
+   */
20 34
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
21 35
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
22 36
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
@@ -26,14 +40,22 @@
26 40
    * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
27 41
    * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
28 42
    * but only if the current temperature is far enough below the target for a reliable test.
43
+   *
44
+   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
45
+   * WATCH_TEMP_INCREASE should not be below 2.
29 46
    */
30 47
   #define WATCH_TEMP_PERIOD 16                // Seconds
31 48
   #define WATCH_TEMP_INCREASE 4               // Degrees Celsius
32 49
 #endif
33 50
 
51
+  /**
52
+   * Thermal Protection parameters for the bed
53
+   * are like the above for the hotends.
54
+   * WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
55
+   */
34 56
 #if ENABLED(THERMAL_PROTECTION_BED)
35 57
   #define THERMAL_PROTECTION_BED_PERIOD 20    // Seconds
36
-  #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
58
+  #define THERMAL_PROTECTION_BED_HYSTERESIS 4 // Degrees Celsius
37 59
 #endif
38 60
 
39 61
 #if ENABLED(PIDTEMP)
@@ -52,7 +74,7 @@
52 74
  * The maximum buffered steps/sec of the extruder motor is called "se".
53 75
  * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
54 76
  * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
55
- * mintemp and maxtemp. Turn this off by excuting M109 without F*
77
+ * mintemp and maxtemp. Turn this off by executing M109 without F*
56 78
  * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
57 79
  * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
58 80
  */
@@ -137,7 +159,7 @@
137 159
 #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
138 160
 
139 161
   // 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.
140
-  // That way the machine is capable to align the bed during home, since both Z steppers are homed. 
162
+  // That way the machine is capable to align the bed during home, since both Z steppers are homed.
141 163
   // There is also an implementation of M666 (software endstops adjustment) to this feature.
142 164
   // After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
143 165
   // 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.
@@ -232,7 +254,13 @@
232 254
 #define INVERT_E_STEP_PIN false
233 255
 
234 256
 // Default stepper release if idle. Set to 0 to deactivate.
257
+// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
258
+// Time can be set by M18 and M84.
235 259
 #define DEFAULT_STEPPER_DEACTIVE_TIME 60
260
+#define DISABLE_INACTIVE_X true
261
+#define DISABLE_INACTIVE_Y true
262
+#define DISABLE_INACTIVE_Z true  // set to false if the nozzle will fall down on your printed part when print has finished.
263
+#define DISABLE_INACTIVE_E true
236 264
 
237 265
 #define DEFAULT_MINIMUMFEEDRATE       0.0     // minimum feedrate
238 266
 #define DEFAULT_MINTRAVELFEEDRATE     0.0
@@ -268,6 +296,9 @@
268 296
 // Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
269 297
 #define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
270 298
 
299
+// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
300
+//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
301
+
271 302
 // uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
272 303
 //#define DIGIPOT_I2C
273 304
 // Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
@@ -335,8 +366,8 @@
335 366
   // save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
336 367
   // we don't have a big font for Cyrillic, Kana
337 368
   //#define USE_BIG_EDIT_FONT
338
- 
339
-  // If you have spare 2300Byte of progmem and want to use a 
369
+
370
+  // If you have spare 2300Byte of progmem and want to use a
340 371
   // smaller font on the Info-screen uncomment the next line.
341 372
   //#define USE_SMALL_INFOFONT
342 373
 #endif // DOGLCD
@@ -344,13 +375,13 @@
344 375
 // @section more
345 376
 
346 377
 // The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
347
-//#define USE_WATCHDOG
378
+#define USE_WATCHDOG
348 379
 
349 380
 #if ENABLED(USE_WATCHDOG)
350
-// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
351
-// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
352
-//  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
353
-//#define WATCHDOG_RESET_MANUAL
381
+  // If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
382
+  // The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
383
+  //  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
384
+  //#define WATCHDOG_RESET_MANUAL
354 385
 #endif
355 386
 
356 387
 // @section lcd
@@ -361,6 +392,7 @@
361 392
 //#define BABYSTEPPING
362 393
 #if ENABLED(BABYSTEPPING)
363 394
   #define BABYSTEP_XY  //not only z, but also XY in the menu. more clutter, more functions
395
+                       //not implemented for deltabots!
364 396
   #define BABYSTEP_INVERT_Z false  //true for inverse movements in Z
365 397
   #define BABYSTEP_MULTIPLICATOR 1 //faster movements
366 398
 #endif
@@ -379,7 +411,6 @@
379 411
 #if ENABLED(ADVANCE)
380 412
   #define EXTRUDER_ADVANCE_K .0
381 413
   #define D_FILAMENT 2.85
382
-  #define STEPS_MM_E 836
383 414
 #endif
384 415
 
385 416
 // @section extras
@@ -388,7 +419,7 @@
388 419
 #define MM_PER_ARC_SEGMENT 1
389 420
 #define N_ARC_CORRECTION 25
390 421
 
391
-const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
422
+const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
392 423
 
393 424
 // @section temperature
394 425
 
@@ -460,8 +491,8 @@ const unsigned int dropsegments=5; //everything with less than this number of st
460 491
 #endif
461 492
 
462 493
 /******************************************************************************\
463
- * enable this section if you have TMC26X motor drivers. 
464
- * you need to import the TMC26XStepper library into the arduino IDE for this
494
+ * enable this section if you have TMC26X motor drivers.
495
+ * you need to import the TMC26XStepper library into the Arduino IDE for this
465 496
  ******************************************************************************/
466 497
 
467 498
 // @section tmc
@@ -469,61 +500,61 @@ const unsigned int dropsegments=5; //everything with less than this number of st
469 500
 //#define HAVE_TMCDRIVER
470 501
 #if ENABLED(HAVE_TMCDRIVER)
471 502
 
472
-//#define X_IS_TMC
503
+  //#define X_IS_TMC
473 504
   #define X_MAX_CURRENT 1000  //in mA
474 505
   #define X_SENSE_RESISTOR 91 //in mOhms
475 506
   #define X_MICROSTEPS 16     //number of microsteps
476
-  
477
-//#define X2_IS_TMC
507
+
508
+  //#define X2_IS_TMC
478 509
   #define X2_MAX_CURRENT 1000  //in mA
479 510
   #define X2_SENSE_RESISTOR 91 //in mOhms
480 511
   #define X2_MICROSTEPS 16     //number of microsteps
481
-  
482
-//#define Y_IS_TMC
512
+
513
+  //#define Y_IS_TMC
483 514
   #define Y_MAX_CURRENT 1000  //in mA
484 515
   #define Y_SENSE_RESISTOR 91 //in mOhms
485 516
   #define Y_MICROSTEPS 16     //number of microsteps
486
-  
487
-//#define Y2_IS_TMC
517
+
518
+  //#define Y2_IS_TMC
488 519
   #define Y2_MAX_CURRENT 1000  //in mA
489 520
   #define Y2_SENSE_RESISTOR 91 //in mOhms
490
-  #define Y2_MICROSTEPS 16     //number of microsteps 
491
-  
492
-//#define Z_IS_TMC
521
+  #define Y2_MICROSTEPS 16     //number of microsteps
522
+
523
+  //#define Z_IS_TMC
493 524
   #define Z_MAX_CURRENT 1000  //in mA
494 525
   #define Z_SENSE_RESISTOR 91 //in mOhms
495 526
   #define Z_MICROSTEPS 16     //number of microsteps
496
-  
497
-//#define Z2_IS_TMC
527
+
528
+  //#define Z2_IS_TMC
498 529
   #define Z2_MAX_CURRENT 1000  //in mA
499 530
   #define Z2_SENSE_RESISTOR 91 //in mOhms
500 531
   #define Z2_MICROSTEPS 16     //number of microsteps
501
-  
502
-//#define E0_IS_TMC
532
+
533
+  //#define E0_IS_TMC
503 534
   #define E0_MAX_CURRENT 1000  //in mA
504 535
   #define E0_SENSE_RESISTOR 91 //in mOhms
505 536
   #define E0_MICROSTEPS 16     //number of microsteps
506
-  
507
-//#define E1_IS_TMC
537
+
538
+  //#define E1_IS_TMC
508 539
   #define E1_MAX_CURRENT 1000  //in mA
509 540
   #define E1_SENSE_RESISTOR 91 //in mOhms
510
-  #define E1_MICROSTEPS 16     //number of microsteps 
511
-  
512
-//#define E2_IS_TMC
541
+  #define E1_MICROSTEPS 16     //number of microsteps
542
+
543
+  //#define E2_IS_TMC
513 544
   #define E2_MAX_CURRENT 1000  //in mA
514 545
   #define E2_SENSE_RESISTOR 91 //in mOhms
515
-  #define E2_MICROSTEPS 16     //number of microsteps 
516
-  
517
-//#define E3_IS_TMC
546
+  #define E2_MICROSTEPS 16     //number of microsteps
547
+
548
+  //#define E3_IS_TMC
518 549
   #define E3_MAX_CURRENT 1000  //in mA
519 550
   #define E3_SENSE_RESISTOR 91 //in mOhms
520
-  #define E3_MICROSTEPS 16     //number of microsteps   
551
+  #define E3_MICROSTEPS 16     //number of microsteps
521 552
 
522 553
 #endif
523 554
 
524 555
 /******************************************************************************\
525
- * enable this section if you have L6470  motor drivers. 
526
- * you need to import the L6470 library into the arduino IDE for this
556
+ * enable this section if you have L6470  motor drivers.
557
+ * you need to import the L6470 library into the Arduino IDE for this
527 558
  ******************************************************************************/
528 559
 
529 560
 // @section l6470
@@ -531,69 +562,66 @@ const unsigned int dropsegments=5; //everything with less than this number of st
531 562
 //#define HAVE_L6470DRIVER
532 563
 #if ENABLED(HAVE_L6470DRIVER)
533 564
 
534
-//#define X_IS_L6470
565
+  //#define X_IS_L6470
535 566
   #define X_MICROSTEPS 16     //number of microsteps
536
-  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
567
+  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
537 568
   #define X_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
538 569
   #define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
539
-  
540
-//#define X2_IS_L6470
570
+
571
+  //#define X2_IS_L6470
541 572
   #define X2_MICROSTEPS 16     //number of microsteps
542
-  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
573
+  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
543 574
   #define X2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
544 575
   #define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
545
-  
546
-//#define Y_IS_L6470
576
+
577
+  //#define Y_IS_L6470
547 578
   #define Y_MICROSTEPS 16     //number of microsteps
548
-  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
579
+  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
549 580
   #define Y_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
550 581
   #define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
551
-  
552
-//#define Y2_IS_L6470
553
-  #define Y2_MICROSTEPS 16     //number of microsteps 
554
-  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
582
+
583
+  //#define Y2_IS_L6470
584
+  #define Y2_MICROSTEPS 16     //number of microsteps
585
+  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
555 586
   #define Y2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
556
-  #define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall 
557
-  
558
-//#define Z_IS_L6470
587
+  #define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
588
+
589
+  //#define Z_IS_L6470
559 590
   #define Z_MICROSTEPS 16     //number of microsteps
560
-  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
591
+  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
561 592
   #define Z_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
562 593
   #define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
563
-  
564
-//#define Z2_IS_L6470
594
+
595
+  //#define Z2_IS_L6470
565 596
   #define Z2_MICROSTEPS 16     //number of microsteps
566
-  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
597
+  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
567 598
   #define Z2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
568 599
   #define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
569
-  
570
-//#define E0_IS_L6470
600
+
601
+  //#define E0_IS_L6470
571 602
   #define E0_MICROSTEPS 16     //number of microsteps
572
-  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
603
+  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
573 604
   #define E0_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
574 605
   #define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
575
-  
576
-//#define E1_IS_L6470
577
-  #define E1_MICROSTEPS 16     //number of microsteps 
606
+
607
+  //#define E1_IS_L6470
578 608
   #define E1_MICROSTEPS 16     //number of microsteps
579
-  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
609
+  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
580 610
   #define E1_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
581 611
   #define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
582
-  
583
-//#define E2_IS_L6470
584
-  #define E2_MICROSTEPS 16     //number of microsteps 
612
+
613
+  //#define E2_IS_L6470
585 614
   #define E2_MICROSTEPS 16     //number of microsteps
586
-  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
615
+  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
587 616
   #define E2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
588 617
   #define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
589
-  
590
-//#define E3_IS_L6470
591
-  #define E3_MICROSTEPS 16     //number of microsteps   
618
+
619
+  //#define E3_IS_L6470
592 620
   #define E3_MICROSTEPS 16     //number of microsteps
593
-  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high    
621
+  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
594 622
   #define E3_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
595 623
   #define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
596
-  
624
+
597 625
 #endif
598 626
 
599 627
 #include "Conditionals.h"

+ 21
- 0
Marlin/example_configurations/delta/kossel_xl/README.md Näytä tiedosto

@@ -0,0 +1,21 @@
1
+# Configuration for Kossel k800 XL
2
+This example configuration ist for a Kossel XL with a printable bed diameter of 280mm and a height of 385mm. It also has the auto bed leveling probe (with a endstop switch) and the heat bed activated. 
3
+
4
+## Configuration
5
+You might have/want to edit at least the following settings in Configuration.h:
6
+* <code>MANUAL_Z_HOME_POS<code> The hight of your printing space available, auto bed leveling makes this not as important as before
7
+* <code>DELTA_PRINTABLE_RADIUS</code> The printable radius
8
+* <code>DEFAULT_AXIS_STEPS_PER_UNIT</code> [http://zennmaster.com/makingstuff/reprap-101-calibrating-your-extruder-part-1-e-steps](The steps for the extruder to optimize the amount of filament flow)
9
+
10
+### Fine tuning
11
+* Increase <code>DELTA_RADIUS</code> when the model is convex (bulge in the middle)
12
+* Increase <code>DELTA_DIAGONAL_ROD</code> when the model is larger then expected
13
+
14
+### [http://reprap.org/wiki/PID_Tuning](PID Tuning)
15
+* <code>DEFAULT_Kp</code> (PID tuning for the hotend)
16
+* <code>DEFAULT_Ki</code> (PID tuning for the hotend)
17
+* <code>DEFAULT_Kd</code> (PID tuning for the hotend)
18
+
19
+### PSU Options
20
+* The power supply is configured to 2 (to use a relay to switch 12V on and off)
21
+* It is configured to be off by default

+ 153
- 102
Marlin/example_configurations/makibox/Configuration.h Näytä tiedosto

@@ -110,6 +110,7 @@ Here are some standard links for getting your machine calibrated:
110 110
 //--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
111 111
 //
112 112
 //// Temperature sensor settings:
113
+// -3 is thermocouple with MAX31855 (only for sensor 0)
113 114
 // -2 is thermocouple with MAX6675 (only for sensor 0)
114 115
 // -1 is thermocouple with AD595
115 116
 // 0 is not used
@@ -129,6 +130,7 @@ Here are some standard links for getting your machine calibrated:
129 130
 // 13 is 100k Hisens 3950  1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
130 131
 // 20 is the PT100 circuit found in the Ultimainboard V2.x
131 132
 // 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
133
+// 70 is the 100K thermistor found in the bq Hephestos 2
132 134
 //
133 135
 //    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
134 136
 //                          (but gives greater accuracy and more stable PID)
@@ -144,7 +146,7 @@ Here are some standard links for getting your machine calibrated:
144 146
 //     Use it for Testing or Development purposes. NEVER for production machine.
145 147
 //#define DUMMY_THERMISTOR_998_VALUE 25
146 148
 //#define DUMMY_THERMISTOR_999_VALUE 100
147
-// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
149
+// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-3': "Thermocouple + MAX31855 (only for sensor 0)", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
148 150
 #define TEMP_SENSOR_0 1
149 151
 #define TEMP_SENSOR_1 0
150 152
 #define TEMP_SENSOR_2 0
@@ -178,14 +180,9 @@ Here are some standard links for getting your machine calibrated:
178 180
 #define HEATER_3_MAXTEMP 275
179 181
 #define BED_MAXTEMP 150
180 182
 
181
-// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
182
-// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
183
-// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
184
-//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
185
-
186 183
 // If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
187
-//#define EXTRUDER_WATTS (12.0*12.0/6.7) //  P=I^2/R
188
-//#define BED_WATTS (12.0*12.0/1.1)      // P=I^2/R
184
+//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
185
+//#define BED_WATTS (12.0*12.0/1.1)      // P=U^2/R
189 186
 
190 187
 //===========================================================================
191 188
 //============================= PID Settings ================================
@@ -256,13 +253,13 @@ Here are some standard links for getting your machine calibrated:
256 253
 
257 254
   #define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
258 255
 
259
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
256
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
260 257
   //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
261 258
   #define  DEFAULT_bedKp 10.00
262 259
   #define  DEFAULT_bedKi .023
263 260
   #define  DEFAULT_bedKd 305.4
264 261
 
265
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
262
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
266 263
   //from pidautotune
267 264
   //#define  DEFAULT_bedKp 97.1
268 265
   //#define  DEFAULT_bedKi 1.41
@@ -287,16 +284,15 @@ Here are some standard links for getting your machine calibrated:
287 284
 //===========================================================================
288 285
 
289 286
 /**
290
- * Thermal Runaway Protection protects your printer from damage and fire if a
287
+ * Thermal Protection protects your printer from damage and fire if a
291 288
  * thermistor falls out or temperature sensors fail in any way.
292 289
  *
293 290
  * The issue: If a thermistor falls out or a temperature sensor fails,
294 291
  * Marlin can no longer sense the actual temperature. Since a disconnected
295 292
  * thermistor reads as a low temperature, the firmware will keep the heater on.
296 293
  *
297
- * The solution: Once the temperature reaches the target, start observing.
298
- * If the temperature stays too far below the target (hysteresis) for too long,
299
- * the firmware will halt as a safety precaution.
294
+ * If you get "Thermal Runaway" or "Heating failed" errors the
295
+ * details can be tuned in Configuration_adv.h
300 296
  */
301 297
 
302 298
 #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
@@ -344,10 +340,52 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
344 340
 //#define DISABLE_MAX_ENDSTOPS
345 341
 //#define DISABLE_MIN_ENDSTOPS
346 342
 
347
-// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
348
-// This only affects a Z probe endstop if you have separate Z min endstop as well and have
349
-// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
350
-// this has no effect.
343
+//===========================================================================
344
+//============================= Z Probe Options =============================
345
+//===========================================================================
346
+
347
+// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
348
+// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
349
+//
350
+// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
351
+//
352
+// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
353
+// Example: To park the head outside the bed area when homing with G28.
354
+//
355
+// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
356
+//
357
+// For a servo-based Z probe, you must set up servo support below, including
358
+// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
359
+//
360
+// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
361
+// - Use 5V for powered (usu. inductive) sensors.
362
+// - Otherwise connect:
363
+//   - normally-closed switches to GND and D32.
364
+//   - normally-open switches to 5V and D32.
365
+//
366
+// Normally-closed switches are advised and are the default.
367
+//
368
+// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
369
+// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
370
+// default pin for all RAMPS-based boards. Some other boards map differently.
371
+// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
372
+//
373
+// WARNING:
374
+// Setting the wrong pin may have unexpected and potentially disastrous consequences.
375
+// Use with caution and do your homework.
376
+//
377
+//#define Z_MIN_PROBE_ENDSTOP
378
+
379
+// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
380
+// The Z_MIN_PIN will then be used for both Z-homing and probing.
381
+#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
382
+
383
+// To use a probe you must enable one of the two options above!
384
+
385
+// This option disables the use of the Z_MIN_PROBE_PIN
386
+// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
387
+// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
388
+// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
351 389
 //#define DISABLE_Z_MIN_PROBE_ENDSTOP
352 390
 
353 391
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
@@ -357,11 +395,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
357 395
 #define Z_ENABLE_ON 0
358 396
 #define E_ENABLE_ON 0 // For all extruders
359 397
 
360
-// Disables axis when it's not being used.
398
+// Disables axis stepper immediately when it's not being used.
361 399
 // WARNING: When motors turn off there is a chance of losing position accuracy!
362 400
 #define DISABLE_X false
363 401
 #define DISABLE_Y false
364 402
 #define DISABLE_Z false
403
+// Warn on display about possibly reduced accuracy
404
+//#define DISABLE_REDUCED_ACCURACY_WARNING
365 405
 
366 406
 // @section extruder
367 407
 
@@ -384,6 +424,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
384 424
 #define INVERT_E3_DIR false
385 425
 
386 426
 // @section homing
427
+//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
428
+                                    // Be sure you have this distance over your Z_MAX_POS in case.
387 429
 
388 430
 // ENDSTOP SETTINGS:
389 431
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
@@ -419,24 +461,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
419 461
 #endif
420 462
 
421 463
 //===========================================================================
422
-//=========================== Manual Bed Leveling ===========================
464
+//============================ Mesh Bed Leveling ============================
423 465
 //===========================================================================
424 466
 
425
-//#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
426 467
 //#define MESH_BED_LEVELING    // Enable mesh bed leveling.
427 468
 
428
-#if ENABLED(MANUAL_BED_LEVELING)
429
-  #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
430
-#endif  // MANUAL_BED_LEVELING
431
-
432 469
 #if ENABLED(MESH_BED_LEVELING)
433 470
   #define MESH_MIN_X 10
434
-  #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
471
+  #define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
435 472
   #define MESH_MIN_Y 10
436
-  #define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
473
+  #define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
437 474
   #define MESH_NUM_X_POINTS 3  // Don't use more than 7 points per axis, implementation limited.
438 475
   #define MESH_NUM_Y_POINTS 3
439 476
   #define MESH_HOME_SEARCH_Z 4  // Z after Home, bed somewhere below but above 0.0.
477
+
478
+  //#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
479
+
480
+  #if ENABLED(MANUAL_BED_LEVELING)
481
+    #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
482
+  #endif  // MANUAL_BED_LEVELING
483
+
440 484
 #endif  // MESH_BED_LEVELING
441 485
 
442 486
 //===========================================================================
@@ -447,7 +491,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
447 491
 
448 492
 //#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
449 493
 //#define DEBUG_LEVELING_FEATURE
450
-#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
494
+#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
451 495
 
452 496
 #if ENABLED(AUTO_BED_LEVELING_FEATURE)
453 497
 
@@ -459,7 +503,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
459 503
   //   This mode is preferred because there are more measurements.
460 504
   //
461 505
   // - "3-point" mode
462
-  //   Probe 3 arbitrary points on the bed (that aren't colinear)
506
+  //   Probe 3 arbitrary points on the bed (that aren't collinear)
463 507
   //   You specify the XY coordinates of all 3 points.
464 508
 
465 509
   // Enable this to sample the bed in a grid (least squares solution).
@@ -473,7 +517,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
473 517
     #define FRONT_PROBE_BED_POSITION 20
474 518
     #define BACK_PROBE_BED_POSITION 170
475 519
 
476
-    #define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
520
+    #define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
477 521
 
478 522
     // Set the number of grid points per dimension.
479 523
     // You probably don't need more than 3 (squared=9).
@@ -481,25 +525,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
481 525
 
482 526
   #else  // !AUTO_BED_LEVELING_GRID
483 527
 
484
-      // Arbitrary points to probe.
485
-      // A simple cross-product is used to estimate the plane of the bed.
486
-      #define ABL_PROBE_PT_1_X 15
487
-      #define ABL_PROBE_PT_1_Y 180
488
-      #define ABL_PROBE_PT_2_X 15
489
-      #define ABL_PROBE_PT_2_Y 20
490
-      #define ABL_PROBE_PT_3_X 170
491
-      #define ABL_PROBE_PT_3_Y 20
528
+    // Arbitrary points to probe.
529
+    // A simple cross-product is used to estimate the plane of the bed.
530
+    #define ABL_PROBE_PT_1_X 15
531
+    #define ABL_PROBE_PT_1_Y 180
532
+    #define ABL_PROBE_PT_2_X 15
533
+    #define ABL_PROBE_PT_2_Y 20
534
+    #define ABL_PROBE_PT_3_X 170
535
+    #define ABL_PROBE_PT_3_Y 20
492 536
 
493 537
   #endif // AUTO_BED_LEVELING_GRID
494 538
 
495
-  // Offsets to the Z probe relative to the nozzle tip.
539
+  // Z Probe to nozzle (X,Y) offset, relative to (0, 0).
496 540
   // X and Y offsets must be integers.
497
-  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // Z probe to nozzle X offset: -left  +right
498
-  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Z probe to nozzle Y offset: -front +behind
499
-  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z probe to nozzle Z offset: -below (always!)
500
-
501
-  #define Z_RAISE_BEFORE_HOMING 4       // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
502
-                                        // Be sure you have this distance over your Z_MAX_POS in case.
541
+  //
542
+  // In the following example the X and Y offsets are both positive:
543
+  // #define X_PROBE_OFFSET_FROM_EXTRUDER 10
544
+  // #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
545
+  //
546
+  //    +-- BACK ---+
547
+  //    |           |
548
+  //  L |    (+) P  | R <-- probe (20,20)
549
+  //  E |           | I
550
+  //  F | (-) N (+) | G <-- nozzle (10,10)
551
+  //  T |           | H
552
+  //    |    (-)    | T
553
+  //    |           |
554
+  //    O-- FRONT --+
555
+  //  (0,0)
556
+  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // X offset: -left  [of the nozzle] +right
557
+  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Y offset: -front [of the nozzle] +behind
558
+  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z offset: -below [the nozzle] (always negative!)
503 559
 
504 560
   #define XY_TRAVEL_SPEED 8000         // X and Y axis travel speed between probes, in mm/min.
505 561
 
@@ -507,16 +563,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
507 563
   #define Z_RAISE_BETWEEN_PROBINGS 5  // How much the Z axis will be raised when traveling from between next probing points.
508 564
   #define Z_RAISE_AFTER_PROBING 15    // How much the Z axis will be raised after the last probing point.
509 565
 
510
-//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
511
-                                                                            // Useful to retract a deployable Z probe.
566
+  //#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
567
+                                                                             // Useful to retract a deployable Z probe.
568
+
569
+  // Probes are sensors/switches that need to be activated before they can be used
570
+  // and deactivated after the use.
571
+  // Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
572
+
573
+  // A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
574
+  // when the hardware endstops are active.
575
+  //#define FIX_MOUNTED_PROBE
576
+
577
+  // A Servo Probe can be defined in the servo section below.
512 578
 
513
-  //#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
579
+  // An Allen Key Probe is currently predefined only in the delta example configurations.
580
+
581
+  //#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
514 582
   //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
515 583
 
516
-// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
517
-// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
584
+  // If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
585
+  // it is highly recommended you leave Z_SAFE_HOMING enabled!
518 586
 
519
-  #define Z_SAFE_HOMING   // This feature is meant to avoid Z homing with Z probe outside the bed area.
587
+  #define Z_SAFE_HOMING   // Use the z-min-probe for homing to z-min - not the z-min-endstop.
588
+                          // This feature is meant to avoid Z homing with Z probe outside the bed area.
520 589
                           // When defined, it will:
521 590
                           // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
522 591
                           // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
@@ -530,37 +599,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
530 599
 
531 600
   #endif
532 601
 
533
-  // Support for a dedicated Z probe endstop separate from the Z min endstop.
534
-  // If you would like to use both a Z probe and a Z min endstop together,
535
-  // uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
536
-  // If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
537
-  // Example: To park the head outside the bed area when homing with G28.
538
-  //
539
-  // WARNING:
540
-  // The Z min endstop will need to set properly as it would without a Z probe
541
-  // to prevent head crashes and premature stopping during a print.
542
-  //
543
-  // To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
544
-  // defined in the pins_XXXXX.h file for your control board.
545
-  // If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
546
-  // Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
547
-  // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
548
-  // in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
549
-  // otherwise connect to ground and D32 for normally closed configuration
550
-  // and 5V and D32 for normally open configurations.
551
-  // Normally closed configuration is advised and assumed.
552
-  // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
553
-  // Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
554
-  // Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
555
-  // D32 is currently selected in the RAMPS 1.3/1.4 pin file.
556
-  // All other boards will need changes to the respective pins_XXXXX.h file.
557
-  //
558
-  // WARNING:
559
-  // Setting the wrong pin may have unexpected and potentially disastrous outcomes.
560
-  // Use with caution and do your homework.
561
-  //
562
-  //#define Z_MIN_PROBE_ENDSTOP
563
-
564 602
 #endif // AUTO_BED_LEVELING_FEATURE
565 603
 
566 604
 
@@ -591,7 +629,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
591 629
 
592 630
 #define DEFAULT_AXIS_STEPS_PER_UNIT   {400, 400, 400, 163}     // default steps per unit for ***** MakiBox A6 *****
593 631
 #define DEFAULT_MAX_FEEDRATE          {60, 60, 20, 45}         // (mm/sec)
594
-#define DEFAULT_MAX_ACCELERATION      {2000,2000,30,10000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot.
632
+#define DEFAULT_MAX_ACCELERATION      {2000,2000,30,10000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
595 633
 
596 634
 #define DEFAULT_ACCELERATION          3000    // X, Y, Z and E acceleration in mm/s^2 for printing moves
597 635
 #define DEFAULT_RETRACT_ACCELERATION  3000    // E acceleration in mm/s^2 for retracts
@@ -635,6 +673,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
635 673
 #endif
636 674
 
637 675
 //
676
+// Host Keepalive
677
+//
678
+// By default Marlin will send a busy status message to the host
679
+// every 2 seconds when it can't accept commands.
680
+//
681
+//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
682
+
683
+//
638 684
 // M100 Free Memory Watcher
639 685
 //
640 686
 //#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
@@ -654,13 +700,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
654 700
 // @section lcd
655 701
 
656 702
 // Define your display language below. Replace (en) with your language code and uncomment.
657
-// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
703
+// en, pl, fr, de, es, ru, bg, it, pt, pt_utf8, pt-br, pt-br_utf8, fi, an, nl, ca, eu, kana, kana_utf8, cn, cz, test
658 704
 // See also language.h
659 705
 //#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
660 706
 
661 707
 // Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
662 708
 // To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
663
-// See also documentation/LCDLanguageFont.md
709
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
664 710
   #define DISPLAY_CHARSET_HD44780_JAPAN        // this is the most common hardware
665 711
   //#define DISPLAY_CHARSET_HD44780_WESTERN
666 712
   //#define DISPLAY_CHARSET_HD44780_CYRILLIC
@@ -668,11 +714,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
668 714
 //#define ULTRA_LCD  //general LCD support, also 16x2
669 715
 //#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
670 716
 #define SDSUPPORT // Enable SD Card Support in Hardware Console
671
-#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
672
-//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
717
+                  // Changed behaviour! If you need SDSUPPORT uncomment it!
718
+#define SPI_SPEED SPI_HALF_SPEED // (also SPI_QUARTER_SPEED, SPI_EIGHTH_SPEED) Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
673 719
 //#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
674 720
 //#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
675 721
 //#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
722
+//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
676 723
 //#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
677 724
 //#define ULTIPANEL  //the UltiPanel as on Thingiverse
678 725
 //#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
@@ -689,13 +736,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
689 736
 
690 737
 // The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
691 738
 // http://panucatt.com
692
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
739
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
693 740
 //#define VIKI2
694 741
 //#define miniVIKI
695 742
 
696 743
 // This is a new controller currently under development.  https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
697 744
 //
698
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
745
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
699 746
 //#define ELB_FULL_GRAPHIC_CONTROLLER
700 747
 //#define SD_DETECT_INVERTED
701 748
 
@@ -710,7 +757,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
710 757
 // The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
711 758
 // http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
712 759
 //
713
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
760
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
714 761
 //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
715 762
 
716 763
 // The RepRapWorld REPRAPWORLD_KEYPAD v1.1
@@ -733,6 +780,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
733 780
 
734 781
 //#define LCD_I2C_SAINSMART_YWROBOT
735 782
 
783
+//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
784
+
736 785
 // PANELOLU2 LCD with status LEDs, separate encoder and click inputs
737 786
 //
738 787
 // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
@@ -746,7 +795,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
746 795
 //#define LCD_I2C_VIKI
747 796
 
748 797
 // SSD1306 OLED generic display support
749
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
798
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
750 799
 //#define U8GLIB_SSD1306
751 800
 
752 801
 // Shift register panels
@@ -758,7 +807,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
758 807
 
759 808
 // @section extras
760 809
 
761
-// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
810
+// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
762 811
 //#define FAST_PWM_FAN
763 812
 
764 813
 // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
@@ -840,19 +889,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
840 889
 // Uncomment below to enable
841 890
 //#define FILAMENT_SENSOR
842 891
 
843
-#define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
844
-#define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
845
-
846 892
 #define DEFAULT_NOMINAL_FILAMENT_DIA 3.00  //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
847
-#define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
848
-#define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
849
-#define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
850 893
 
851
-//defines used in the code
852
-#define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
894
+#if ENABLED(FILAMENT_SENSOR)
895
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
896
+  #define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
897
+
898
+  #define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
899
+  #define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
900
+  #define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
853 901
 
854
-//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
855
-//#define FILAMENT_LCD_DISPLAY
902
+  #define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
903
+
904
+  //When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
905
+  //#define FILAMENT_LCD_DISPLAY
906
+#endif
856 907
 
857 908
 #include "Configuration_adv.h"
858 909
 #include "thermistortables.h"

+ 88
- 62
Marlin/example_configurations/makibox/Configuration_adv.h Näytä tiedosto

@@ -17,6 +17,20 @@
17 17
 /**
18 18
  * Thermal Protection parameters
19 19
  */
20
+  /**
21
+   * Thermal Protection protects your printer from damage and fire if a
22
+   * thermistor falls out or temperature sensors fail in any way.
23
+   *
24
+   * The issue: If a thermistor falls out or a temperature sensor fails,
25
+   * Marlin can no longer sense the actual temperature. Since a disconnected
26
+   * thermistor reads as a low temperature, the firmware will keep the heater on.
27
+   *
28
+   * The solution: Once the temperature reaches the target, start observing.
29
+   * If the temperature stays too far below the target (hysteresis) for too long (period),
30
+   * the firmware will halt the machine as a safety precaution.
31
+   *
32
+   * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
33
+   */
20 34
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
21 35
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
22 36
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
@@ -26,26 +40,24 @@
26 40
    * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
27 41
    * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
28 42
    * but only if the current temperature is far enough below the target for a reliable test.
43
+   *
44
+   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
45
+   * WATCH_TEMP_INCREASE should not be below 2.
29 46
    */
30 47
   #define WATCH_TEMP_PERIOD 16                // Seconds
31 48
   #define WATCH_TEMP_INCREASE 4               // Degrees Celsius
32 49
 #endif
33 50
 
51
+  /**
52
+   * Thermal Protection parameters for the bed
53
+   * are like the above for the hotends.
54
+   * WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
55
+   */
34 56
 #if ENABLED(THERMAL_PROTECTION_BED)
35 57
   #define THERMAL_PROTECTION_BED_PERIOD 20    // Seconds
36 58
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
37 59
 #endif
38 60
 
39
-/**
40
- * Automatic Temperature:
41
- * The hotend target temperature is calculated by all the buffered lines of gcode.
42
- * The maximum buffered steps/sec of the extruder motor is called "se".
43
- * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
44
- * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
45
- * mintemp and maxtemp. Turn this off by excuting M109 without F*
46
- * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
47
- * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
48
- */
49 61
 #if ENABLED(PIDTEMP)
50 62
   // this adds an experimental additional term to the heating power, proportional to the extrusion speed.
51 63
   // if Kc is chosen well, the additional required power due to increased melting should be compensated.
@@ -56,14 +68,16 @@
56 68
   #endif
57 69
 #endif
58 70
 
59
-
60
-//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
61
-//The maximum buffered steps/sec of the extruder motor are called "se".
62
-//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
63
-// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
64
-// you exit the value by any M109 without F*
65
-// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
66
-// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
71
+/**
72
+ * Automatic Temperature:
73
+ * The hotend target temperature is calculated by all the buffered lines of gcode.
74
+ * The maximum buffered steps/sec of the extruder motor is called "se".
75
+ * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
76
+ * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
77
+ * mintemp and maxtemp. Turn this off by executing M109 without F*
78
+ * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
79
+ * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
80
+ */
67 81
 #define AUTOTEMP
68 82
 #if ENABLED(AUTOTEMP)
69 83
   #define AUTOTEMP_OLDWEIGHT 0.98
@@ -240,7 +254,13 @@
240 254
 #define INVERT_E_STEP_PIN false
241 255
 
242 256
 // Default stepper release if idle. Set to 0 to deactivate.
257
+// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
258
+// Time can be set by M18 and M84.
243 259
 #define DEFAULT_STEPPER_DEACTIVE_TIME 60
260
+#define DISABLE_INACTIVE_X true
261
+#define DISABLE_INACTIVE_Y true
262
+#define DISABLE_INACTIVE_Z true  // set to false if the nozzle will fall down on your printed part when print has finished.
263
+#define DISABLE_INACTIVE_E true
244 264
 
245 265
 #define DEFAULT_MINIMUMFEEDRATE       0.0     // minimum feedrate
246 266
 #define DEFAULT_MINTRAVELFEEDRATE     0.0
@@ -276,6 +296,9 @@
276 296
 // Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
277 297
 #define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
278 298
 
299
+// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
300
+//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
301
+
279 302
 // uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
280 303
 //#define DIGIPOT_I2C
281 304
 // Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
@@ -298,10 +321,11 @@
298 321
 
299 322
 #if ENABLED(SDSUPPORT)
300 323
 
301
-  // If you are using a RAMPS board or cheap E-bay purchased boards that do not detect when an SD card is inserted
302
-  // You can get round this by connecting a push button or single throw switch to the pin defined as SD_DETECT_PIN
303
-  // in the pins.h file.  When using a push button pulling the pin to ground this will need inverted.  This setting should
304
-  // be commented out otherwise
324
+  // Some RAMPS and other boards don't detect when an SD card is inserted. You can work
325
+  // around this by connecting a push button or single throw switch to the pin defined
326
+  // as SD_DETECT_PIN in your board's pins definitions.
327
+  // This setting should be disabled unless you are using a push button, pulling the pin to ground.
328
+  // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
305 329
   //#define SD_DETECT_INVERTED
306 330
 
307 331
   #define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
@@ -348,17 +372,16 @@
348 372
   //#define USE_SMALL_INFOFONT
349 373
 #endif // DOGLCD
350 374
 
351
-
352 375
 // @section more
353 376
 
354 377
 // The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
355
-//#define USE_WATCHDOG
378
+#define USE_WATCHDOG
356 379
 
357 380
 #if ENABLED(USE_WATCHDOG)
358
-// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
359
-// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
360
-//  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
361
-//#define WATCHDOG_RESET_MANUAL
381
+  // If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
382
+  // The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
383
+  //  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
384
+  //#define WATCHDOG_RESET_MANUAL
362 385
 #endif
363 386
 
364 387
 // @section lcd
@@ -369,6 +392,7 @@
369 392
 //#define BABYSTEPPING
370 393
 #if ENABLED(BABYSTEPPING)
371 394
   #define BABYSTEP_XY  //not only z, but also XY in the menu. more clutter, more functions
395
+                       //not implemented for deltabots!
372 396
   #define BABYSTEP_INVERT_Z false  //true for inverse movements in Z
373 397
   #define BABYSTEP_MULTIPLICATOR 1 //faster movements
374 398
 #endif
@@ -387,7 +411,6 @@
387 411
 #if ENABLED(ADVANCE)
388 412
   #define EXTRUDER_ADVANCE_K .0
389 413
   #define D_FILAMENT 2.85
390
-  #define STEPS_MM_E 836
391 414
 #endif
392 415
 
393 416
 // @section extras
@@ -396,7 +419,7 @@
396 419
 #define MM_PER_ARC_SEGMENT 1
397 420
 #define N_ARC_CORRECTION 25
398 421
 
399
-const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
422
+const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
400 423
 
401 424
 // @section temperature
402 425
 
@@ -461,12 +484,15 @@ const unsigned int dropsegments=5; //everything with less than this number of st
461 484
     #define FILAMENTCHANGE_ZADD 10
462 485
     #define FILAMENTCHANGE_FIRSTRETRACT -2
463 486
     #define FILAMENTCHANGE_FINALRETRACT -100
487
+    #define AUTO_FILAMENT_CHANGE                //This extrude filament until you press the button on LCD
488
+    #define AUTO_FILAMENT_CHANGE_LENGTH 0.04    //Extrusion length on automatic extrusion loop
489
+    #define AUTO_FILAMENT_CHANGE_FEEDRATE 300   //Extrusion feedrate (mm/min) on automatic extrusion loop
464 490
   #endif
465 491
 #endif
466 492
 
467 493
 /******************************************************************************\
468 494
  * enable this section if you have TMC26X motor drivers.
469
- * you need to import the TMC26XStepper library into the arduino IDE for this
495
+ * you need to import the TMC26XStepper library into the Arduino IDE for this
470 496
  ******************************************************************************/
471 497
 
472 498
 // @section tmc
@@ -474,52 +500,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
474 500
 //#define HAVE_TMCDRIVER
475 501
 #if ENABLED(HAVE_TMCDRIVER)
476 502
 
477
-//#define X_IS_TMC
503
+  //#define X_IS_TMC
478 504
   #define X_MAX_CURRENT 1000  //in mA
479 505
   #define X_SENSE_RESISTOR 91 //in mOhms
480 506
   #define X_MICROSTEPS 16     //number of microsteps
481 507
 
482
-//#define X2_IS_TMC
508
+  //#define X2_IS_TMC
483 509
   #define X2_MAX_CURRENT 1000  //in mA
484 510
   #define X2_SENSE_RESISTOR 91 //in mOhms
485 511
   #define X2_MICROSTEPS 16     //number of microsteps
486 512
 
487
-//#define Y_IS_TMC
513
+  //#define Y_IS_TMC
488 514
   #define Y_MAX_CURRENT 1000  //in mA
489 515
   #define Y_SENSE_RESISTOR 91 //in mOhms
490 516
   #define Y_MICROSTEPS 16     //number of microsteps
491 517
 
492
-//#define Y2_IS_TMC
518
+  //#define Y2_IS_TMC
493 519
   #define Y2_MAX_CURRENT 1000  //in mA
494 520
   #define Y2_SENSE_RESISTOR 91 //in mOhms
495 521
   #define Y2_MICROSTEPS 16     //number of microsteps
496 522
 
497
-//#define Z_IS_TMC
523
+  //#define Z_IS_TMC
498 524
   #define Z_MAX_CURRENT 1000  //in mA
499 525
   #define Z_SENSE_RESISTOR 91 //in mOhms
500 526
   #define Z_MICROSTEPS 16     //number of microsteps
501 527
 
502
-//#define Z2_IS_TMC
528
+  //#define Z2_IS_TMC
503 529
   #define Z2_MAX_CURRENT 1000  //in mA
504 530
   #define Z2_SENSE_RESISTOR 91 //in mOhms
505 531
   #define Z2_MICROSTEPS 16     //number of microsteps
506 532
 
507
-//#define E0_IS_TMC
533
+  //#define E0_IS_TMC
508 534
   #define E0_MAX_CURRENT 1000  //in mA
509 535
   #define E0_SENSE_RESISTOR 91 //in mOhms
510 536
   #define E0_MICROSTEPS 16     //number of microsteps
511 537
 
512
-//#define E1_IS_TMC
538
+  //#define E1_IS_TMC
513 539
   #define E1_MAX_CURRENT 1000  //in mA
514 540
   #define E1_SENSE_RESISTOR 91 //in mOhms
515 541
   #define E1_MICROSTEPS 16     //number of microsteps
516 542
 
517
-//#define E2_IS_TMC
543
+  //#define E2_IS_TMC
518 544
   #define E2_MAX_CURRENT 1000  //in mA
519 545
   #define E2_SENSE_RESISTOR 91 //in mOhms
520 546
   #define E2_MICROSTEPS 16     //number of microsteps
521 547
 
522
-//#define E3_IS_TMC
548
+  //#define E3_IS_TMC
523 549
   #define E3_MAX_CURRENT 1000  //in mA
524 550
   #define E3_SENSE_RESISTOR 91 //in mOhms
525 551
   #define E3_MICROSTEPS 16     //number of microsteps
@@ -528,7 +554,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
528 554
 
529 555
 /******************************************************************************\
530 556
  * enable this section if you have L6470  motor drivers.
531
- * you need to import the L6470 library into the arduino IDE for this
557
+ * you need to import the L6470 library into the Arduino IDE for this
532 558
  ******************************************************************************/
533 559
 
534 560
 // @section l6470
@@ -536,63 +562,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
536 562
 //#define HAVE_L6470DRIVER
537 563
 #if ENABLED(HAVE_L6470DRIVER)
538 564
 
539
-//#define X_IS_L6470
565
+  //#define X_IS_L6470
540 566
   #define X_MICROSTEPS 16     //number of microsteps
541
-  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
567
+  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
542 568
   #define X_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
543 569
   #define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
544 570
 
545
-//#define X2_IS_L6470
571
+  //#define X2_IS_L6470
546 572
   #define X2_MICROSTEPS 16     //number of microsteps
547
-  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
573
+  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
548 574
   #define X2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
549 575
   #define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
550 576
 
551
-//#define Y_IS_L6470
577
+  //#define Y_IS_L6470
552 578
   #define Y_MICROSTEPS 16     //number of microsteps
553
-  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
579
+  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
554 580
   #define Y_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
555 581
   #define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
556 582
 
557
-//#define Y2_IS_L6470
583
+  //#define Y2_IS_L6470
558 584
   #define Y2_MICROSTEPS 16     //number of microsteps
559
-  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
585
+  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
560 586
   #define Y2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
561 587
   #define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
562 588
 
563
-//#define Z_IS_L6470
589
+  //#define Z_IS_L6470
564 590
   #define Z_MICROSTEPS 16     //number of microsteps
565
-  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
591
+  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
566 592
   #define Z_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
567 593
   #define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
568 594
 
569
-//#define Z2_IS_L6470
595
+  //#define Z2_IS_L6470
570 596
   #define Z2_MICROSTEPS 16     //number of microsteps
571
-  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
597
+  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
572 598
   #define Z2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
573 599
   #define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
574 600
 
575
-//#define E0_IS_L6470
601
+  //#define E0_IS_L6470
576 602
   #define E0_MICROSTEPS 16     //number of microsteps
577
-  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
603
+  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
578 604
   #define E0_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
579 605
   #define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
580 606
 
581
-//#define E1_IS_L6470
607
+  //#define E1_IS_L6470
582 608
   #define E1_MICROSTEPS 16     //number of microsteps
583
-  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
609
+  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
584 610
   #define E1_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
585 611
   #define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
586 612
 
587
-//#define E2_IS_L6470
613
+  //#define E2_IS_L6470
588 614
   #define E2_MICROSTEPS 16     //number of microsteps
589
-  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
615
+  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
590 616
   #define E2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
591 617
   #define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
592 618
 
593
-//#define E3_IS_L6470
619
+  //#define E3_IS_L6470
594 620
   #define E3_MICROSTEPS 16     //number of microsteps
595
-  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
621
+  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
596 622
   #define E3_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
597 623
   #define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
598 624
 

+ 152
- 103
Marlin/example_configurations/tvrrug/Round2/Configuration.h Näytä tiedosto

@@ -110,6 +110,7 @@ Here are some standard links for getting your machine calibrated:
110 110
 //--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
111 111
 //
112 112
 //// Temperature sensor settings:
113
+// -3 is thermocouple with MAX31855 (only for sensor 0)
113 114
 // -2 is thermocouple with MAX6675 (only for sensor 0)
114 115
 // -1 is thermocouple with AD595
115 116
 // 0 is not used
@@ -129,6 +130,7 @@ Here are some standard links for getting your machine calibrated:
129 130
 // 13 is 100k Hisens 3950  1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
130 131
 // 20 is the PT100 circuit found in the Ultimainboard V2.x
131 132
 // 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
133
+// 70 is the 100K thermistor found in the bq Hephestos 2
132 134
 //
133 135
 //    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
134 136
 //                          (but gives greater accuracy and more stable PID)
@@ -144,7 +146,7 @@ Here are some standard links for getting your machine calibrated:
144 146
 //     Use it for Testing or Development purposes. NEVER for production machine.
145 147
 //#define DUMMY_THERMISTOR_998_VALUE 25
146 148
 //#define DUMMY_THERMISTOR_999_VALUE 100
147
-// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
149
+// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-J01", '8': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9': "100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10': "100k / 4.7k RS 198-961", '11': "100k / 4.7k beta 3950 1%", '12': "100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13': "100k Hisens 3950  1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-3': "Thermocouple + MAX31855 (only for sensor 0)", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
148 150
 #define TEMP_SENSOR_0 5
149 151
 #define TEMP_SENSOR_1 0
150 152
 #define TEMP_SENSOR_2 0
@@ -178,14 +180,9 @@ Here are some standard links for getting your machine calibrated:
178 180
 #define HEATER_3_MAXTEMP 275
179 181
 #define BED_MAXTEMP 150
180 182
 
181
-// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
182
-// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
183
-// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
184
-//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
185
-
186 183
 // If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
187
-//#define EXTRUDER_WATTS (12.0*12.0/6.7) //  P=I^2/R
188
-//#define BED_WATTS (12.0*12.0/1.1)      // P=I^2/R
184
+//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
185
+//#define BED_WATTS (12.0*12.0/1.1)      // P=U^2/R
189 186
 
190 187
 //===========================================================================
191 188
 //============================= PID Settings ================================
@@ -243,13 +240,13 @@ Here are some standard links for getting your machine calibrated:
243 240
 
244 241
   #define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
245 242
 
246
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
243
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
247 244
   //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
248 245
   #define  DEFAULT_bedKp 10.00
249 246
   #define  DEFAULT_bedKi .023
250 247
   #define  DEFAULT_bedKd 305.4
251 248
 
252
-  //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
249
+  //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
253 250
   //from pidautotune
254 251
   //#define  DEFAULT_bedKp 97.1
255 252
   //#define  DEFAULT_bedKi 1.41
@@ -274,16 +271,15 @@ Here are some standard links for getting your machine calibrated:
274 271
 //===========================================================================
275 272
 
276 273
 /**
277
- * Thermal Runaway Protection protects your printer from damage and fire if a
274
+ * Thermal Protection protects your printer from damage and fire if a
278 275
  * thermistor falls out or temperature sensors fail in any way.
279 276
  *
280 277
  * The issue: If a thermistor falls out or a temperature sensor fails,
281 278
  * Marlin can no longer sense the actual temperature. Since a disconnected
282 279
  * thermistor reads as a low temperature, the firmware will keep the heater on.
283 280
  *
284
- * The solution: Once the temperature reaches the target, start observing.
285
- * If the temperature stays too far below the target (hysteresis) for too long,
286
- * the firmware will halt as a safety precaution.
281
+ * If you get "Thermal Runaway" or "Heating failed" errors the
282
+ * details can be tuned in Configuration_adv.h
287 283
  */
288 284
 
289 285
 #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
@@ -331,10 +327,52 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
331 327
 //#define DISABLE_MAX_ENDSTOPS
332 328
 //#define DISABLE_MIN_ENDSTOPS
333 329
 
334
-// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
335
-// This only affects a Z probe endstop if you have separate Z min endstop as well and have
336
-// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
337
-// this has no effect.
330
+//===========================================================================
331
+//============================= Z Probe Options =============================
332
+//===========================================================================
333
+
334
+// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
335
+// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
336
+//
337
+// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
338
+//
339
+// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
340
+// Example: To park the head outside the bed area when homing with G28.
341
+//
342
+// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
343
+//
344
+// For a servo-based Z probe, you must set up servo support below, including
345
+// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
346
+//
347
+// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
348
+// - Use 5V for powered (usu. inductive) sensors.
349
+// - Otherwise connect:
350
+//   - normally-closed switches to GND and D32.
351
+//   - normally-open switches to 5V and D32.
352
+//
353
+// Normally-closed switches are advised and are the default.
354
+//
355
+// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
356
+// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
357
+// default pin for all RAMPS-based boards. Some other boards map differently.
358
+// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
359
+//
360
+// WARNING:
361
+// Setting the wrong pin may have unexpected and potentially disastrous consequences.
362
+// Use with caution and do your homework.
363
+//
364
+//#define Z_MIN_PROBE_ENDSTOP
365
+
366
+// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
367
+// The Z_MIN_PIN will then be used for both Z-homing and probing.
368
+#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
369
+
370
+// To use a probe you must enable one of the two options above!
371
+
372
+// This option disables the use of the Z_MIN_PROBE_PIN
373
+// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
374
+// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
375
+// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
338 376
 //#define DISABLE_Z_MIN_PROBE_ENDSTOP
339 377
 
340 378
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
@@ -344,11 +382,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
344 382
 #define Z_ENABLE_ON 1
345 383
 #define E_ENABLE_ON 1 // For all extruders
346 384
 
347
-// Disables axis when it's not being used.
385
+// Disables axis stepper immediately when it's not being used.
348 386
 // WARNING: When motors turn off there is a chance of losing position accuracy!
349 387
 #define DISABLE_X false
350 388
 #define DISABLE_Y false
351 389
 #define DISABLE_Z false
390
+// Warn on display about possibly reduced accuracy
391
+//#define DISABLE_REDUCED_ACCURACY_WARNING
352 392
 
353 393
 // @section extruder
354 394
 
@@ -371,6 +411,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
371 411
 #define INVERT_E3_DIR false
372 412
 
373 413
 // @section homing
414
+//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
415
+                                    // Be sure you have this distance over your Z_MAX_POS in case.
374 416
 
375 417
 // ENDSTOP SETTINGS:
376 418
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
@@ -406,24 +448,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
406 448
 #endif
407 449
 
408 450
 //===========================================================================
409
-//=========================== Manual Bed Leveling ===========================
451
+//============================ Mesh Bed Leveling ============================
410 452
 //===========================================================================
411 453
 
412
-//#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
413 454
 //#define MESH_BED_LEVELING    // Enable mesh bed leveling.
414 455
 
415
-#if ENABLED(MANUAL_BED_LEVELING)
416
-  #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
417
-#endif  // MANUAL_BED_LEVELING
418
-
419 456
 #if ENABLED(MESH_BED_LEVELING)
420 457
   #define MESH_MIN_X 10
421
-  #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
458
+  #define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
422 459
   #define MESH_MIN_Y 10
423
-  #define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
460
+  #define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
424 461
   #define MESH_NUM_X_POINTS 3  // Don't use more than 7 points per axis, implementation limited.
425 462
   #define MESH_NUM_Y_POINTS 3
426 463
   #define MESH_HOME_SEARCH_Z 4  // Z after Home, bed somewhere below but above 0.0.
464
+
465
+  //#define MANUAL_BED_LEVELING  // Add display menu option for bed leveling.
466
+
467
+  #if ENABLED(MANUAL_BED_LEVELING)
468
+    #define MBL_Z_STEP 0.025  // Step size while manually probing Z axis.
469
+  #endif  // MANUAL_BED_LEVELING
470
+
427 471
 #endif  // MESH_BED_LEVELING
428 472
 
429 473
 //===========================================================================
@@ -432,10 +476,9 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
432 476
 
433 477
 // @section bedlevel
434 478
 
435
-
436 479
 //#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
437 480
 //#define DEBUG_LEVELING_FEATURE
438
-#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
481
+#define Z_MIN_PROBE_REPEATABILITY_TEST  // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
439 482
 
440 483
 #if ENABLED(AUTO_BED_LEVELING_FEATURE)
441 484
 
@@ -447,7 +490,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
447 490
   //   This mode is preferred because there are more measurements.
448 491
   //
449 492
   // - "3-point" mode
450
-  //   Probe 3 arbitrary points on the bed (that aren't colinear)
493
+  //   Probe 3 arbitrary points on the bed (that aren't collinear)
451 494
   //   You specify the XY coordinates of all 3 points.
452 495
 
453 496
   // Enable this to sample the bed in a grid (least squares solution).
@@ -461,7 +504,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
461 504
     #define FRONT_PROBE_BED_POSITION 20
462 505
     #define BACK_PROBE_BED_POSITION 170
463 506
 
464
-    #define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
507
+    #define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
465 508
 
466 509
     // Set the number of grid points per dimension.
467 510
     // You probably don't need more than 3 (squared=9).
@@ -469,25 +512,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
469 512
 
470 513
   #else  // !AUTO_BED_LEVELING_GRID
471 514
 
472
-      // Arbitrary points to probe.
473
-      // A simple cross-product is used to estimate the plane of the bed.
474
-      #define ABL_PROBE_PT_1_X 15
475
-      #define ABL_PROBE_PT_1_Y 180
476
-      #define ABL_PROBE_PT_2_X 15
477
-      #define ABL_PROBE_PT_2_Y 20
478
-      #define ABL_PROBE_PT_3_X 170
479
-      #define ABL_PROBE_PT_3_Y 20
515
+    // Arbitrary points to probe.
516
+    // A simple cross-product is used to estimate the plane of the bed.
517
+    #define ABL_PROBE_PT_1_X 15
518
+    #define ABL_PROBE_PT_1_Y 180
519
+    #define ABL_PROBE_PT_2_X 15
520
+    #define ABL_PROBE_PT_2_Y 20
521
+    #define ABL_PROBE_PT_3_X 170
522
+    #define ABL_PROBE_PT_3_Y 20
480 523
 
481 524
   #endif // AUTO_BED_LEVELING_GRID
482 525
 
483
-  // Offsets to the Z probe relative to the nozzle tip.
526
+  // Z Probe to nozzle (X,Y) offset, relative to (0, 0).
484 527
   // X and Y offsets must be integers.
485
-  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // Z probe to nozzle X offset: -left  +right
486
-  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Z probe to nozzle Y offset: -front +behind
487
-  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z probe to nozzle Z offset: -below (always!)
488
-
489
-  #define Z_RAISE_BEFORE_HOMING 4       // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
490
-                                        // Be sure you have this distance over your Z_MAX_POS in case.
528
+  //
529
+  // In the following example the X and Y offsets are both positive:
530
+  // #define X_PROBE_OFFSET_FROM_EXTRUDER 10
531
+  // #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
532
+  //
533
+  //    +-- BACK ---+
534
+  //    |           |
535
+  //  L |    (+) P  | R <-- probe (20,20)
536
+  //  E |           | I
537
+  //  F | (-) N (+) | G <-- nozzle (10,10)
538
+  //  T |           | H
539
+  //    |    (-)    | T
540
+  //    |           |
541
+  //    O-- FRONT --+
542
+  //  (0,0)
543
+  #define X_PROBE_OFFSET_FROM_EXTRUDER -25     // X offset: -left  [of the nozzle] +right
544
+  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29     // Y offset: -front [of the nozzle] +behind
545
+  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35  // Z offset: -below [the nozzle] (always negative!)
491 546
 
492 547
   #define XY_TRAVEL_SPEED 8000         // X and Y axis travel speed between probes, in mm/min.
493 548
 
@@ -495,16 +550,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
495 550
   #define Z_RAISE_BETWEEN_PROBINGS 5  // How much the Z axis will be raised when traveling from between next probing points.
496 551
   #define Z_RAISE_AFTER_PROBING 15    // How much the Z axis will be raised after the last probing point.
497 552
 
498
-//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
499
-                                                                            // Useful to retract a deployable Z probe.
553
+  //#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
554
+                                                                             // Useful to retract a deployable Z probe.
555
+
556
+  // Probes are sensors/switches that need to be activated before they can be used
557
+  // and deactivated after the use.
558
+  // Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
559
+
560
+  // A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
561
+  // when the hardware endstops are active.
562
+  //#define FIX_MOUNTED_PROBE
563
+
564
+  // A Servo Probe can be defined in the servo section below.
500 565
 
501
-  //#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
566
+  // An Allen Key Probe is currently predefined only in the delta example configurations.
567
+
568
+  //#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
502 569
   //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
503 570
 
504
-// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
505
-// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
571
+  // If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
572
+  // it is highly recommended you leave Z_SAFE_HOMING enabled!
506 573
 
507
-  #define Z_SAFE_HOMING   // This feature is meant to avoid Z homing with Z probe outside the bed area.
574
+  #define Z_SAFE_HOMING   // Use the z-min-probe for homing to z-min - not the z-min-endstop.
575
+                          // This feature is meant to avoid Z homing with Z probe outside the bed area.
508 576
                           // When defined, it will:
509 577
                           // - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
510 578
                           // - If stepper drivers timeout, it will need X and Y homing again before Z homing.
@@ -518,37 +586,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
518 586
 
519 587
   #endif
520 588
 
521
-  // Support for a dedicated Z probe endstop separate from the Z min endstop.
522
-  // If you would like to use both a Z probe and a Z min endstop together,
523
-  // uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
524
-  // If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
525
-  // Example: To park the head outside the bed area when homing with G28.
526
-  //
527
-  // WARNING:
528
-  // The Z min endstop will need to set properly as it would without a Z probe
529
-  // to prevent head crashes and premature stopping during a print.
530
-  //
531
-  // To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
532
-  // defined in the pins_XXXXX.h file for your control board.
533
-  // If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
534
-  // Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
535
-  // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
536
-  // in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
537
-  // otherwise connect to ground and D32 for normally closed configuration
538
-  // and 5V and D32 for normally open configurations.
539
-  // Normally closed configuration is advised and assumed.
540
-  // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
541
-  // Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
542
-  // Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
543
-  // D32 is currently selected in the RAMPS 1.3/1.4 pin file.
544
-  // All other boards will need changes to the respective pins_XXXXX.h file.
545
-  //
546
-  // WARNING:
547
-  // Setting the wrong pin may have unexpected and potentially disastrous outcomes.
548
-  // Use with caution and do your homework.
549
-  //
550
-  //#define Z_MIN_PROBE_ENDSTOP
551
-
552 589
 #endif // AUTO_BED_LEVELING_FEATURE
553 590
 
554 591
 
@@ -627,6 +664,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
627 664
 #endif
628 665
 
629 666
 //
667
+// Host Keepalive
668
+//
669
+// By default Marlin will send a busy status message to the host
670
+// every 2 seconds when it can't accept commands.
671
+//
672
+//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
673
+
674
+//
630 675
 // M100 Free Memory Watcher
631 676
 //
632 677
 //#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
@@ -646,13 +691,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
646 691
 // @section lcd
647 692
 
648 693
 // Define your display language below. Replace (en) with your language code and uncomment.
649
-// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
694
+// en, pl, fr, de, es, ru, bg, it, pt, pt_utf8, pt-br, pt-br_utf8, fi, an, nl, ca, eu, kana, kana_utf8, cn, cz, test
650 695
 // See also language.h
651 696
 //#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
652 697
 
653 698
 // Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
654 699
 // To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
655
-// See also documentation/LCDLanguageFont.md
700
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
656 701
   #define DISPLAY_CHARSET_HD44780_JAPAN        // this is the most common hardware
657 702
   //#define DISPLAY_CHARSET_HD44780_WESTERN
658 703
   //#define DISPLAY_CHARSET_HD44780_CYRILLIC
@@ -660,12 +705,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
660 705
 //#define ULTRA_LCD  //general LCD support, also 16x2
661 706
 //#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
662 707
 //#define SDSUPPORT // Enable SD Card Support in Hardware Console
663
-// Changed behaviour! If you need SDSUPPORT uncomment it!
664
-//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
665
-//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
708
+                    // Changed behaviour! If you need SDSUPPORT uncomment it!
709
+//#define SPI_SPEED SPI_HALF_SPEED // (also SPI_QUARTER_SPEED, SPI_EIGHTH_SPEED) Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
666 710
 //#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
667 711
 //#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
668 712
 //#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
713
+//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
669 714
 //#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
670 715
 //#define ULTIPANEL  //the UltiPanel as on Thingiverse
671 716
 //#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
@@ -682,13 +727,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
682 727
 
683 728
 // The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
684 729
 // http://panucatt.com
685
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
730
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
686 731
 //#define VIKI2
687 732
 //#define miniVIKI
688 733
 
689 734
 // This is a new controller currently under development.  https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
690 735
 //
691
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
736
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
692 737
 //#define ELB_FULL_GRAPHIC_CONTROLLER
693 738
 //#define SD_DETECT_INVERTED
694 739
 
@@ -703,7 +748,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
703 748
 // The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
704 749
 // http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
705 750
 //
706
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
751
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
707 752
 //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
708 753
 
709 754
 // The RepRapWorld REPRAPWORLD_KEYPAD v1.1
@@ -726,6 +771,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
726 771
 
727 772
 //#define LCD_I2C_SAINSMART_YWROBOT
728 773
 
774
+//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
775
+
729 776
 // PANELOLU2 LCD with status LEDs, separate encoder and click inputs
730 777
 //
731 778
 // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
@@ -739,7 +786,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
739 786
 //#define LCD_I2C_VIKI
740 787
 
741 788
 // SSD1306 OLED generic display support
742
-// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
789
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
743 790
 //#define U8GLIB_SSD1306
744 791
 
745 792
 // Shift register panels
@@ -751,7 +798,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
751 798
 
752 799
 // @section extras
753 800
 
754
-// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
801
+// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
755 802
 //#define FAST_PWM_FAN
756 803
 
757 804
 // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
@@ -833,19 +880,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
833 880
 // Uncomment below to enable
834 881
 //#define FILAMENT_SENSOR
835 882
 
836
-#define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
837
-#define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
838
-
839 883
 #define DEFAULT_NOMINAL_FILAMENT_DIA 3.00  //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
840
-#define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
841
-#define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
842
-#define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
843 884
 
844
-//defines used in the code
845
-#define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
885
+#if ENABLED(FILAMENT_SENSOR)
886
+  #define FILAMENT_SENSOR_EXTRUDER_NUM 0   //The number of the extruder that has the filament sensor (0,1,2)
887
+  #define MEASUREMENT_DELAY_CM        14   //measurement delay in cm.  This is the distance from filament sensor to middle of barrel
888
+
889
+  #define MEASURED_UPPER_LIMIT         3.30  //upper limit factor used for sensor reading validation in mm
890
+  #define MEASURED_LOWER_LIMIT         1.90  //lower limit factor for sensor reading validation in mm
891
+  #define MAX_MEASUREMENT_DELAY       20     //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM  and lower number saves RAM)
846 892
 
847
-//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
848
-//#define FILAMENT_LCD_DISPLAY
893
+  #define DEFAULT_MEASURED_FILAMENT_DIA  DEFAULT_NOMINAL_FILAMENT_DIA  //set measured to nominal initially
894
+
895
+  //When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status.  Status will appear for 5 sec.
896
+  //#define FILAMENT_LCD_DISPLAY
897
+#endif
849 898
 
850 899
 #include "Configuration_adv.h"
851 900
 #include "thermistortables.h"

+ 83
- 58
Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h Näytä tiedosto

@@ -17,6 +17,20 @@
17 17
 /**
18 18
  * Thermal Protection parameters
19 19
  */
20
+  /**
21
+   * Thermal Protection protects your printer from damage and fire if a
22
+   * thermistor falls out or temperature sensors fail in any way.
23
+   *
24
+   * The issue: If a thermistor falls out or a temperature sensor fails,
25
+   * Marlin can no longer sense the actual temperature. Since a disconnected
26
+   * thermistor reads as a low temperature, the firmware will keep the heater on.
27
+   *
28
+   * The solution: Once the temperature reaches the target, start observing.
29
+   * If the temperature stays too far below the target (hysteresis) for too long (period),
30
+   * the firmware will halt the machine as a safety precaution.
31
+   *
32
+   * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
33
+   */
20 34
 #if ENABLED(THERMAL_PROTECTION_HOTENDS)
21 35
   #define THERMAL_PROTECTION_PERIOD 40        // Seconds
22 36
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
@@ -26,26 +40,24 @@
26 40
    * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
27 41
    * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
28 42
    * but only if the current temperature is far enough below the target for a reliable test.
43
+   *
44
+   * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
45
+   * WATCH_TEMP_INCREASE should not be below 2.
29 46
    */
30 47
   #define WATCH_TEMP_PERIOD 16                // Seconds
31 48
   #define WATCH_TEMP_INCREASE 4               // Degrees Celsius
32 49
 #endif
33 50
 
51
+  /**
52
+   * Thermal Protection parameters for the bed
53
+   * are like the above for the hotends.
54
+   * WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
55
+   */
34 56
 #if ENABLED(THERMAL_PROTECTION_BED)
35 57
   #define THERMAL_PROTECTION_BED_PERIOD 20    // Seconds
36 58
   #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
37 59
 #endif
38 60
 
39
-/**
40
- * Automatic Temperature:
41
- * The hotend target temperature is calculated by all the buffered lines of gcode.
42
- * The maximum buffered steps/sec of the extruder motor is called "se".
43
- * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
44
- * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
45
- * mintemp and maxtemp. Turn this off by excuting M109 without F*
46
- * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
47
- * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
48
- */
49 61
 #if ENABLED(PIDTEMP)
50 62
   // this adds an experimental additional term to the heating power, proportional to the extrusion speed.
51 63
   // if Kc is chosen well, the additional required power due to increased melting should be compensated.
@@ -56,14 +68,16 @@
56 68
   #endif
57 69
 #endif
58 70
 
59
-
60
-//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
61
-//The maximum buffered steps/sec of the extruder motor are called "se".
62
-//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
63
-// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
64
-// you exit the value by any M109 without F*
65
-// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
66
-// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
71
+/**
72
+ * Automatic Temperature:
73
+ * The hotend target temperature is calculated by all the buffered lines of gcode.
74
+ * The maximum buffered steps/sec of the extruder motor is called "se".
75
+ * Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
76
+ * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
77
+ * mintemp and maxtemp. Turn this off by executing M109 without F*
78
+ * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
79
+ * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
80
+ */
67 81
 #define AUTOTEMP
68 82
 #if ENABLED(AUTOTEMP)
69 83
   #define AUTOTEMP_OLDWEIGHT 0.98
@@ -240,7 +254,13 @@
240 254
 #define INVERT_E_STEP_PIN false
241 255
 
242 256
 // Default stepper release if idle. Set to 0 to deactivate.
257
+// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
258
+// Time can be set by M18 and M84.
243 259
 #define DEFAULT_STEPPER_DEACTIVE_TIME 60
260
+#define DISABLE_INACTIVE_X true
261
+#define DISABLE_INACTIVE_Y true
262
+#define DISABLE_INACTIVE_Z true  // set to false if the nozzle will fall down on your printed part when print has finished.
263
+#define DISABLE_INACTIVE_E true
244 264
 
245 265
 #define DEFAULT_MINIMUMFEEDRATE       0.0     // minimum feedrate
246 266
 #define DEFAULT_MINTRAVELFEEDRATE     0.0
@@ -276,6 +296,9 @@
276 296
 // Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
277 297
 #define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
278 298
 
299
+// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
300
+//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
301
+
279 302
 // uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
280 303
 //#define DIGIPOT_I2C
281 304
 // Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
@@ -349,17 +372,16 @@
349 372
   //#define USE_SMALL_INFOFONT
350 373
 #endif // DOGLCD
351 374
 
352
-
353 375
 // @section more
354 376
 
355 377
 // The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
356
-//#define USE_WATCHDOG
378
+#define USE_WATCHDOG
357 379
 
358 380
 #if ENABLED(USE_WATCHDOG)
359
-// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
360
-// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
361
-//  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
362
-//#define WATCHDOG_RESET_MANUAL
381
+  // If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
382
+  // The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
383
+  //  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
384
+  //#define WATCHDOG_RESET_MANUAL
363 385
 #endif
364 386
 
365 387
 // @section lcd
@@ -370,6 +392,7 @@
370 392
 //#define BABYSTEPPING
371 393
 #if ENABLED(BABYSTEPPING)
372 394
   #define BABYSTEP_XY  //not only z, but also XY in the menu. more clutter, more functions
395
+                       //not implemented for deltabots!
373 396
   #define BABYSTEP_INVERT_Z false  //true for inverse movements in Z
374 397
   #define BABYSTEP_MULTIPLICATOR 1 //faster movements
375 398
 #endif
@@ -388,7 +411,6 @@
388 411
 #if ENABLED(ADVANCE)
389 412
   #define EXTRUDER_ADVANCE_K .0
390 413
   #define D_FILAMENT 2.85
391
-  #define STEPS_MM_E 836
392 414
 #endif
393 415
 
394 416
 // @section extras
@@ -397,7 +419,7 @@
397 419
 #define MM_PER_ARC_SEGMENT 1
398 420
 #define N_ARC_CORRECTION 25
399 421
 
400
-const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
422
+const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
401 423
 
402 424
 // @section temperature
403 425
 
@@ -462,12 +484,15 @@ const unsigned int dropsegments=5; //everything with less than this number of st
462 484
     #define FILAMENTCHANGE_ZADD 10
463 485
     #define FILAMENTCHANGE_FIRSTRETRACT -2
464 486
     #define FILAMENTCHANGE_FINALRETRACT -100
487
+    #define AUTO_FILAMENT_CHANGE                //This extrude filament until you press the button on LCD
488
+    #define AUTO_FILAMENT_CHANGE_LENGTH 0.04    //Extrusion length on automatic extrusion loop
489
+    #define AUTO_FILAMENT_CHANGE_FEEDRATE 300   //Extrusion feedrate (mm/min) on automatic extrusion loop
465 490
   #endif
466 491
 #endif
467 492
 
468 493
 /******************************************************************************\
469 494
  * enable this section if you have TMC26X motor drivers.
470
- * you need to import the TMC26XStepper library into the arduino IDE for this
495
+ * you need to import the TMC26XStepper library into the Arduino IDE for this
471 496
  ******************************************************************************/
472 497
 
473 498
 // @section tmc
@@ -475,52 +500,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
475 500
 //#define HAVE_TMCDRIVER
476 501
 #if ENABLED(HAVE_TMCDRIVER)
477 502
 
478
-//#define X_IS_TMC
503
+  //#define X_IS_TMC
479 504
   #define X_MAX_CURRENT 1000  //in mA
480 505
   #define X_SENSE_RESISTOR 91 //in mOhms
481 506
   #define X_MICROSTEPS 16     //number of microsteps
482 507
 
483
-//#define X2_IS_TMC
508
+  //#define X2_IS_TMC
484 509
   #define X2_MAX_CURRENT 1000  //in mA
485 510
   #define X2_SENSE_RESISTOR 91 //in mOhms
486 511
   #define X2_MICROSTEPS 16     //number of microsteps
487 512
 
488
-//#define Y_IS_TMC
513
+  //#define Y_IS_TMC
489 514
   #define Y_MAX_CURRENT 1000  //in mA
490 515
   #define Y_SENSE_RESISTOR 91 //in mOhms
491 516
   #define Y_MICROSTEPS 16     //number of microsteps
492 517
 
493
-//#define Y2_IS_TMC
518
+  //#define Y2_IS_TMC
494 519
   #define Y2_MAX_CURRENT 1000  //in mA
495 520
   #define Y2_SENSE_RESISTOR 91 //in mOhms
496 521
   #define Y2_MICROSTEPS 16     //number of microsteps
497 522
 
498
-//#define Z_IS_TMC
523
+  //#define Z_IS_TMC
499 524
   #define Z_MAX_CURRENT 1000  //in mA
500 525
   #define Z_SENSE_RESISTOR 91 //in mOhms
501 526
   #define Z_MICROSTEPS 16     //number of microsteps
502 527
 
503
-//#define Z2_IS_TMC
528
+  //#define Z2_IS_TMC
504 529
   #define Z2_MAX_CURRENT 1000  //in mA
505 530
   #define Z2_SENSE_RESISTOR 91 //in mOhms
506 531
   #define Z2_MICROSTEPS 16     //number of microsteps
507 532
 
508
-//#define E0_IS_TMC
533
+  //#define E0_IS_TMC
509 534
   #define E0_MAX_CURRENT 1000  //in mA
510 535
   #define E0_SENSE_RESISTOR 91 //in mOhms
511 536
   #define E0_MICROSTEPS 16     //number of microsteps
512 537
 
513
-//#define E1_IS_TMC
538
+  //#define E1_IS_TMC
514 539
   #define E1_MAX_CURRENT 1000  //in mA
515 540
   #define E1_SENSE_RESISTOR 91 //in mOhms
516 541
   #define E1_MICROSTEPS 16     //number of microsteps
517 542
 
518
-//#define E2_IS_TMC
543
+  //#define E2_IS_TMC
519 544
   #define E2_MAX_CURRENT 1000  //in mA
520 545
   #define E2_SENSE_RESISTOR 91 //in mOhms
521 546
   #define E2_MICROSTEPS 16     //number of microsteps
522 547
 
523
-//#define E3_IS_TMC
548
+  //#define E3_IS_TMC
524 549
   #define E3_MAX_CURRENT 1000  //in mA
525 550
   #define E3_SENSE_RESISTOR 91 //in mOhms
526 551
   #define E3_MICROSTEPS 16     //number of microsteps
@@ -529,7 +554,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
529 554
 
530 555
 /******************************************************************************\
531 556
  * enable this section if you have L6470  motor drivers.
532
- * you need to import the L6470 library into the arduino IDE for this
557
+ * you need to import the L6470 library into the Arduino IDE for this
533 558
  ******************************************************************************/
534 559
 
535 560
 // @section l6470
@@ -537,63 +562,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
537 562
 //#define HAVE_L6470DRIVER
538 563
 #if ENABLED(HAVE_L6470DRIVER)
539 564
 
540
-//#define X_IS_L6470
565
+  //#define X_IS_L6470
541 566
   #define X_MICROSTEPS 16     //number of microsteps
542
-  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
567
+  #define X_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
543 568
   #define X_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
544 569
   #define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
545 570
 
546
-//#define X2_IS_L6470
571
+  //#define X2_IS_L6470
547 572
   #define X2_MICROSTEPS 16     //number of microsteps
548
-  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
573
+  #define X2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
549 574
   #define X2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
550 575
   #define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
551 576
 
552
-//#define Y_IS_L6470
577
+  //#define Y_IS_L6470
553 578
   #define Y_MICROSTEPS 16     //number of microsteps
554
-  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
579
+  #define Y_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
555 580
   #define Y_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
556 581
   #define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
557 582
 
558
-//#define Y2_IS_L6470
583
+  //#define Y2_IS_L6470
559 584
   #define Y2_MICROSTEPS 16     //number of microsteps
560
-  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
585
+  #define Y2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
561 586
   #define Y2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
562 587
   #define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
563 588
 
564
-//#define Z_IS_L6470
589
+  //#define Z_IS_L6470
565 590
   #define Z_MICROSTEPS 16     //number of microsteps
566
-  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
591
+  #define Z_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
567 592
   #define Z_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
568 593
   #define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
569 594
 
570
-//#define Z2_IS_L6470
595
+  //#define Z2_IS_L6470
571 596
   #define Z2_MICROSTEPS 16     //number of microsteps
572
-  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
597
+  #define Z2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
573 598
   #define Z2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
574 599
   #define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
575 600
 
576
-//#define E0_IS_L6470
601
+  //#define E0_IS_L6470
577 602
   #define E0_MICROSTEPS 16     //number of microsteps
578
-  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
603
+  #define E0_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
579 604
   #define E0_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
580 605
   #define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
581 606
 
582
-//#define E1_IS_L6470
607
+  //#define E1_IS_L6470
583 608
   #define E1_MICROSTEPS 16     //number of microsteps
584
-  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
609
+  #define E1_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
585 610
   #define E1_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
586 611
   #define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
587 612
 
588
-//#define E2_IS_L6470
613
+  //#define E2_IS_L6470
589 614
   #define E2_MICROSTEPS 16     //number of microsteps
590
-  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
615
+  #define E2_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
591 616
   #define E2_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
592 617
   #define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
593 618
 
594
-//#define E3_IS_L6470
619
+  //#define E3_IS_L6470
595 620
   #define E3_MICROSTEPS 16     //number of microsteps
596
-  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be carefull not to go too high
621
+  #define E3_K_VAL 50          // 0 - 255, Higher values, are higher power. Be careful not to go too high
597 622
   #define E3_OVERCURRENT 2000  //maxc current in mA. If the current goes over this value, the driver will switch off
598 623
   #define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
599 624
 

+ 47
- 44
Marlin/language.h Näytä tiedosto

@@ -3,37 +3,38 @@
3 3
 
4 4
 #include "Configuration.h"
5 5
 
6
-#define LANGUAGE_CONCAT(M)       #M
7
-#define GENERATE_LANGUAGE_INCLUDE(M)  LANGUAGE_CONCAT(language_##M.h)
6
+#define GENERATE_LANGUAGE_INCLUDE(M)  STRINGIFY_(language_##M.h)
8 7
 
9 8
 
10 9
 // NOTE: IF YOU CHANGE LANGUAGE FILES OR MERGE A FILE WITH CHANGES
11 10
 //
12 11
 //   ==> ALWAYS TRY TO COMPILE MARLIN WITH/WITHOUT "ULTIPANEL" / "ULTRALCD" / "SDSUPPORT" #define IN "Configuration.h"
13 12
 //   ==> ALSO TRY ALL AVAILABLE LANGUAGE OPTIONS
14
-// See also documentation/LCDLanguageFont.md
13
+// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
15 14
 
16 15
 // Languages
17
-// en       English
18
-// pl       Polish
19
-// fr       French
20
-// de       German
21
-// es       Spanish
22
-// ru       Russian
23
-// bg       Bulgarian
24
-// it       Italian
25
-// pt       Portuguese
26
-// pt-br    Portuguese (Brazil)
27
-// fi       Finnish
28
-// an       Aragonese
29
-// nl       Dutch
30
-// gl       Galician
31
-// ca       Catalan
32
-// eu       Basque-Euskera
33
-// kana     Japanese
34
-// kana_utf Japanese
35
-// cn       Chinese
36
-// cz       Czech
16
+// en         English
17
+// pl         Polish
18
+// fr         French
19
+// de         German
20
+// es         Spanish
21
+// ru         Russian
22
+// bg         Bulgarian
23
+// it         Italian
24
+// pt         Portuguese
25
+// pt_utf8    Portuguese (UTF8)
26
+// pt-br      Portuguese (Brazilian)
27
+// pt-br_utf8 Portuguese (Brazilian UTF8)
28
+// fi         Finnish
29
+// an         Aragonese
30
+// nl         Dutch
31
+// gl         Galician
32
+// ca         Catalan
33
+// eu         Basque-Euskera
34
+// kana       Japanese
35
+// kana_utf8  Japanese (UTF8)
36
+// cn         Chinese
37
+// cz         Czech
37 38
 
38 39
 // fallback if no language is set, don't change
39 40
 #ifndef LANGUAGE_INCLUDE
@@ -49,47 +50,45 @@
49 50
 #define PROTOCOL_VERSION "1.0"
50 51
 
51 52
 #if MB(ULTIMAKER)|| MB(ULTIMAKER_OLD)|| MB(ULTIMAIN_2)
52
-  #define MACHINE_NAME "Ultimaker"
53
-  #define SOURCE_CODE_URL "https://github.com/Ultimaker/Marlin"
53
+  #define DEFAULT_MACHINE_NAME "Ultimaker"
54
+  #define DEFAULT_SOURCE_URL "https://github.com/Ultimaker/Marlin"
54 55
 #elif MB(RUMBA)
55
-  #define MACHINE_NAME "Rumba"
56
+  #define DEFAULT_MACHINE_NAME "Rumba"
56 57
 #elif MB(3DRAG)
57
-  #define MACHINE_NAME "3Drag"
58
-  #define SOURCE_CODE_URL "http://3dprint.elettronicain.it/"
58
+  #define DEFAULT_MACHINE_NAME "3Drag"
59
+  #define DEFAULT_SOURCE_URL "http://3dprint.elettronicain.it/"
59 60
 #elif MB(K8200)
60
-  #define MACHINE_NAME "K8200"
61
-  #define SOURCE_CODE_URL "https://github.com/CONSULitAS/Marlin-K8200"
61
+  #define DEFAULT_MACHINE_NAME "K8200"
62
+  #define DEFAULT_SOURCE_URL "https://github.com/CONSULitAS/Marlin-K8200"
62 63
 #elif MB(5DPRINT)
63
-  #define MACHINE_NAME "Makibox"
64
+  #define DEFAULT_MACHINE_NAME "Makibox"
64 65
 #elif MB(SAV_MKI)
65
-  #define MACHINE_NAME "SAV MkI"
66
-  #define SOURCE_CODE_URL "https://github.com/fmalpartida/Marlin/tree/SAV-MkI-config"
67
-#elif !defined(MACHINE_NAME)
68
-  #define MACHINE_NAME "3D Printer"
66
+  #define DEFAULT_MACHINE_NAME "SAV MkI"
67
+  #define DEFAULT_SOURCE_URL "https://github.com/fmalpartida/Marlin/tree/SAV-MkI-config"
68
+#else
69
+  #define DEFAULT_MACHINE_NAME "3D Printer"
70
+  #define DEFAULT_SOURCE_URL "https://github.com/MarlinFirmware/Marlin"
69 71
 #endif
70 72
 
71 73
 #ifdef CUSTOM_MACHINE_NAME
72
-  #undef MACHINE_NAME
73 74
   #define MACHINE_NAME CUSTOM_MACHINE_NAME
75
+#else
76
+  #define MACHINE_NAME DEFAULT_MACHINE_NAME
74 77
 #endif
75 78
 
76 79
 #ifndef SOURCE_CODE_URL
77
-  #define SOURCE_CODE_URL "https://github.com/MarlinFirmware/Marlin"
80
+  #define SOURCE_CODE_URL DEFAULT_SOURCE_URL
78 81
 #endif
79 82
 
80 83
 #ifndef DETAILED_BUILD_VERSION
81 84
   #error BUILD_VERSION Information must be specified
82 85
 #endif
83 86
 
84
-#ifndef UUID
85
-  #define UUID "00000000-0000-0000-0000-000000000000"
87
+#ifndef MACHINE_UUID
88
+  #define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
86 89
 #endif
87 90
 
88 91
 
89
-#define STRINGIFY_(n) #n
90
-#define STRINGIFY(n) STRINGIFY_(n)
91
-
92
-
93 92
 // Common LCD messages
94 93
 
95 94
   /* nothing here yet */
@@ -122,10 +121,14 @@
122 121
 #define MSG_INVALID_EXTRUDER                "Invalid extruder"
123 122
 #define MSG_INVALID_SOLENOID                "Invalid solenoid"
124 123
 #define MSG_ERR_NO_THERMISTORS              "No thermistors - no temperature"
125
-#define MSG_M115_REPORT                     "FIRMWARE_NAME:Marlin " DETAILED_BUILD_VERSION " SOURCE_CODE_URL:" SOURCE_CODE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" UUID "\n"
124
+#define MSG_M115_REPORT                     "FIRMWARE_NAME:Marlin " DETAILED_BUILD_VERSION " SOURCE_CODE_URL:" SOURCE_CODE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
126 125
 #define MSG_COUNT_X                         " Count X: "
126
+#define MSG_COUNT_A                         " Count A: "
127 127
 #define MSG_ERR_KILLED                      "Printer halted. kill() called!"
128 128
 #define MSG_ERR_STOPPED                     "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
129
+#define MSG_BUSY_PROCESSING                 "busy: processing"
130
+#define MSG_BUSY_PAUSED_FOR_USER            "busy: paused for user"
131
+#define MSG_BUSY_PAUSED_FOR_INPUT           "busy: paused for input"
129 132
 #define MSG_RESEND                          "Resend: "
130 133
 #define MSG_UNKNOWN_COMMAND                 "Unknown command: \""
131 134
 #define MSG_ACTIVE_EXTRUDER                 "Active Extruder: "

+ 2
- 1
Marlin/language_an.h Näytä tiedosto

@@ -2,7 +2,7 @@
2 2
  * Aragonese
3 3
  *
4 4
  * LCD Menu Messages
5
- * See also documentation/LCDLanguageFont.md
5
+ * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
6 6
  *
7 7
  */
8 8
 #ifndef LANGUAGE_AN_H
@@ -20,6 +20,7 @@
20 20
 #define MSG_AUTOSTART                       " Autostart"
21 21
 #define MSG_DISABLE_STEPPERS                "Amortar motors"
22 22
 #define MSG_AUTO_HOME                       "Levar a l'orichen"
23
+#define MSG_LEVEL_BED_HOMING                "Homing"
23 24
 #define MSG_SET_HOME_OFFSETS                "Set home offsets"
24 25
 #define MSG_SET_ORIGIN                      "Establir zero"
25 26
 #define MSG_PREHEAT_PLA                     "Precalentar PLA"

+ 2
- 1
Marlin/language_bg.h Näytä tiedosto

@@ -2,7 +2,7 @@
2 2
  * Bulgarian
3 3
  *
4 4
  * LCD Menu Messages
5
- * See also documentation/LCDLanguageFont.md
5
+ * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
6 6
  *
7 7
  */
8 8
 #ifndef LANGUAGE_BG_H
@@ -20,6 +20,7 @@
20 20
 #define MSG_AUTOSTART                       "Автостарт"
21 21
 #define MSG_DISABLE_STEPPERS                "Изкл. двигатели"
22 22
 #define MSG_AUTO_HOME                       "Паркиране"
23
+#define MSG_LEVEL_BED_HOMING                "Homing"
23 24
 #define MSG_SET_HOME_OFFSETS                "Задай Начало"
24 25
 #define MSG_SET_ORIGIN                      "Изходна точка"
25 26
 #define MSG_PREHEAT_PLA                     "Подгряване PLA"

+ 2
- 1
Marlin/language_ca.h Näytä tiedosto

@@ -2,7 +2,7 @@
2 2
  * Catalan
3 3
  *
4 4
  * LCD Menu Messages
5
- * See also documentation/LCDLanguageFont.md
5
+ * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
6 6
  *
7 7
  */
8 8
 #ifndef LANGUAGE_CA_H
@@ -21,6 +21,7 @@
21 21
 #define MSG_AUTOSTART                       "Inici automatic"
22 22
 #define MSG_DISABLE_STEPPERS                "Apagar motors"
23 23
 #define MSG_AUTO_HOME                       "Home global"
24
+#define MSG_LEVEL_BED_HOMING                "Homing"
24 25
 #define MSG_SET_HOME_OFFSETS                "Set home offsets"
25 26
 #define MSG_SET_ORIGIN                      "Establir origen"
26 27
 #define MSG_PREHEAT_PLA                     "Preescalfar PLA"

+ 3
- 2
Marlin/language_cn.h Näytä tiedosto

@@ -2,13 +2,13 @@
2 2
  * Chinese
3 3
  *
4 4
  * LCD Menu Messages
5
- * Se also documentation/LCDLanguageFont.md
5
+ * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
6 6
  *
7 7
  */
8 8
 #ifndef LANGUAGE_CN_H
9 9
 #define LANGUAGE_CN_H
10 10
 
11
-#define MAPPER_NON         // For direct asci codes
11
+#define MAPPER_NON         // For direct ascii codes
12 12
 #define DISPLAY_CHARSET_ISO10646_CN
13 13
 
14 14
 #define WELCOME_MSG                         "\xa4\xa5\xa6\xa7"
@@ -18,6 +18,7 @@
18 18
 #define MSG_AUTOSTART                       "\xb1\xb2\xb3\xb4"
19 19
 #define MSG_DISABLE_STEPPERS                "\xb5\xb6\xb7\xb8\xb9\xba"
20 20
 #define MSG_AUTO_HOME                       "\xbb\xbc\xbd"
21
+#define MSG_LEVEL_BED_HOMING                "Homing"
21 22
 #define MSG_SET_HOME_OFFSETS                "\xbe\xbf\xbb\xbc\xbd\xc0\xc1"
22 23
 #define MSG_SET_ORIGIN                      "\xbe\xbf\xbc\xbd"
23 24
 #define MSG_PREHEAT_PLA                     "\xc3\xc4 PLA"

+ 2
- 1
Marlin/language_cz.h Näytä tiedosto

@@ -2,7 +2,7 @@
2 2
  * Czech
3 3
  *
4 4
  * LCD Menu Messages
5
- * See also documentation/LCDLanguageFont.md
5
+ * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
6 6
  *
7 7
  * Translated by Petr Zahradnik, Computer Laboratory
8 8
  * Blog and video blog Zahradnik se bavi
@@ -24,6 +24,7 @@
24 24
 #define MSG_AUTOSTART                       "Autostart"
25 25
 #define MSG_DISABLE_STEPPERS                "Uvolnit motory"
26 26
 #define MSG_AUTO_HOME                       "Domovska pozice"
27
+#define MSG_LEVEL_BED_HOMING                "Mereni podlozky"
27 28
 #define MSG_SET_HOME_OFFSETS                "Nastavit ofsety"
28 29
 #define MSG_SET_ORIGIN                      "Nastavit pocatek"
29 30
 #define MSG_PREHEAT_PLA                     "Zahrat PLA"

+ 2
- 1
Marlin/language_da.h Näytä tiedosto

@@ -2,7 +2,7 @@
2 2
  * Danish
3 3
  *
4 4
  * LCD Menu Messages
5
- * See also documentation/LCDLanguageFont.md
5
+ * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
6 6
  *
7 7
  */
8 8
 #ifndef LANGUAGE_DA_H
@@ -21,6 +21,7 @@
21 21
 #define MSG_AUTO_HOME                       "Home" // G28
22 22
 #define MSG_COOLDOWN                        "Afkøl"
23 23
 #define MSG_DISABLE_STEPPERS                "Slå stepper fra"
24
+#define MSG_LEVEL_BED_HOMING                "Homing"
24 25
 #define MSG_SET_HOME_OFFSETS                "Sæt home offsets"
25 26
 #define MSG_SET_ORIGIN                      "Sæt origin"
26 27
 #define MSG_SWITCH_PS_ON                    "Slå strøm til"

+ 2
- 1
Marlin/language_de.h Näytä tiedosto

@@ -2,7 +2,7 @@
2 2
  * German
3 3
  *
4 4
  * LCD Menu Messages
5
- * See also documentation/LCDLanguageFont.md
5
+ * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
6 6
  *
7 7
  */
8 8
 #ifndef LANGUAGE_DE_H
@@ -20,6 +20,7 @@
20 20
 #define MSG_AUTOSTART                       "Autostart"
21 21
 #define MSG_DISABLE_STEPPERS                "Motoren Aus" // M84
22 22
 #define MSG_AUTO_HOME                       "Home" // G28
23
+#define MSG_LEVEL_BED_HOMING                "Homing"
23 24
 #define MSG_SET_HOME_OFFSETS                "Setze Home hier"
24 25
 #define MSG_SET_ORIGIN                      "Setze Null hier" //"G92 X0 Y0 Z0" commented out in ultralcd.cpp
25 26
 #define MSG_PREHEAT_PLA                     "Vorwärmen PLA"

+ 5
- 2
Marlin/language_en.h Näytä tiedosto

@@ -2,14 +2,14 @@
2 2
  * English
3 3
  *
4 4
  * LCD Menu Messages
5
- * Se also documentation/LCDLanguageFont.md
5
+ * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
6 6
  *
7 7
  */
8 8
 #ifndef LANGUAGE_EN_H
9 9
 #define LANGUAGE_EN_H
10 10
 
11 11
 #if DISABLED(MAPPER_NON) && DISABLED(MAPPER_C2C3) && DISABLED(MAPPER_D0D1) && DISABLED(MAPPER_D0D1_MOD) && DISABLED(MAPPER_E382E383)
12
-  #define MAPPER_NON         // For direct asci codes
12
+  #define MAPPER_NON         // For direct ascii codes
13 13
 #endif
14 14
 
15 15
 //#define SIMULATE_ROMFONT //Comment in to see what is seen on the character based displays
@@ -39,6 +39,9 @@
39 39
 #ifndef MSG_AUTO_HOME
40 40
   #define MSG_AUTO_HOME                       "Auto home"
41 41
 #endif
42
+#ifndef MSG_LEVEL_BED_HOMING
43
+  #define MSG_LEVEL_BED_HOMING                "Homing"
44
+#endif
42 45
 #ifndef MSG_SET_HOME_OFFSETS
43 46
   #define MSG_SET_HOME_OFFSETS                "Set home offsets"
44 47
 #endif

+ 3
- 1
Marlin/language_es.h Näytä tiedosto

@@ -2,7 +2,7 @@
2 2
  * Spanish
3 3
  *
4 4
  * LCD Menu Messages
5
- * See also documentation/LCDLanguageFont.md
5
+ * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
6 6
  *
7 7
  */
8 8
 #ifndef LANGUAGE_ES_H
@@ -20,6 +20,7 @@
20 20
 #define MSG_AUTOSTART                       "Autostart"
21 21
 #define MSG_DISABLE_STEPPERS                "Apagar motores"
22 22
 #define MSG_AUTO_HOME                       "Llevar al origen"
23
+#define MSG_LEVEL_BED_HOMING                "Homing"
23 24
 #define MSG_SET_HOME_OFFSETS                "Ajustar offsets"
24 25
 #define MSG_SET_ORIGIN                      "Establecer cero"
25 26
 #define MSG_PREHEAT_PLA                     "Precalentar PLA"
@@ -38,6 +39,7 @@
38 39
 #define MSG_EXTRUDE                         "Extruir"
39 40
 #define MSG_RETRACT                         "Retraer"
40 41
 #define MSG_MOVE_AXIS                       "Mover ejes"
42
+#define MSG_LEVEL_BED                       "Nivelar cama"
41 43
 #define MSG_MOVE_X                          "Mover X"
42 44
 #define MSG_MOVE_Y                          "Mover Y"
43 45
 #define MSG_MOVE_Z                          "Mover Z"

+ 2
- 1
Marlin/language_eu.h Näytä tiedosto

@@ -2,7 +2,7 @@
2 2
  * Basque-Euskera
3 3
  *
4 4
  * LCD Menu Messages
5
- * See also documentation/LCDLanguageFont.md
5
+ * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
6 6
  *
7 7
  */
8 8
 #ifndef LANGUAGE_EU_H
@@ -20,6 +20,7 @@
20 20
 #define MSG_AUTOSTART                       "Auto hasiera"
21 21
 #define MSG_DISABLE_STEPPERS                "Itzali motoreak"
22 22
 #define MSG_AUTO_HOME                       "Hasierara joan"
23
+#define MSG_LEVEL_BED_HOMING                "Homing"
23 24
 #define MSG_SET_HOME_OFFSETS                "Set home offsets"
24 25
 #define MSG_SET_ORIGIN                      "Hasiera ipini"
25 26
 #define MSG_PREHEAT_PLA                     "Aurreberotu PLA"

+ 2
- 1
Marlin/language_fi.h Näytä tiedosto

@@ -2,7 +2,7 @@
2 2
  * Finnish
3 3
  *
4 4
  * LCD Menu Messages
5
- * See also documentation/LCDLanguageFont.md
5
+ * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
6 6
  *
7 7
  */
8 8
 #ifndef LANGUAGE_FI_H
@@ -20,6 +20,7 @@
20 20
 #define MSG_AUTOSTART                       "Automaatti"
21 21
 #define MSG_DISABLE_STEPPERS                "Vapauta moottorit"
22 22
 #define MSG_AUTO_HOME                       "Aja referenssiin"
23
+#define MSG_LEVEL_BED_HOMING                "Homing"
23 24
 #define MSG_SET_HOME_OFFSETS                "Set home offsets"
24 25
 #define MSG_SET_ORIGIN                      "Aseta origo"
25 26
 #define MSG_PREHEAT_PLA                     "Esilämmitä PLA"

+ 2
- 1
Marlin/language_fr.h Näytä tiedosto

@@ -2,7 +2,7 @@
2 2
  * French
3 3
  *
4 4
  * LCD Menu Messages
5
- * See also documentation/LCDLanguageFont.md
5
+ * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
6 6
  *
7 7
  */
8 8
 #ifndef LANGUAGE_FR_H
@@ -21,6 +21,7 @@
21 21
 #define MSG_AUTOSTART                       "Demarrage auto"
22 22
 #define MSG_DISABLE_STEPPERS                "Arreter moteurs"
23 23
 #define MSG_AUTO_HOME                       "Home auto."
24
+#define MSG_LEVEL_BED_HOMING                "Homing"
24 25
 #define MSG_SET_HOME_OFFSETS                "Set home offsets"
25 26
 #define MSG_SET_ORIGIN                      "Regler origine"
26 27
 #define MSG_PREHEAT_PLA                     "Prechauffage PLA"

+ 1
- 1
Marlin/language_gl.h Näytä tiedosto

@@ -2,7 +2,7 @@
2 2
  * Galician language (ISO "gl")
3 3
  *
4 4
  * LCD Menu Messages
5
- * Se also documentation/LCDLanguageFont.md
5
+ * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
6 6
  *
7 7
  */
8 8
 #ifndef LANGUAGE_GL_H

+ 3
- 1
Marlin/language_it.h Näytä tiedosto

@@ -2,7 +2,7 @@
2 2
  * Italian
3 3
  *
4 4
  * LCD Menu Messages
5
- * See also documentation/LCDLanguageFont.md
5
+ * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
6 6
  *
7 7
  */
8 8
 #ifndef LANGUAGE_IT_H
@@ -20,6 +20,7 @@
20 20
 #define MSG_AUTOSTART                       "Autostart"
21 21
 #define MSG_DISABLE_STEPPERS                "Disabilita Motori"
22 22
 #define MSG_AUTO_HOME                       "Auto Home"
23
+#define MSG_LEVEL_BED_HOMING                "Homing"
23 24
 #define MSG_SET_HOME_OFFSETS                "Setta offset home"
24 25
 #define MSG_SET_ORIGIN                      "Imposta Origine"
25 26
 #define MSG_PREHEAT_PLA                     "Preriscalda PLA"
@@ -38,6 +39,7 @@
38 39
 #define MSG_EXTRUDE                         "Estrudi"
39 40
 #define MSG_RETRACT                         "Ritrai"
40 41
 #define MSG_MOVE_AXIS                       "Muovi Asse"
42
+#define MSG_LEVEL_BED                       "Livellamento piano"
41 43
 #define MSG_MOVE_X                          "Muovi X"
42 44
 #define MSG_MOVE_Y                          "Muovi Y"
43 45
 #define MSG_MOVE_Z                          "Muovi Z"

+ 0
- 0
Marlin/language_kana.h Näytä tiedosto


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

Loading…
Peruuta
Tallenna